From 49d82d6ac11bbbea142544fcf497fa12115d8f0f Mon Sep 17 00:00:00 2001 From: Vehicle Researcher Date: Fri, 2 Oct 2020 01:45:44 +0000 Subject: [PATCH 01/22] openpilot v0.7.9 release --- CONTRIBUTING.md | 4 +- Jenkinsfile | 10 +- README.md | 57 +- RELEASES.md | 8 + SConstruct | 71 +- cereal/car.capnp | 21 +- cereal/log.capnp | 82 +- cereal/messaging/__init__.py | 67 +- cereal/messaging/impl_msgq.cc | 17 +- cereal/messaging/messaging.hpp | 29 +- cereal/messaging/messaging_pyx_setup.py | 5 +- cereal/messaging/msgq.cc | 25 +- cereal/messaging/socketmaster.cc | 9 +- cereal/service_list.yaml | 2 + common/android.py | 286 ---- common/basedir.py | 10 +- common/gpio.py | 22 + common/hardware.py | 57 + common/hardware_android.py | 302 ++++ common/hardware_base.py | 41 + common/hardware_tici.py | 58 + common/params.py | 22 +- common/realtime.py | 45 +- common/text_window.py | 2 +- launch_chffrplus.sh | 107 +- opendbc/can/common_pyx_setup.py | 2 +- opendbc/can/packer_pyx.pyx | 8 +- opendbc/can/parser.cc | 2 +- opendbc/can/parser.py | 4 +- opendbc/can/parser_pyx.pyx | 10 +- opendbc/can/process_dbc.py | 4 +- opendbc/chrysler_pacifica_2017_hybrid.dbc | 2 +- opendbc/gm_global_a_object.dbc | 2 +- opendbc/lexus_ct200h_2018_pt_generated.dbc | 2 +- opendbc/lexus_is_2018_pt_generated.dbc | 2 +- opendbc/lexus_nx300h_2018_pt_generated.dbc | 2 +- opendbc/lexus_rx_350_2016_pt_generated.dbc | 2 +- opendbc/lexus_rx_hybrid_2017_pt_generated.dbc | 2 +- opendbc/toyota_avalon_2017_pt_generated.dbc | 2 +- .../toyota_camry_hybrid_2018_pt_generated.dbc | 2 +- opendbc/toyota_corolla_2017_pt_generated.dbc | 4 +- .../toyota_highlander_2017_pt_generated.dbc | 2 +- ...ta_highlander_hybrid_2018_pt_generated.dbc | 2 +- opendbc/toyota_nodsu_hybrid_pt_generated.dbc | 2 +- opendbc/toyota_nodsu_pt_generated.dbc | 2 +- opendbc/toyota_prius_2017_pt_generated.dbc | 2 +- opendbc/toyota_rav4_2017_pt_generated.dbc | 2 +- .../toyota_rav4_hybrid_2017_pt_generated.dbc | 2 +- .../toyota_sienna_xle_2018_pt_generated.dbc | 2 +- panda/__init__.py | 2 +- panda/board/board.h | 15 +- panda/board/board_declarations.h | 26 +- panda/board/boards/black.h | 46 +- panda/board/boards/common.h | 6 +- panda/board/boards/dos.h | 50 +- panda/board/boards/grey.h | 22 +- panda/board/boards/pedal.h | 36 +- panda/board/boards/uno.h | 44 +- panda/board/boards/white.h | 50 +- panda/board/drivers/clock_source.h | 100 ++ panda/board/drivers/uart.h | 16 +- panda/board/faults.h | 42 +- panda/board/gpio.h | 8 +- panda/board/main.c | 173 ++- panda/board/main_declarations.h | 1 + panda/board/power_saving.h | 6 +- panda/board/safety/safety_hyundai.h | 2 +- panda/board/spi_flasher.h | 2 +- panda/certs/debugesp | 15 - panda/certs/debugesp.pub | 1 - panda/certs/releaseesp.pub | 1 - panda/python/__init__.py | 15 +- panda/python/dfu.py | 2 +- panda/python/esptool.py | 1317 ----------------- panda/python/flash_release.py | 42 +- rednose/helpers/__init__.py | 4 +- .../assets/offroad/circled-checkmark.png | Bin 0 -> 2236 bytes selfdrive/assets/offroad/icon_app_store.png | Bin 0 -> 12277 bytes selfdrive/assets/offroad/icon_calibration.png | Bin 0 -> 8910 bytes selfdrive/assets/offroad/icon_checkmark.png | Bin 0 -> 4471 bytes .../assets/offroad/icon_chevron_right.png | Bin 0 -> 1420 bytes selfdrive/assets/offroad/icon_connect_app.png | Bin 0 -> 24265 bytes selfdrive/assets/offroad/icon_eon.png | Bin 0 -> 8624 bytes selfdrive/assets/offroad/icon_map.png | Bin 0 -> 28235 bytes selfdrive/assets/offroad/icon_map_speed.png | Bin 0 -> 29822 bytes selfdrive/assets/offroad/icon_menu.png | Bin 0 -> 635 bytes selfdrive/assets/offroad/icon_metric.png | Bin 0 -> 604 bytes selfdrive/assets/offroad/icon_minus.png | Bin 0 -> 2577 bytes selfdrive/assets/offroad/icon_monitoring.png | Bin 0 -> 58679 bytes selfdrive/assets/offroad/icon_network.png | Bin 0 -> 39872 bytes selfdrive/assets/offroad/icon_openpilot.png | Bin 0 -> 42640 bytes .../offroad/icon_openpilot_mirrored.png | Bin 0 -> 18150 bytes selfdrive/assets/offroad/icon_play_store.png | Bin 0 -> 14623 bytes selfdrive/assets/offroad/icon_plus.png | Bin 0 -> 2833 bytes selfdrive/assets/offroad/icon_road.png | Bin 0 -> 6674 bytes selfdrive/assets/offroad/icon_settings.png | Bin 0 -> 13369 bytes selfdrive/assets/offroad/icon_shell.png | Bin 0 -> 42462 bytes selfdrive/assets/offroad/icon_speed_limit.png | Bin 0 -> 3321 bytes selfdrive/assets/offroad/icon_user.png | Bin 0 -> 15798 bytes selfdrive/assets/offroad/icon_warning.png | Bin 0 -> 8002 bytes .../assets/offroad/illustration_arrow.png | Bin 0 -> 1265 bytes .../offroad/illustration_sim_absent.png | Bin 0 -> 6608 bytes .../offroad/illustration_sim_present.png | Bin 0 -> 6331 bytes .../offroad/illustration_training_lane_01.png | Bin 0 -> 268080 bytes .../offroad/illustration_training_lane_02.png | Bin 0 -> 69907 bytes .../offroad/illustration_training_lead_01.png | Bin 0 -> 1515 bytes .../offroad/illustration_training_lead_02.png | Bin 0 -> 2054 bytes selfdrive/assets/offroad/indicator_wifi_0.png | Bin 0 -> 3038 bytes .../assets/offroad/indicator_wifi_100.png | Bin 0 -> 3270 bytes .../assets/offroad/indicator_wifi_25.png | Bin 0 -> 3087 bytes .../assets/offroad/indicator_wifi_50.png | Bin 0 -> 3121 bytes .../assets/offroad/indicator_wifi_75.png | Bin 0 -> 3186 bytes selfdrive/athena/athenad.py | 20 +- selfdrive/boardd/SConscript | 2 +- selfdrive/boardd/boardd.cc | 192 +-- selfdrive/boardd/can_list_to_can_capnp.cc | 26 +- selfdrive/boardd/panda.cc | 37 +- selfdrive/boardd/panda.h | 3 + selfdrive/boardd/pigeon.cc | 226 +++ selfdrive/boardd/pigeon.h | 43 + selfdrive/camerad/SConscript | 6 +- .../camerad/cameras/camera_frame_stream.cc | 10 +- .../camerad/cameras/camera_frame_stream.h | 12 +- selfdrive/camerad/cameras/camera_qcom.cc | 22 +- selfdrive/camerad/cameras/camera_qcom.h | 29 +- selfdrive/camerad/cameras/debayer.cl | 14 - selfdrive/camerad/main.cc | 481 +++++- .../camerad/transforms/rgb_to_yuv_test.cc | 9 +- selfdrive/car/honda/carcontroller.py | 33 +- selfdrive/car/honda/carstate.py | 10 +- selfdrive/car/honda/hondacan.py | 112 +- selfdrive/car/honda/interface.py | 2 +- selfdrive/car/honda/values.py | 13 + selfdrive/car/hyundai/carcontroller.py | 9 +- selfdrive/car/hyundai/carstate.py | 5 +- selfdrive/car/hyundai/interface.py | 2 +- selfdrive/car/hyundai/values.py | 16 +- selfdrive/car/mazda/carstate.py | 6 +- selfdrive/car/mazda/interface.py | 28 +- selfdrive/car/mazda/mazdacan.py | 6 +- selfdrive/car/mazda/values.py | 25 +- selfdrive/car/mock/interface.py | 4 +- selfdrive/car/toyota/interface.py | 2 +- selfdrive/car/toyota/values.py | 29 + selfdrive/clocksd/SConscript | 2 +- selfdrive/clocksd/clocksd.cc | 38 +- selfdrive/common/SConscript | 5 +- selfdrive/common/clutil.c | 38 + selfdrive/common/clutil.h | 1 + selfdrive/common/framebuffer.cc | 11 +- selfdrive/common/gpio.cc | 29 + selfdrive/common/gpio.h | 35 + selfdrive/common/i2c.cc | 80 + selfdrive/common/i2c.h | 16 + selfdrive/common/modeldata.h | 36 +- selfdrive/common/params.cc | 46 +- selfdrive/common/params.h | 1 + selfdrive/common/spinner.c | 1 + selfdrive/common/swaglog.cc | 6 +- selfdrive/common/touch.c | 28 - selfdrive/common/touch.h | 6 +- selfdrive/common/util.c | 17 +- selfdrive/common/util.h | 1 + selfdrive/common/utilpp.h | 17 +- selfdrive/common/version.h | 2 +- selfdrive/common/visionbuf_cl.c | 1 + selfdrive/common/visionipc.c | 4 +- selfdrive/common/visionipc.h | 6 + selfdrive/controls/controlsd.py | 36 +- selfdrive/controls/lib/alertmanager.py | 48 +- selfdrive/controls/lib/events.py | 67 +- selfdrive/controls/lib/long_mpc.py | 2 +- selfdrive/controls/lib/longcontrol.py | 12 +- selfdrive/controls/lib/planner.py | 10 +- selfdrive/controls/plannerd.py | 11 +- selfdrive/controls/radard.py | 13 +- selfdrive/crash.py | 4 +- selfdrive/debug/cpu_usage_stat.py | 12 +- selfdrive/debug/cycle_alerts.py | 73 +- selfdrive/debug/disable_ecu.py | 40 + selfdrive/debug/dump.py | 9 +- selfdrive/debug/get_fingerprint.py | 3 + selfdrive/debug/uiview.py | 7 +- selfdrive/locationd/calibration_helpers.py | 10 - selfdrive/locationd/calibrationd.py | 207 +-- selfdrive/locationd/paramsd.py | 34 +- selfdrive/locationd/ublox_msg.cc | 27 +- selfdrive/locationd/ubloxd_test.cc | 10 +- selfdrive/logcatd/SConscript | 8 +- .../{logcatd.cc => logcatd_android.cc} | 6 +- selfdrive/logcatd/logcatd_systemd.cc | 71 + selfdrive/loggerd/config.py | 26 +- selfdrive/loggerd/encoder.c | 18 +- selfdrive/loggerd/logger.cc | 13 +- selfdrive/loggerd/loggerd.cc | 255 ++-- selfdrive/loggerd/uploader.py | 68 +- selfdrive/loggerd/xattr_cache.py | 13 + selfdrive/manager.py | 44 +- selfdrive/modeld/SConscript | 6 +- selfdrive/modeld/dmonitoringmodeld | 17 +- selfdrive/modeld/dmonitoringmodeld.cc | 26 +- selfdrive/modeld/modeld | 12 +- selfdrive/modeld/modeld.cc | 104 +- selfdrive/modeld/models/commonmodel.c | 10 +- selfdrive/modeld/models/commonmodel.h | 4 - selfdrive/modeld/models/dmonitoring.cc | 67 +- selfdrive/modeld/models/dmonitoring.h | 2 - selfdrive/modeld/models/driving.cc | 60 +- selfdrive/modeld/models/driving.h | 6 +- selfdrive/modeld/runners/snpemodel.cc | 4 +- selfdrive/modeld/runners/snpemodel.h | 2 +- selfdrive/monitoring/dmonitoringd.py | 85 +- selfdrive/monitoring/driver_monitor.py | 15 +- selfdrive/pandad.py | 21 +- selfdrive/proclogd/proclogd.cc | 7 +- selfdrive/registration.py | 7 +- selfdrive/rtshield.py | 16 + selfdrive/sensord/SConscript | 22 +- selfdrive/sensord/gpsd.cc | 16 +- selfdrive/sensord/sensors/bmx055_accel.cc | 71 + selfdrive/sensord/sensors/bmx055_accel.hpp | 36 + selfdrive/sensord/sensors/bmx055_gyro.cc | 81 + selfdrive/sensord/sensors/bmx055_gyro.hpp | 36 + selfdrive/sensord/sensors/bmx055_magn.cc | 109 ++ selfdrive/sensord/sensors/bmx055_magn.hpp | 27 + selfdrive/sensord/sensors/bmx055_temp.cc | 44 + selfdrive/sensord/sensors/bmx055_temp.hpp | 13 + selfdrive/sensord/sensors/constants.hpp | 18 + selfdrive/sensord/sensors/file_sensor.cc | 15 + selfdrive/sensord/sensors/file_sensor.hpp | 19 + selfdrive/sensord/sensors/i2c_sensor.cc | 24 + selfdrive/sensord/sensors/i2c_sensor.hpp | 24 + selfdrive/sensord/sensors/light_sensor.cc | 23 + selfdrive/sensord/sensors/light_sensor.hpp | 8 + selfdrive/sensord/sensors/sensor.hpp | 9 + .../sensord/{sensors.cc => sensors_qcom.cc} | 92 +- selfdrive/sensord/sensors_qcom2.cc | 90 ++ selfdrive/test/helpers.py | 24 +- selfdrive/test/setup_device_ci.sh | 2 +- selfdrive/test/test_cpu_usage.py | 25 +- selfdrive/thermald/power_monitoring.py | 196 ++- selfdrive/thermald/thermald.py | 117 +- selfdrive/tombstoned.py | 43 +- selfdrive/ui/SConscript | 31 +- .../ui/{sound.cc => android/sl_sound.cc} | 48 +- selfdrive/ui/android/sl_sound.hpp | 26 + selfdrive/ui/android/ui.cc | 265 ++++ selfdrive/ui/linux.cc | 107 -- selfdrive/ui/paint.cc | 366 ++--- selfdrive/ui/paint.hpp | 11 + selfdrive/ui/qt/qt_sound.cc | 30 + selfdrive/ui/qt/qt_sound.hpp | 16 + selfdrive/ui/qt/settings.cc | 140 ++ selfdrive/ui/qt/settings.hpp | 28 + selfdrive/ui/qt/ui.cc | 37 + selfdrive/ui/qt/wifi.cc | 69 + selfdrive/ui/qt/window.cc | 159 ++ selfdrive/ui/qt/window.hpp | 68 + selfdrive/ui/sidebar.cc | 62 +- selfdrive/ui/sidebar.hpp | 4 + selfdrive/ui/sound.hpp | 40 +- selfdrive/ui/spinner/Makefile | 1 + selfdrive/ui/spinner/spinner | Bin 534752 -> 551136 bytes selfdrive/ui/text/Makefile | 1 + selfdrive/ui/ui.cc | 895 ++--------- selfdrive/ui/ui.hpp | 217 ++- selfdrive/updated.py | 283 ++-- selfdrive/version.py | 24 +- 268 files changed, 5976 insertions(+), 5096 deletions(-) delete mode 100644 common/android.py create mode 100644 common/gpio.py create mode 100644 common/hardware.py create mode 100644 common/hardware_android.py create mode 100644 common/hardware_base.py create mode 100644 common/hardware_tici.py create mode 100644 panda/board/drivers/clock_source.h delete mode 100644 panda/certs/debugesp delete mode 100644 panda/certs/debugesp.pub delete mode 100644 panda/certs/releaseesp.pub delete mode 100755 panda/python/esptool.py create mode 100644 selfdrive/assets/offroad/circled-checkmark.png create mode 100644 selfdrive/assets/offroad/icon_app_store.png create mode 100644 selfdrive/assets/offroad/icon_calibration.png create mode 100644 selfdrive/assets/offroad/icon_checkmark.png create mode 100644 selfdrive/assets/offroad/icon_chevron_right.png create mode 100644 selfdrive/assets/offroad/icon_connect_app.png create mode 100644 selfdrive/assets/offroad/icon_eon.png create mode 100644 selfdrive/assets/offroad/icon_map.png create mode 100644 selfdrive/assets/offroad/icon_map_speed.png create mode 100644 selfdrive/assets/offroad/icon_menu.png create mode 100644 selfdrive/assets/offroad/icon_metric.png create mode 100644 selfdrive/assets/offroad/icon_minus.png create mode 100644 selfdrive/assets/offroad/icon_monitoring.png create mode 100644 selfdrive/assets/offroad/icon_network.png create mode 100644 selfdrive/assets/offroad/icon_openpilot.png create mode 100644 selfdrive/assets/offroad/icon_openpilot_mirrored.png create mode 100644 selfdrive/assets/offroad/icon_play_store.png create mode 100644 selfdrive/assets/offroad/icon_plus.png create mode 100644 selfdrive/assets/offroad/icon_road.png create mode 100644 selfdrive/assets/offroad/icon_settings.png create mode 100644 selfdrive/assets/offroad/icon_shell.png create mode 100644 selfdrive/assets/offroad/icon_speed_limit.png create mode 100644 selfdrive/assets/offroad/icon_user.png create mode 100644 selfdrive/assets/offroad/icon_warning.png create mode 100644 selfdrive/assets/offroad/illustration_arrow.png create mode 100644 selfdrive/assets/offroad/illustration_sim_absent.png create mode 100644 selfdrive/assets/offroad/illustration_sim_present.png create mode 100644 selfdrive/assets/offroad/illustration_training_lane_01.png create mode 100644 selfdrive/assets/offroad/illustration_training_lane_02.png create mode 100644 selfdrive/assets/offroad/illustration_training_lead_01.png create mode 100644 selfdrive/assets/offroad/illustration_training_lead_02.png create mode 100644 selfdrive/assets/offroad/indicator_wifi_0.png create mode 100644 selfdrive/assets/offroad/indicator_wifi_100.png create mode 100644 selfdrive/assets/offroad/indicator_wifi_25.png create mode 100644 selfdrive/assets/offroad/indicator_wifi_50.png create mode 100644 selfdrive/assets/offroad/indicator_wifi_75.png create mode 100644 selfdrive/boardd/pigeon.cc create mode 100644 selfdrive/boardd/pigeon.h create mode 100644 selfdrive/common/gpio.cc create mode 100644 selfdrive/common/gpio.h create mode 100644 selfdrive/common/i2c.cc create mode 100644 selfdrive/common/i2c.h create mode 100644 selfdrive/debug/disable_ecu.py mode change 100644 => 100755 selfdrive/debug/uiview.py delete mode 100644 selfdrive/locationd/calibration_helpers.py rename selfdrive/logcatd/{logcatd.cc => logcatd_android.cc} (88%) create mode 100644 selfdrive/logcatd/logcatd_systemd.cc create mode 100644 selfdrive/loggerd/xattr_cache.py create mode 100644 selfdrive/rtshield.py create mode 100644 selfdrive/sensord/sensors/bmx055_accel.cc create mode 100644 selfdrive/sensord/sensors/bmx055_accel.hpp create mode 100644 selfdrive/sensord/sensors/bmx055_gyro.cc create mode 100644 selfdrive/sensord/sensors/bmx055_gyro.hpp create mode 100644 selfdrive/sensord/sensors/bmx055_magn.cc create mode 100644 selfdrive/sensord/sensors/bmx055_magn.hpp create mode 100644 selfdrive/sensord/sensors/bmx055_temp.cc create mode 100644 selfdrive/sensord/sensors/bmx055_temp.hpp create mode 100644 selfdrive/sensord/sensors/constants.hpp create mode 100644 selfdrive/sensord/sensors/file_sensor.cc create mode 100644 selfdrive/sensord/sensors/file_sensor.hpp create mode 100644 selfdrive/sensord/sensors/i2c_sensor.cc create mode 100644 selfdrive/sensord/sensors/i2c_sensor.hpp create mode 100644 selfdrive/sensord/sensors/light_sensor.cc create mode 100644 selfdrive/sensord/sensors/light_sensor.hpp create mode 100644 selfdrive/sensord/sensors/sensor.hpp rename selfdrive/sensord/{sensors.cc => sensors_qcom.cc} (67%) create mode 100644 selfdrive/sensord/sensors_qcom2.cc rename selfdrive/ui/{sound.cc => android/sl_sound.cc} (79%) create mode 100644 selfdrive/ui/android/sl_sound.hpp create mode 100644 selfdrive/ui/android/ui.cc delete mode 100644 selfdrive/ui/linux.cc create mode 100644 selfdrive/ui/paint.hpp create mode 100644 selfdrive/ui/qt/qt_sound.cc create mode 100644 selfdrive/ui/qt/qt_sound.hpp create mode 100644 selfdrive/ui/qt/settings.cc create mode 100644 selfdrive/ui/qt/settings.hpp create mode 100644 selfdrive/ui/qt/ui.cc create mode 100644 selfdrive/ui/qt/wifi.cc create mode 100644 selfdrive/ui/qt/window.cc create mode 100644 selfdrive/ui/qt/window.hpp create mode 100644 selfdrive/ui/sidebar.hpp diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index b8564c1e855183..8f54cdf0789faf 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -18,7 +18,7 @@ You can test your changes on your machine by running `run_docker_tests.sh`. This ### Automated Testing -All PRs and commits are automatically checked by Github Actions. Check out `.github/workflows/` for what Github Actions runs. Any new tests sould be added to Github Actions. +All PRs and commits are automatically checked by Github Actions. Check out `.github/workflows/` for what Github Actions runs. Any new tests should be added to Github Actions. ### Code Style and Linting @@ -28,7 +28,7 @@ Code is automatically checked for style by Github Actions as part of the automat We've released a [Model Port guide](https://medium.com/@comma_ai/openpilot-port-guide-for-toyota-models-e5467f4b5fe6) for porting to Toyota/Lexus models. -If you port openpilot to a substantially new car brand, see this more generic [Brand Port guide](https://medium.com/@comma_ai/how-to-write-a-car-port-for-openpilot-7ce0785eda84). You might also be eligible for a bounty. See our bounties at [comma.ai/bounties.html](https://comma.ai/bounties.html) +If you port openpilot to a substantially new car brand, see this more generic [Brand Port guide](https://medium.com/@comma_ai/how-to-write-a-car-port-for-openpilot-7ce0785eda84). You might also be eligible for a bounty. ## Pull Requests diff --git a/Jenkinsfile b/Jenkinsfile index dd0e2c12fa1b31..df52f59e16b8b1 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -70,7 +70,7 @@ pipeline { stage('PC tests') { agent { dockerfile { - filename 'Dockerfile.openpilot' + filename 'Dockerfile.openpilotci' args '--privileged --shm-size=1G --user=root' } } @@ -132,6 +132,7 @@ pipeline { ["build cereal", "SCONS_CACHE=1 scons -j4 cereal/"], ["test sounds", "nosetests -s selfdrive/test/test_sounds.py"], ["test boardd loopback", "nosetests -s selfdrive/boardd/tests/test_boardd_loopback.py"], + ["test loggerd", "CI=1 python selfdrive/loggerd/tests/test_loggerd.py"], //["test updater", "python installer/updater/test_updater.py"], ]) } @@ -140,6 +141,13 @@ pipeline { } } } + + post { + always { + cleanWs() + } + } + } } diff --git a/README.md b/README.md index f78a070883146c..17a095252eb0da 100644 --- a/README.md +++ b/README.md @@ -70,31 +70,30 @@ Supported Cars | Honda | Accord Hybrid 2018-20 | All | Stock | 0mph | 3mph | | Honda | Civic Hatchback 2017-19 | Honda Sensing | Stock | 0mph | 12mph | | Honda | Civic Sedan/Coupe 2016-18 | Honda Sensing | openpilot | 0mph | 12mph | -| Honda | Civic Sedan/Coupe 2019-20 | Honda Sensing | Stock | 0mph | 2mph2 | +| Honda | Civic Sedan/Coupe 2019-20 | All | Stock | 0mph | 2mph2 | | Honda | CR-V 2015-16 | Touring | openpilot | 25mph1 | 12mph | | Honda | CR-V 2017-20 | Honda Sensing | Stock | 0mph | 12mph | | Honda | CR-V Hybrid 2017-2019 | Honda Sensing | Stock | 0mph | 12mph | | Honda | Fit 2018-19 | Honda Sensing | openpilot | 25mph1 | 12mph | | Honda | HR-V 2019 | Honda Sensing | openpilot | 25mph1 | 12mph | -| Honda | Insight 2019-20 | Honda Sensing | Stock | 0mph | 3mph | +| Honda | Insight 2019-20 | All | Stock | 0mph | 3mph | | Honda | Odyssey 2018-20 | Honda Sensing | openpilot | 25mph1 | 0mph | | Honda | Passport 2019 | All | openpilot | 25mph1 | 12mph | -| Honda | Pilot 2016-18 | Honda Sensing | openpilot | 25mph1 | 12mph | -| Honda | Pilot 2019 | All | openpilot | 25mph1 | 12mph | +| Honda | Pilot 2016-19 | Honda Sensing | openpilot | 25mph1 | 12mph | | Honda | Ridgeline 2017-20 | Honda Sensing | openpilot | 25mph1 | 12mph | +| Hyundai | Palisade 2020 | All | Stock | 0mph | 0mph | | Hyundai | Sonata 2020 | All | Stock | 0mph | 0mph | -| Lexus | CT Hybrid 2017-18 | All | Stock3| 0mph | 0mph | +| Lexus | CT Hybrid 2017-18 | LSS | Stock3| 0mph | 0mph | | Lexus | ES 2019 | All | openpilot | 0mph | 0mph | | Lexus | ES Hybrid 2019 | All | openpilot | 0mph | 0mph | | Lexus | IS 2017-2019 | All | Stock | 22mph | 0mph | | Lexus | IS Hybrid 2017 | All | Stock | 0mph | 0mph | | Lexus | NX Hybrid 2018 | All | Stock3| 0mph | 0mph | -| Lexus | RX 2016-17 | All | Stock3| 0mph | 0mph | +| Lexus | RX 2016-18 | All | Stock3| 0mph | 0mph | | Lexus | RX 2020 | All | openpilot | 0mph | 0mph | | Lexus | RX Hybrid 2016-19 | All | Stock3| 0mph | 0mph | | Lexus | RX Hybrid 2020 | All | openpilot | 0mph | 0mph | -| Toyota | Avalon 2016 | TSS-P | Stock3| 20mph1 | 0mph | -| Toyota | Avalon 2017-18 | All | Stock3| 20mph1 | 0mph | +| Toyota | Avalon 2016-18 | TSS-P | Stock3| 20mph1 | 0mph | | Toyota | Camry 2018-20 | All | Stock | 0mph4 | 0mph | | Toyota | Camry Hybrid 2018-19 | All | Stock | 0mph4 | 0mph | | Toyota | C-HR 2017-19 | All | Stock | 0mph | 0mph | @@ -102,19 +101,16 @@ Supported Cars | Toyota | Corolla 2017-19 | All | Stock3| 20mph1 | 0mph | | Toyota | Corolla 2020 | All | openpilot | 0mph | 0mph | | Toyota | Corolla Hatchback 2019-20 | All | openpilot | 0mph | 0mph | -| Toyota | Corolla Hybrid 2020 | All | openpilot | 0mph | 0mph | +| Toyota | Corolla Hybrid 2020-21 | All | openpilot | 0mph | 0mph | | Toyota | Highlander 2017-19 | All | Stock3| 0mph | 0mph | -| Toyota | Highlander Hybrid 2017-19 | All | Stock3| 0mph | 0mph | | Toyota | Highlander 2020 | All | openpilot | 0mph | 0mph | +| Toyota | Highlander Hybrid 2017-19 | All | Stock3| 0mph | 0mph | | Toyota | Highlander Hybrid 2020 | All | openpilot | 0mph | 0mph | -| Toyota | Prius 2016 | TSS-P | Stock3| 0mph | 0mph | -| Toyota | Prius 2017-20 | All | Stock3| 0mph | 0mph | +| Toyota | Prius 2016-20 | TSS-P | Stock3| 0mph | 0mph | | Toyota | Prius Prime 2017-20 | All | Stock3| 0mph | 0mph | -| Toyota | Rav4 2016 | TSS-P | Stock3| 20mph1 | 0mph | -| Toyota | Rav4 2017-18 | All | Stock3| 20mph1 | 0mph | +| Toyota | Rav4 2016-18 | TSS-P | Stock3| 20mph1 | 0mph | | Toyota | Rav4 2019-20 | All | openpilot | 0mph | 0mph | -| Toyota | Rav4 Hybrid 2016 | TSS-P | Stock3| 0mph | 0mph | -| Toyota | Rav4 Hybrid 2017-18 | All | Stock3| 0mph | 0mph | +| Toyota | Rav4 Hybrid 2016-18 | TSS-P | Stock3| 0mph | 0mph | | Toyota | Rav4 Hybrid 2019-20 | All | openpilot | 0mph | 0mph | | Toyota | Sienna 2018-20 | All | Stock3| 0mph | 0mph | @@ -143,24 +139,22 @@ Community Maintained Cars and Features | Holden | Astra 20171 | Adaptive Cruise | openpilot | 0mph | 7mph | | Hyundai | Elantra 2017-19 | SCC + LKAS | Stock | 19mph | 34mph | | Hyundai | Genesis 2015-16 | SCC + LKAS | Stock | 19mph | 37mph | -| Hyundai | Ioniq Electric Premium SE 2020| SCC + LKAS | Stock | 0mph | 32mph | -| Hyundai | Ioniq Electric Limited 2019 | SCC + LKAS | Stock | 0mph | 32mph | +| Hyundai | Ioniq Electric 2019-20 | SCC + LKAS | Stock | 0mph | 32mph | | Hyundai | Kona 2020 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Kona EV 2019 | SCC + LKAS | Stock | 0mph | 0mph | -| Hyundai | Palisade 2020 | All | Stock | 0mph | 0mph | | Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph | | Hyundai | Sonata 2019 | All | Stock | 0mph | 0mph | | Hyundai | Veloster 2019 | SCC + LKAS | Stock | 5mph | 0mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | | Kia | Forte 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | Optima 2017 | SCC + LKAS/LDWS | Stock | 0mph | 32mph | +| Kia | Optima 2017 | SCC + LKAS | Stock | 0mph | 32mph | | Kia | Optima 2019 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Sorento 2018 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Stinger 2018 | SCC + LKAS | Stock | 0mph | 0mph | -| Nissan | Leaf 2018-19 | Propilot | Stock | 0mph | 0mph | -| Nissan | Rogue 2019 | Propilot | Stock | 0mph | 0mph | -| Nissan | X-Trail 2017 | Propilot | Stock | 0mph | 0mph | +| Nissan | Leaf 2018-19 | ProPILOT | Stock | 0mph | 0mph | +| Nissan | Rogue 2019 | ProPILOT | Stock | 0mph | 0mph | +| Nissan | X-Trail 2017 | ProPILOT | Stock | 0mph | 0mph | | Subaru | Ascent 2019 | EyeSight | Stock | 0mph | 0mph | | Subaru | Crosstrek 2018-19 | EyeSight | Stock | 0mph | 0mph | | Subaru | Forester 2019 | EyeSight | Stock | 0mph | 0mph | @@ -274,8 +268,23 @@ Safety and Testing Testing on PC ------ +For simplified development and experimentation, openpilot runs in the CARLA driving simulator, which allows you to develop openpilot without a car. + +Steps: +1) Start the CARLA server on first terminal +``` +bash -c "$(curl https://raw.githubusercontent.com/commaai/openpilot/master/tools/sim/start_carla.sh)" +``` +2) Start openpilot on second terminal +``` +bash -c "$(curl https://raw.githubusercontent.com/commaai/openpilot/master/tools/sim/start_openpilot_docker.sh)" +``` +3) Press 1 to engage openpilot + +See the full [README](tools/sim/README.md) + +You should also take a look at the tools directory in master: lots of tools you can use to replay driving data, test, and develop openpilot from your PC. -Check out the tools directory in master: lots of tools you can use to replay driving data, test and develop openpilot from your pc. Community and Contributing ------ diff --git a/RELEASES.md b/RELEASES.md index 0c6dd3d4fb0783..e8a157567c00ad 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,11 @@ +Version 0.7.9 (2020-10-09) +======================== + * Improved car battery power management + * Improved updater robustness + * Improved realtime performance + * Reduced UI and modeld lags + * Increased torque on 2020 Hyundai Sonata and Palisade + Version 0.7.8 (2020-08-19) ======================== * New driver monitoring model: improved face detection and better compatibility with sunglasses diff --git a/SConstruct b/SConstruct index 322bdd5f9faeed..fc119262b59b1b 100644 --- a/SConstruct +++ b/SConstruct @@ -6,6 +6,8 @@ import subprocess import sys import platform +TICI = os.path.isfile('/TICI') + AddOption('--test', action='store_true', help='build test files') @@ -18,10 +20,11 @@ AddOption('--asan', cython_dependencies = [Value(v) for v in (sys.version, distutils.__version__, Cython.__version__)] Export('cython_dependencies') -arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() +real_arch = arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() if platform.system() == "Darwin": arch = "Darwin" -if arch == "aarch64" and not os.path.isdir("/system"): + +if arch == "aarch64" and TICI: arch = "larch64" webcam = bool(ARGUMENTS.get("use_webcam", 0)) @@ -44,7 +47,6 @@ if arch == "aarch64" or arch == "larch64": libpath = [ "/usr/lib", - "/data/data/com.termux/files/usr/lib", "/system/vendor/lib64", "/system/comma/usr/lib", "#phonelibs/nanovg", @@ -62,11 +64,12 @@ if arch == "aarch64" or arch == "larch64": else: libpath += [ "#phonelibs/snpe/aarch64", - "#phonelibs/libyuv/lib" + "#phonelibs/libyuv/lib", + "/system/vendor/lib64" ] cflags = ["-DQCOM", "-mcpu=cortex-a57"] cxxflags = ["-DQCOM", "-mcpu=cortex-a57"] - rpath = ["/system/vendor/lib64"] + rpath = [] if QCOM_REPLAY: cflags += ["-DQCOM_REPLAY"] @@ -131,8 +134,11 @@ env = Environment( "-O2", "-Wunused", "-Werror", + "-Wno-unknown-warning-option", "-Wno-deprecated-register", "-Wno-inconsistent-missing-override", + "-Wno-c99-designator", + "-Wno-reorder-init-list", ] + cflags + ccflags_asan, CPPPATH=cpppath + [ @@ -143,7 +149,6 @@ env = Environment( "#phonelibs/openmax/include", "#phonelibs/json11", "#phonelibs/curl/include", - #"#phonelibs/opencv/include", # use opencv4 instead "#phonelibs/libgralloc/include", "#phonelibs/android_frameworks_native/include", "#phonelibs/android_hardware_libhardware/include", @@ -156,6 +161,8 @@ env = Environment( "#selfdrive/camerad/include", "#selfdrive/loggerd/include", "#selfdrive/modeld", + "#selfdrive/sensord", + "#selfdrive/ui", "#cereal/messaging", "#cereal", "#opendbc/can", @@ -176,6 +183,44 @@ env = Environment( ] ) +qt_env = None +if arch in ["x86_64", "Darwin", "larch64"]: + qt_env = env.Clone() + + if arch == "Darwin": + qt_env['QTDIR'] = "/usr/local/opt/qt" + QT_BASE = "/usr/local/opt/qt/" + qt_dirs = [ + QT_BASE + "include/", + QT_BASE + "include/QtWidgets", + QT_BASE + "include/QtGui", + QT_BASE + "include/QtCore", + QT_BASE + "include/QtDBus", + QT_BASE + "include/QtMultimedia", + ] + qt_env["LINKFLAGS"] += ["-F" + QT_BASE + "lib"] + else: + qt_dirs = [ + f"/usr/include/{real_arch}-linux-gnu/qt5", + f"/usr/include/{real_arch}-linux-gnu/qt5/QtWidgets", + f"/usr/include/{real_arch}-linux-gnu/qt5/QtGui", + f"/usr/include/{real_arch}-linux-gnu/qt5/QtCore", + f"/usr/include/{real_arch}-linux-gnu/qt5/QtDBus", + f"/usr/include/{real_arch}-linux-gnu/qt5/QtMultimedia", + f"/usr/include/{real_arch}-linux-gnu/qt5/QtGui/5.5.1/QtGui", + ] + + qt_env.Tool('qt') + qt_env['CPPPATH'] += qt_dirs + qt_flags = [ + "-D_REENTRANT", + "-DQT_NO_DEBUG", + "-DQT_WIDGETS_LIB", + "-DQT_GUI_LIB", + "-DQT_CORE_LIB" + ] + qt_env['CXXFLAGS'] += qt_flags + if os.environ.get('SCONS_CACHE'): cache_dir = '/tmp/scons_cache' @@ -214,7 +259,7 @@ def abspath(x): # still needed for apks zmq = 'zmq' -Export('env', 'arch', 'zmq', 'SHARED', 'webcam', 'QCOM_REPLAY') +Export('env', 'qt_env', 'arch', 'zmq', 'SHARED', 'webcam', 'QCOM_REPLAY') # cereal and messaging are shared with the system SConscript(['cereal/SConscript']) @@ -255,16 +300,18 @@ SConscript(['selfdrive/controls/lib/longitudinal_mpc_model/SConscript']) SConscript(['selfdrive/boardd/SConscript']) SConscript(['selfdrive/proclogd/SConscript']) +SConscript(['selfdrive/clocksd/SConscript']) -SConscript(['selfdrive/ui/SConscript']) SConscript(['selfdrive/loggerd/SConscript']) SConscript(['selfdrive/locationd/SConscript']) SConscript(['selfdrive/locationd/models/SConscript']) +SConscript(['selfdrive/sensord/SConscript']) +SConscript(['selfdrive/ui/SConscript']) -if arch == "aarch64": +if arch != "Darwin": SConscript(['selfdrive/logcatd/SConscript']) - SConscript(['selfdrive/sensord/SConscript']) - SConscript(['selfdrive/clocksd/SConscript']) -else: + + +if arch == "x86_64": SConscript(['tools/lib/index_log/SConscript']) diff --git a/cereal/car.capnp b/cereal/car.capnp index 0db47f78bc00b4..17bc461b3c7d4a 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -38,7 +38,6 @@ struct CarEvent @0x9b1657f34caf3ad3 { pedalPressed @13; cruiseDisabled @14; radarCanError @15; - dataNeededDEPRECATED @16; speedTooLow @17; outOfSpace @18; overheat @19; @@ -49,29 +48,22 @@ struct CarEvent @0x9b1657f34caf3ad3 { pcmDisable @24; noTarget @25; radarFault @26; - modelCommIssueDEPRECATED @27; brakeHold @28; parkBrake @29; manualRestart @30; lowSpeedLockout @31; plannerError @32; - ipasOverrideDEPRECATED @33; debugAlert @34; steerTempUnavailableMute @35; resumeRequired @36; preDriverDistracted @37; promptDriverDistracted @38; driverDistracted @39; - geofenceDEPRECATED @40; - driverMonitorOnDEPRECATED @41; - driverMonitorOffDEPRECATED @42; preDriverUnresponsive @43; promptDriverUnresponsive @44; driverUnresponsive @45; belowSteerSpeed @46; - calibrationProgressDEPRECATED @47; lowBattery @48; - invalidGiraffeHondaDEPRECATED @49; vehicleModelInvalid @50; controlsFailed @51; sensorDataInvalid @52; @@ -104,8 +96,6 @@ struct CarEvent @0x9b1657f34caf3ad3 { fcw @79; steerSaturated @80; whitePandaUnsupported @81; - startupWhitePanda @82; - canErrorPersistentDEPRECATED @83; belowEngageSpeed @84; noGps @85; focusRecoverActive @86; @@ -113,6 +103,17 @@ struct CarEvent @0x9b1657f34caf3ad3 { neosUpdateRequired @88; modeldLagging @89; deviceFalling @90; + + dataNeededDEPRECATED @16; + modelCommIssueDEPRECATED @27; + ipasOverrideDEPRECATED @33; + geofenceDEPRECATED @40; + driverMonitorOnDEPRECATED @41; + driverMonitorOffDEPRECATED @42; + calibrationProgressDEPRECATED @47; + invalidGiraffeHondaDEPRECATED @49; + canErrorPersistentDEPRECATED @83; + startupWhitePandaDEPRECATED @82; } } diff --git a/cereal/log.capnp b/cereal/log.capnp index 64a577bc5d1e24..c8419500acc968 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -186,6 +186,7 @@ struct SensorEventData { gyroUncalibrated @12 :SensorVec; proximity @13: Float32; light @14: Float32; + temperature @15: Float32; } source @8 :SensorSource; @@ -203,6 +204,8 @@ struct SensorEventData { lsm6ds3 @5; # accelerometer (c2) bmp280 @6; # barometer (c2) mmc3416x @7; # magnetometer (c2) + bmx055 @8; + rpr0521 @9; } } @@ -267,14 +270,15 @@ struct CanData { } struct ThermalData { - cpu0 @0 :UInt16; - cpu1 @1 :UInt16; - cpu2 @2 :UInt16; - cpu3 @3 :UInt16; - mem @4 :UInt16; - gpu @5 :UInt16; - bat @6 :UInt32; - pa0 @21 :UInt16; + # Deprecated + cpu0DEPRECATED @0 :UInt16; + cpu1DEPRECATED @1 :UInt16; + cpu2DEPRECATED @2 :UInt16; + cpu3DEPRECATED @3 :UInt16; + memDEPRECATED @4 :UInt16; + gpuDEPRECATED @5 :UInt16; + batDEPRECATED @6 :UInt32; + pa0DEPRECATED @21 :UInt16; # not thermal freeSpace @7 :Float32; @@ -286,6 +290,7 @@ struct ThermalData { networkType @22 :NetworkType; offroadPowerUsage @23 :UInt32; # Power usage since going offroad in uWh networkStrength @24 :NetworkStrength; + carBatteryCapacity @25 :UInt32; # Estimated remaining car battery capacity in uWh fanSpeed @10 :UInt16; started @11 :Bool; @@ -298,6 +303,12 @@ struct ThermalData { memUsedPercent @19 :Int8; cpuPerc @20 :Int8; + cpu @26 :List(Float32); + gpu @27 :List(Float32); + mem @28 :Float32; + bat @29 :Float32; + ambient @30 :Float32; + enum ThermalStatus { green @0; # all processes run yellow @1; # critical processes run (kill uploader), engage still allowed @@ -373,6 +384,8 @@ struct HealthData { interruptRateTim3 @17; registerDivergent @18; interruptRateKlineInit @19; + interruptRateClockSource @20; + interruptRateTim9 @21; # Update max fault type in boardd when adding faults } @@ -602,7 +615,7 @@ struct ControlsState @0x97ff69c53601abf1 { output @3 :Float32; lqrOutput @4 :Float32; saturated @5 :Bool; - } + } } struct LiveEventData { @@ -675,6 +688,52 @@ struct ModelData { } } + +struct ModelDataV2 { + frameId @0 :UInt32; + frameAge @1 :UInt32; + frameDropPerc @2 :Float32; + timestampEof @3 :UInt64; + + position @4 :XYZTData; + orientation @5 :XYZTData; + velocity @6 :XYZTData; + orientationRate @7 :XYZTData; + laneLines @8 :List(XYZTData); + laneLineProbs @9 :List(Float32); + roadEdges @10 :List(XYZTData); + leads @11 :List(LeadDataV2); + + meta @12 :MetaData; + + struct XYZTData { + x @0 :List(Float32); + y @1 :List(Float32); + z @2 :List(Float32); + t @3 :List(Float32); + xStd @4 :List(Float32); + yStd @5 :List(Float32); + zStd @6 :List(Float32); + } + + struct LeadDataV2 { + prob @0 :Float32; + t @1 :Float32; + xyva @2 :List(Float32); + xyvaStd @3 :List(Float32); + } + + struct MetaData { + engagedProb @0 :Float32; + desirePrediction @1 :List(Float32); + brakeDisengageProb @2 :Float32; + gasDisengageProb @3 :Float32; + steerOverrideProb @4 :Float32; + desireState @5 :List(Float32); + } +} + + struct CalibrationFeatures { frameId @0 :UInt32; @@ -1906,7 +1965,6 @@ struct DMonitoringState { isDistracted @2 :Bool; awarenessStatus @3 :Float32; isRHD @4 :Bool; - rhdChecked @5 :Bool; posePitchOffset @6 :Float32; posePitchValidCount @7 :UInt32; poseYawOffset @8 :Float32; @@ -1917,6 +1975,8 @@ struct DMonitoringState { isLowStd @13 :Bool; hiStdCount @14 :UInt32; isPreview @15 :Bool; + + rhdCheckedDEPRECATED @5 :Bool; } struct Boot { @@ -2062,5 +2122,7 @@ struct Event { dMonitoringState @71: DMonitoringState; liveLocationKalman @72 :LiveLocationKalman; sentinel @73 :Sentinel; + wideFrame @74: FrameData; + modelV2 @75 :ModelDataV2; } } diff --git a/cereal/messaging/__init__.py b/cereal/messaging/__init__.py index 5e36bd8d8c17c0..0b1204b47a550a 100644 --- a/cereal/messaging/__init__.py +++ b/cereal/messaging/__init__.py @@ -3,6 +3,8 @@ from .messaging_pyx import MultiplePublishersError, MessagingError # pylint: disable=no-name-in-module, import-error import capnp +from typing import Optional, List, Union + from cereal import log from cereal.services import service_list @@ -19,7 +21,7 @@ context = Context() -def new_message(service=None, size=None): +def new_message(service: Optional[str] = None, size: Optional[int] = None) -> capnp.lib.capnp._DynamicStructBuilder: dat = log.Event.new_message() dat.logMonoTime = int(sec_since_boot() * 1e9) dat.valid = True @@ -30,15 +32,15 @@ def new_message(service=None, size=None): dat.init(service, size) return dat -def pub_sock(endpoint): +def pub_sock(endpoint: str) -> PubSocket: sock = PubSocket() sock.connect(context, endpoint) return sock -def sub_sock(endpoint, poller=None, addr="127.0.0.1", conflate=False, timeout=None): +def sub_sock(endpoint: str, poller: Optional[Poller] = None, addr: str = "127.0.0.1", + conflate: bool = False, timeout: Optional[int] = None) -> SubSocket: sock = SubSocket() - addr = addr.encode('utf8') - sock.connect(context, endpoint, addr, conflate) + sock.connect(context, endpoint, addr.encode('utf8'), conflate) if timeout is not None: sock.setTimeout(timeout) @@ -48,9 +50,9 @@ def sub_sock(endpoint, poller=None, addr="127.0.0.1", conflate=False, timeout=No return sock -def drain_sock_raw(sock, wait_for_one=False): +def drain_sock_raw(sock: SubSocket, wait_for_one: bool = False) -> List[bytes]: """Receive all message currently available on the queue""" - ret = [] + ret: List[bytes] = [] while 1: if wait_for_one and len(ret) == 0: dat = sock.receive() @@ -64,9 +66,9 @@ def drain_sock_raw(sock, wait_for_one=False): return ret -def drain_sock(sock, wait_for_one=False): +def drain_sock(sock: SubSocket, wait_for_one: bool = False) -> List[capnp.lib.capnp._DynamicStructReader]: """Receive all message currently available on the queue""" - ret = [] + ret: List[capnp.lib.capnp._DynamicStructReader] = [] while 1: if wait_for_one and len(ret) == 0: dat = sock.receive() @@ -83,7 +85,7 @@ def drain_sock(sock, wait_for_one=False): # TODO: print when we drop packets? -def recv_sock(sock, wait=False): +def recv_sock(sock: SubSocket, wait: bool = False) -> Union[None, capnp.lib.capnp._DynamicStructReader]: """Same as drain sock, but only returns latest message. Consider using conflate instead.""" dat = None @@ -103,19 +105,19 @@ def recv_sock(sock, wait=False): return dat -def recv_one(sock): +def recv_one(sock: SubSocket) -> Union[None, capnp.lib.capnp._DynamicStructReader]: dat = sock.receive() if dat is not None: dat = log.Event.from_bytes(dat) return dat -def recv_one_or_none(sock): +def recv_one_or_none(sock: SubSocket) -> Union[None, capnp.lib.capnp._DynamicStructReader]: dat = sock.receive(non_blocking=True) if dat is not None: dat = log.Event.from_bytes(dat) return dat -def recv_one_retry(sock): +def recv_one_retry(sock: SubSocket) -> capnp.lib.capnp._DynamicStructReader: """Keep receiving until we get a message""" while True: dat = sock.receive() @@ -123,8 +125,8 @@ def recv_one_retry(sock): return log.Event.from_bytes(dat) class SubMaster(): - def __init__(self, services, ignore_alive=None, addr="127.0.0.1"): - self.poller = Poller() + def __init__(self, services: List[str], poll: Optional[List[str]] = None, + ignore_alive: Optional[List[str]] = None, addr:str ="127.0.0.1"): self.frame = -1 self.updated = {s: False for s in services} self.rcv_time = {s: 0. for s in services} @@ -133,8 +135,12 @@ def __init__(self, services, ignore_alive=None, addr="127.0.0.1"): self.sock = {} self.freq = {} self.data = {} - self.logMonoTime = {} self.valid = {} + self.logMonoTime = {} + + self.poller = Poller() + self.non_polled_services = [s for s in services if poll is not None and + len(poll) and s not in poll] if ignore_alive is not None: self.ignore_alive = ignore_alive @@ -143,30 +149,33 @@ def __init__(self, services, ignore_alive=None, addr="127.0.0.1"): for s in services: if addr is not None: - self.sock[s] = sub_sock(s, poller=self.poller, addr=addr, conflate=True) + p = self.poller if s not in self.non_polled_services else None + self.sock[s] = sub_sock(s, poller=p, addr=addr, conflate=True) self.freq[s] = service_list[s].frequency try: data = new_message(s) except capnp.lib.capnp.KjException: # pylint: disable=c-extension-no-member - # lists - data = new_message(s, 0) + data = new_message(s, 0) # lists self.data[s] = getattr(data, s) self.logMonoTime[s] = 0 self.valid[s] = data.valid - def __getitem__(self, s): + def __getitem__(self, s: str) -> capnp.lib.capnp._DynamicStructReader: return self.data[s] - def update(self, timeout=1000): + def update(self, timeout: int = 1000) -> None: msgs = [] for sock in self.poller.poll(timeout): msgs.append(recv_one_or_none(sock)) + + # non-blocking receive for non-polled sockets + for s in self.non_polled_services: + msgs.append(recv_one_or_none(self.sock[s])) self.update_msgs(sec_since_boot(), msgs) - def update_msgs(self, cur_time, msgs): - # TODO: add optional input that specify the service to wait for + def update_msgs(self, cur_time: float, msgs: List[capnp.lib.capnp._DynamicStructReader]) -> None: self.frame += 1 self.updated = dict.fromkeys(self.updated, False) for msg in msgs: @@ -189,30 +198,28 @@ def update_msgs(self, cur_time, msgs): else: self.alive[s] = True - def all_alive(self, service_list=None): + def all_alive(self, service_list=None) -> bool: if service_list is None: # check all service_list = self.alive.keys() return all(self.alive[s] for s in service_list if s not in self.ignore_alive) - def all_valid(self, service_list=None): + def all_valid(self, service_list=None) -> bool: if service_list is None: # check all service_list = self.valid.keys() return all(self.valid[s] for s in service_list) - def all_alive_and_valid(self, service_list=None): + def all_alive_and_valid(self, service_list=None) -> bool: if service_list is None: # check all service_list = self.alive.keys() return self.all_alive(service_list=service_list) and self.all_valid(service_list=service_list) - class PubMaster(): - def __init__(self, services): + def __init__(self, services: List[str]): self.sock = {} for s in services: self.sock[s] = pub_sock(s) - def send(self, s, dat): - # accept either bytes or capnp builder + def send(self, s: str, dat: Union[bytes, capnp.lib.capnp._DynamicStructBuilder]) -> None: if not isinstance(dat, bytes): dat = dat.to_bytes() self.sock[s].send(dat) diff --git a/cereal/messaging/impl_msgq.cc b/cereal/messaging/impl_msgq.cc index 0a51d12c17ff4e..7da9a227c90d18 100644 --- a/cereal/messaging/impl_msgq.cc +++ b/cereal/messaging/impl_msgq.cc @@ -15,6 +15,18 @@ void sig_handler(int signal) { msgq_do_exit = 1; } +static size_t get_size(std::string endpoint){ + size_t sz = DEFAULT_SEGMENT_SIZE; + +#if !defined(QCOM) && !defined(QCOM2) + if (endpoint == "frame" || endpoint == "frontFrame" || endpoint == "wideFrame"){ + sz *= 10; + } +#endif + + return sz; +} + MSGQContext::MSGQContext() { } @@ -49,13 +61,12 @@ MSGQMessage::~MSGQMessage() { this->close(); } - int MSGQSubSocket::connect(Context *context, std::string endpoint, std::string address, bool conflate){ assert(context); assert(address == "127.0.0.1"); q = new msgq_queue_t; - int r = msgq_new_queue(q, endpoint.c_str(), DEFAULT_SEGMENT_SIZE); + int r = msgq_new_queue(q, endpoint.c_str(), get_size(endpoint)); if (r != 0){ return r; } @@ -143,7 +154,7 @@ int MSGQPubSocket::connect(Context *context, std::string endpoint){ assert(context); q = new msgq_queue_t; - int r = msgq_new_queue(q, endpoint.c_str(), DEFAULT_SEGMENT_SIZE); + int r = msgq_new_queue(q, endpoint.c_str(), get_size(endpoint)); if (r != 0){ return r; } diff --git a/cereal/messaging/messaging.hpp b/cereal/messaging/messaging.hpp index fb0f96af4d0e12..9ade8bf2b4381b 100644 --- a/cereal/messaging/messaging.hpp +++ b/cereal/messaging/messaging.hpp @@ -6,6 +6,10 @@ #include #include "../gen/cpp/log.capnp.h" +#ifdef __APPLE__ +#define CLOCK_BOOTTIME CLOCK_MONOTONIC +#endif + #define MSG_MULTIPLE_PUBLISHERS 100 class Context { @@ -82,11 +86,34 @@ class SubMaster { std::map services_; }; +class MessageBuilder : public capnp::MallocMessageBuilder { +public: + MessageBuilder() = default; + + cereal::Event::Builder initEvent(bool valid = true) { + cereal::Event::Builder event = initRoot(); + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + uint64_t current_time = t.tv_sec * 1000000000ULL + t.tv_nsec; + event.setLogMonoTime(current_time); + event.setValid(valid); + return event; + } + + kj::ArrayPtr toBytes() { + heapArray_ = capnp::messageToFlatArray(*this); + return heapArray_.asBytes(); + } + +private: + kj::Array heapArray_; +}; + class PubMaster { public: PubMaster(const std::initializer_list &service_list); inline int send(const char *name, capnp::byte *data, size_t size) { return sockets_.at(name)->send((char *)data, size); } - int send(const char *name, capnp::MessageBuilder &msg); + int send(const char *name, MessageBuilder &msg); ~PubMaster(); private: diff --git a/cereal/messaging/messaging_pyx_setup.py b/cereal/messaging/messaging_pyx_setup.py index 992b39159975a8..8e67a104c8c0f3 100644 --- a/cereal/messaging/messaging_pyx_setup.py +++ b/cereal/messaging/messaging_pyx_setup.py @@ -6,6 +6,7 @@ from Cython.Build import cythonize from Cython.Distutils import build_ext +TICI = os.path.isfile('/TICI') def get_ext_filename_without_platform_suffix(filename): name, ext = os.path.splitext(filename) @@ -30,11 +31,11 @@ def get_ext_filename(self, ext_name): sourcefiles = ['messaging_pyx.pyx'] -extra_compile_args = ["-std=c++14"] +extra_compile_args = ["-std=c++14", "-Wno-nullability-completeness"] libraries = ['zmq'] ARCH = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() # pylint: disable=unexpected-keyword-arg -if ARCH == "aarch64" and os.path.isdir("/system"): +if ARCH == "aarch64" and not TICI: # android extra_compile_args += ["-Wno-deprecated-register"] libraries += ['gnustl_shared'] diff --git a/cereal/messaging/msgq.cc b/cereal/messaging/msgq.cc index 2630101685eba2..53bdb9af05ba52 100644 --- a/cereal/messaging/msgq.cc +++ b/cereal/messaging/msgq.cc @@ -21,6 +21,8 @@ #include +#include "services.h" + #include "msgq.hpp" void sigusr2_handler(int signal) { @@ -81,11 +83,20 @@ void msgq_wait_for_subscriber(msgq_queue_t *q){ return; } - +bool service_exists(std::string path){ + for (const auto& it : services) { + if (it.name == path) { + return true; + } + } + return false; +} int msgq_new_queue(msgq_queue_t * q, const char * path, size_t size){ assert(size < 0xFFFFFFFF); // Buffer must be smaller than 2^32 bytes - + if (!service_exists(std::string(path))){ + std::cout << "Warning, " << std::string(path) << " is not in service list." << std::endl; + } std::signal(SIGUSR2, sigusr2_handler); const char * prefix = "/dev/shm/"; @@ -102,15 +113,15 @@ int msgq_new_queue(msgq_queue_t * q, const char * path, size_t size){ delete[] full_path; int rc = ftruncate(fd, size + sizeof(msgq_header_t)); - if (rc < 0) + if (rc < 0){ return -1; - + } char * mem = (char*)mmap(NULL, size + sizeof(msgq_header_t), PROT_READ | PROT_WRITE, MAP_SHARED, fd, 0); close(fd); - if (mem == NULL) + if (mem == NULL){ return -1; - + } q->mmap_p = mem; msgq_header_t *header = (msgq_header_t *)mem; @@ -418,8 +429,6 @@ int msgq_msg_recv(msgq_msg_t * msg, msgq_queue_t * q){ int msgq_poll(msgq_pollitem_t * items, size_t nitems, int timeout){ - assert(timeout >= 0); - int num = 0; // Check if messages ready diff --git a/cereal/messaging/socketmaster.cc b/cereal/messaging/socketmaster.cc index a0f6c1ef4e031f..53821aa21fd039 100644 --- a/cereal/messaging/socketmaster.cc +++ b/cereal/messaging/socketmaster.cc @@ -3,10 +3,6 @@ #include "messaging.hpp" #include "services.h" -#ifdef __APPLE__ -#define CLOCK_BOOTTIME CLOCK_MONOTONIC -#endif - static inline uint64_t nanos_since_boot() { struct timespec t; clock_gettime(CLOCK_BOOTTIME, &t); @@ -164,9 +160,8 @@ PubMaster::PubMaster(const std::initializer_list &service_list) { } } -int PubMaster::send(const char *name, capnp::MessageBuilder &msg) { - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); +int PubMaster::send(const char *name, MessageBuilder &msg) { + auto bytes = msg.toBytes(); return send(name, bytes.begin(), bytes.size()); } diff --git a/cereal/service_list.yaml b/cereal/service_list.yaml index 490e903f112759..b140251cf8ca71 100644 --- a/cereal/service_list.yaml +++ b/cereal/service_list.yaml @@ -78,6 +78,8 @@ frontFrame: [8072, true, 10.] dMonitoringState: [8073, true, 5., 1] offroadLayout: [8074, false, 0.] wideEncodeIdx: [8075, true, 20.] +wideFrame: [8076, true, 20.] +modelV2: [8077, true, 20., 20] testModel: [8040, false, 0.] testLiveLocation: [8045, false, 0.] diff --git a/common/android.py b/common/android.py deleted file mode 100644 index 43bb0f3c1e5142..00000000000000 --- a/common/android.py +++ /dev/null @@ -1,286 +0,0 @@ -import os -import binascii -import itertools -import re -import struct -import subprocess -import random -from cereal import log - -NetworkType = log.ThermalData.NetworkType -NetworkStrength = log.ThermalData.NetworkStrength - -ANDROID = os.path.isfile('/EON') - -def get_sound_card_online(): - return (os.path.isfile('/proc/asound/card0/state') and - open('/proc/asound/card0/state').read().strip() == 'ONLINE') - -def getprop(key): - if not ANDROID: - return "" - return subprocess.check_output(["getprop", key], encoding='utf8').strip() - -def get_imei(slot): - slot = str(slot) - if slot not in ("0", "1"): - raise ValueError("SIM slot must be 0 or 1") - - ret = parse_service_call_string(service_call(["iphonesubinfo", "3" , "i32", str(slot)])) - if not ret: - # allow non android to be identified differently - ret = "%015d" % random.randint(0, 1 << 32) - return ret - -def get_serial(): - ret = getprop("ro.serialno") - if ret == "": - ret = "cccccccc" - return ret - -def get_subscriber_info(): - ret = parse_service_call_string(service_call(["iphonesubinfo", "7"])) - if ret is None or len(ret) < 8: - return "" - return ret - -def reboot(reason=None): - if reason is None: - reason_args = ["null"] - else: - reason_args = ["s16", reason] - - subprocess.check_output([ - "service", "call", "power", "16", # IPowerManager.reboot - "i32", "0", # no confirmation, - *reason_args, - "i32", "1" # wait - ]) - -def service_call(call): - if not ANDROID: - return None - - ret = subprocess.check_output(["service", "call", *call], encoding='utf8').strip() - if 'Parcel' not in ret: - return None - - return parse_service_call_bytes(ret) - -def parse_service_call_unpack(r, fmt): - try: - return struct.unpack(fmt, r)[0] - except Exception: - return None - -def parse_service_call_string(r): - try: - r = r[8:] # Cut off length field - r = r.decode('utf_16_be') - - # All pairs of two characters seem to be swapped. Not sure why - result = "" - for a, b, in itertools.zip_longest(r[::2], r[1::2], fillvalue='\x00'): - result += b + a - - result = result.replace('\x00', '') - - return result - except Exception: - return None - -def parse_service_call_bytes(ret): - try: - r = b"" - for hex_part in re.findall(r'[ (]([0-9a-f]{8})', ret): - r += binascii.unhexlify(hex_part) - return r - except Exception: - return None - -def get_network_type(): - if not ANDROID: - return NetworkType.none - - wifi_check = parse_service_call_string(service_call(["connectivity", "2"])) - if wifi_check is None: - return NetworkType.none - elif 'WIFI' in wifi_check: - return NetworkType.wifi - else: - cell_check = parse_service_call_unpack(service_call(['phone', '59']), ">q") - # from TelephonyManager.java - cell_networks = { - 0: NetworkType.none, - 1: NetworkType.cell2G, - 2: NetworkType.cell2G, - 3: NetworkType.cell3G, - 4: NetworkType.cell2G, - 5: NetworkType.cell3G, - 6: NetworkType.cell3G, - 7: NetworkType.cell3G, - 8: NetworkType.cell3G, - 9: NetworkType.cell3G, - 10: NetworkType.cell3G, - 11: NetworkType.cell2G, - 12: NetworkType.cell3G, - 13: NetworkType.cell4G, - 14: NetworkType.cell4G, - 15: NetworkType.cell3G, - 16: NetworkType.cell2G, - 17: NetworkType.cell3G, - 18: NetworkType.cell4G, - 19: NetworkType.cell4G - } - return cell_networks.get(cell_check, NetworkType.none) - -def get_network_strength(network_type): - network_strength = NetworkStrength.unknown - - # from SignalStrength.java - def get_lte_level(rsrp, rssnr): - INT_MAX = 2147483647 - if rsrp == INT_MAX: - lvl_rsrp = NetworkStrength.unknown - elif rsrp >= -95: - lvl_rsrp = NetworkStrength.great - elif rsrp >= -105: - lvl_rsrp = NetworkStrength.good - elif rsrp >= -115: - lvl_rsrp = NetworkStrength.moderate - else: - lvl_rsrp = NetworkStrength.poor - if rssnr == INT_MAX: - lvl_rssnr = NetworkStrength.unknown - elif rssnr >= 45: - lvl_rssnr = NetworkStrength.great - elif rssnr >= 10: - lvl_rssnr = NetworkStrength.good - elif rssnr >= -30: - lvl_rssnr = NetworkStrength.moderate - else: - lvl_rssnr = NetworkStrength.poor - return max(lvl_rsrp, lvl_rssnr) - - def get_tdscdma_level(tdscmadbm): - lvl = NetworkStrength.unknown - if tdscmadbm > -25: - lvl = NetworkStrength.unknown - elif tdscmadbm >= -49: - lvl = NetworkStrength.great - elif tdscmadbm >= -73: - lvl = NetworkStrength.good - elif tdscmadbm >= -97: - lvl = NetworkStrength.moderate - elif tdscmadbm >= -110: - lvl = NetworkStrength.poor - return lvl - - def get_gsm_level(asu): - if asu <= 2 or asu == 99: - lvl = NetworkStrength.unknown - elif asu >= 12: - lvl = NetworkStrength.great - elif asu >= 8: - lvl = NetworkStrength.good - elif asu >= 5: - lvl = NetworkStrength.moderate - else: - lvl = NetworkStrength.poor - return lvl - - def get_evdo_level(evdodbm, evdosnr): - lvl_evdodbm = NetworkStrength.unknown - lvl_evdosnr = NetworkStrength.unknown - if evdodbm >= -65: - lvl_evdodbm = NetworkStrength.great - elif evdodbm >= -75: - lvl_evdodbm = NetworkStrength.good - elif evdodbm >= -90: - lvl_evdodbm = NetworkStrength.moderate - elif evdodbm >= -105: - lvl_evdodbm = NetworkStrength.poor - if evdosnr >= 7: - lvl_evdosnr = NetworkStrength.great - elif evdosnr >= 5: - lvl_evdosnr = NetworkStrength.good - elif evdosnr >= 3: - lvl_evdosnr = NetworkStrength.moderate - elif evdosnr >= 1: - lvl_evdosnr = NetworkStrength.poor - return max(lvl_evdodbm, lvl_evdosnr) - - def get_cdma_level(cdmadbm, cdmaecio): - lvl_cdmadbm = NetworkStrength.unknown - lvl_cdmaecio = NetworkStrength.unknown - if cdmadbm >= -75: - lvl_cdmadbm = NetworkStrength.great - elif cdmadbm >= -85: - lvl_cdmadbm = NetworkStrength.good - elif cdmadbm >= -95: - lvl_cdmadbm = NetworkStrength.moderate - elif cdmadbm >= -100: - lvl_cdmadbm = NetworkStrength.poor - if cdmaecio >= -90: - lvl_cdmaecio = NetworkStrength.great - elif cdmaecio >= -110: - lvl_cdmaecio = NetworkStrength.good - elif cdmaecio >= -130: - lvl_cdmaecio = NetworkStrength.moderate - elif cdmaecio >= -150: - lvl_cdmaecio = NetworkStrength.poor - return max(lvl_cdmadbm, lvl_cdmaecio) - - if network_type == NetworkType.none: - return network_strength - if network_type == NetworkType.wifi: - out = subprocess.check_output('dumpsys connectivity', shell=True).decode('utf-8') - network_strength = NetworkStrength.unknown - for line in out.split('\n'): - signal_str = "SignalStrength: " - if signal_str in line: - lvl_idx_start = line.find(signal_str) + len(signal_str) - lvl_idx_end = line.find(']', lvl_idx_start) - lvl = int(line[lvl_idx_start : lvl_idx_end]) - if lvl >= -50: - network_strength = NetworkStrength.great - elif lvl >= -60: - network_strength = NetworkStrength.good - elif lvl >= -70: - network_strength = NetworkStrength.moderate - else: - network_strength = NetworkStrength.poor - return network_strength - else: - # check cell strength - out = subprocess.check_output('dumpsys telephony.registry', shell=True).decode('utf-8') - for line in out.split('\n'): - if "mSignalStrength" in line: - arr = line.split(' ') - ns = 0 - if ("gsm" in arr[14]): - rsrp = int(arr[9]) - rssnr = int(arr[11]) - ns = get_lte_level(rsrp, rssnr) - if ns == NetworkStrength.unknown: - tdscmadbm = int(arr[13]) - ns = get_tdscdma_level(tdscmadbm) - if ns == NetworkStrength.unknown: - asu = int(arr[1]) - ns = get_gsm_level(asu) - else: - cdmadbm = int(arr[3]) - cdmaecio = int(arr[4]) - evdodbm = int(arr[5]) - evdosnr = int(arr[7]) - lvl_cdma = get_cdma_level(cdmadbm, cdmaecio) - lvl_edmo = get_evdo_level(evdodbm, evdosnr) - if lvl_edmo == NetworkStrength.unknown: - ns = lvl_cdma - elif lvl_cdma == NetworkStrength.unknown: - ns = lvl_edmo - else: - ns = min(lvl_cdma, lvl_edmo) - network_strength = max(network_strength, ns) - - return network_strength diff --git a/common/basedir.py b/common/basedir.py index 4d62fdc19c65b5..d98509ed6de6df 100644 --- a/common/basedir.py +++ b/common/basedir.py @@ -1,10 +1,10 @@ import os BASEDIR = os.path.abspath(os.path.join(os.path.dirname(os.path.realpath(__file__)), "../")) -from common.android import ANDROID -if ANDROID: - PERSIST = "/persist" - PARAMS = "/data/params" -else: +from common.hardware import PC +if PC: PERSIST = os.path.join(BASEDIR, "persist") PARAMS = os.path.join(BASEDIR, "persist", "params") +else: + PERSIST = "/persist" + PARAMS = "/data/params" diff --git a/common/gpio.py b/common/gpio.py new file mode 100644 index 00000000000000..73603f262d1f4c --- /dev/null +++ b/common/gpio.py @@ -0,0 +1,22 @@ +GPIO_HUB_RST_N = 30 +GPIO_UBLOX_RST_N = 32 +GPIO_UBLOX_SAFEBOOT_N = 33 +GPIO_UBLOX_PWR_EN = 34 +GPIO_STM_RST_N = 124 +GPIO_STM_BOOT0 = 134 + + +def gpio_init(pin, output): + try: + with open(f"/sys/class/gpio/gpio{pin}/direction", 'wb') as f: + f.write(b"out" if output else b"in") + except Exception as e: + print(f"Failed to set gpio {pin} direction: {e}") + + +def gpio_set(pin, high): + try: + with open(f"/sys/class/gpio/gpio{pin}/value", 'wb') as f: + f.write(b"1" if high else b"0") + except Exception as e: + print(f"Failed to set gpio {pin} value: {e}") diff --git a/common/hardware.py b/common/hardware.py new file mode 100644 index 00000000000000..67d0c44d19c52b --- /dev/null +++ b/common/hardware.py @@ -0,0 +1,57 @@ +import os +import random +from typing import cast + +from cereal import log +from common.hardware_android import Android +from common.hardware_tici import Tici +from common.hardware_base import HardwareBase + +EON = os.path.isfile('/EON') +TICI = os.path.isfile('/TICI') +PC = not (EON or TICI) +ANDROID = EON + + +NetworkType = log.ThermalData.NetworkType +NetworkStrength = log.ThermalData.NetworkStrength + + +class Pc(HardwareBase): + def get_sound_card_online(self): + return True + + def get_imei(self, slot): + return "%015d" % random.randint(0, 1 << 32) + + def get_serial(self): + return "cccccccc" + + def get_subscriber_info(self): + return "" + + def reboot(self, reason=None): + print("REBOOT!") + + def get_network_type(self): + return NetworkType.wifi + + def get_sim_info(self): + return { + 'sim_id': '', + 'mcc_mnc': None, + 'network_type': ["Unknown"], + 'sim_state': ["ABSENT"], + 'data_connected': False + } + + def get_network_strength(self, network_type): + return NetworkStrength.unknown + + +if EON: + HARDWARE = cast(HardwareBase, Android()) +elif TICI: + HARDWARE = cast(HardwareBase, Tici()) +else: + HARDWARE = cast(HardwareBase, Pc()) diff --git a/common/hardware_android.py b/common/hardware_android.py new file mode 100644 index 00000000000000..91e1d1423e5f78 --- /dev/null +++ b/common/hardware_android.py @@ -0,0 +1,302 @@ +import binascii +import itertools +import os +import re +import struct +import subprocess + +from cereal import log +from common.hardware_base import HardwareBase + +NetworkType = log.ThermalData.NetworkType +NetworkStrength = log.ThermalData.NetworkStrength + + +def service_call(call): + try: + ret = subprocess.check_output(["service", "call", *call], encoding='utf8').strip() + if 'Parcel' not in ret: + return None + return parse_service_call_bytes(ret) + except subprocess.CalledProcessError: + return None + + +def parse_service_call_unpack(r, fmt): + try: + return struct.unpack(fmt, r)[0] + except Exception: + return None + + +def parse_service_call_string(r): + try: + r = r[8:] # Cut off length field + r = r.decode('utf_16_be') + + # All pairs of two characters seem to be swapped. Not sure why + result = "" + for a, b, in itertools.zip_longest(r[::2], r[1::2], fillvalue='\x00'): + result += b + a + + result = result.replace('\x00', '') + + return result + except Exception: + return None + + +def parse_service_call_bytes(ret): + try: + r = b"" + for hex_part in re.findall(r'[ (]([0-9a-f]{8})', ret): + r += binascii.unhexlify(hex_part) + return r + except Exception: + return None + + +def getprop(key): + return subprocess.check_output(["getprop", key], encoding='utf8').strip() + + +class Android(HardwareBase): + def get_sound_card_online(self): + return (os.path.isfile('/proc/asound/card0/state') and + open('/proc/asound/card0/state').read().strip() == 'ONLINE') + + def get_imei(self, slot): + slot = str(slot) + if slot not in ("0", "1"): + raise ValueError("SIM slot must be 0 or 1") + + return parse_service_call_string(service_call(["iphonesubinfo", "3", "i32", str(slot)])) + + def get_serial(self): + ret = getprop("ro.serialno") + if ret == "": + ret = "cccccccc" + return ret + + def get_subscriber_info(self): + ret = parse_service_call_string(service_call(["iphonesubinfo", "7"])) + if ret is None or len(ret) < 8: + return "" + return ret + + def reboot(self, reason=None): + # e.g. reason="recovery" to go into recover mode + if reason is None: + reason_args = ["null"] + else: + reason_args = ["s16", reason] + + subprocess.check_output([ + "service", "call", "power", "16", # IPowerManager.reboot + "i32", "0", # no confirmation, + *reason_args, + "i32", "1" # wait + ]) + + def get_sim_info(self): + # Used for athena + # TODO: build using methods from this class + sim_state = getprop("gsm.sim.state").split(",") + network_type = getprop("gsm.network.type").split(',') + mcc_mnc = getprop("gsm.sim.operator.numeric") or None + + sim_id = parse_service_call_string(service_call(['iphonesubinfo', '11'])) + cell_data_state = parse_service_call_unpack(service_call(['phone', '46']), ">q") + cell_data_connected = (cell_data_state == 2) + + return { + 'sim_id': sim_id, + 'mcc_mnc': mcc_mnc, + 'network_type': network_type, + 'sim_state': sim_state, + 'data_connected': cell_data_connected + } + + def get_network_type(self): + wifi_check = parse_service_call_string(service_call(["connectivity", "2"])) + if wifi_check is None: + return NetworkType.none + elif 'WIFI' in wifi_check: + return NetworkType.wifi + else: + cell_check = parse_service_call_unpack(service_call(['phone', '59']), ">q") + # from TelephonyManager.java + cell_networks = { + 0: NetworkType.none, + 1: NetworkType.cell2G, + 2: NetworkType.cell2G, + 3: NetworkType.cell3G, + 4: NetworkType.cell2G, + 5: NetworkType.cell3G, + 6: NetworkType.cell3G, + 7: NetworkType.cell3G, + 8: NetworkType.cell3G, + 9: NetworkType.cell3G, + 10: NetworkType.cell3G, + 11: NetworkType.cell2G, + 12: NetworkType.cell3G, + 13: NetworkType.cell4G, + 14: NetworkType.cell4G, + 15: NetworkType.cell3G, + 16: NetworkType.cell2G, + 17: NetworkType.cell3G, + 18: NetworkType.cell4G, + 19: NetworkType.cell4G + } + return cell_networks.get(cell_check, NetworkType.none) + + def get_network_strength(self, network_type): + network_strength = NetworkStrength.unknown + + # from SignalStrength.java + def get_lte_level(rsrp, rssnr): + INT_MAX = 2147483647 + if rsrp == INT_MAX: + lvl_rsrp = NetworkStrength.unknown + elif rsrp >= -95: + lvl_rsrp = NetworkStrength.great + elif rsrp >= -105: + lvl_rsrp = NetworkStrength.good + elif rsrp >= -115: + lvl_rsrp = NetworkStrength.moderate + else: + lvl_rsrp = NetworkStrength.poor + if rssnr == INT_MAX: + lvl_rssnr = NetworkStrength.unknown + elif rssnr >= 45: + lvl_rssnr = NetworkStrength.great + elif rssnr >= 10: + lvl_rssnr = NetworkStrength.good + elif rssnr >= -30: + lvl_rssnr = NetworkStrength.moderate + else: + lvl_rssnr = NetworkStrength.poor + return max(lvl_rsrp, lvl_rssnr) + + def get_tdscdma_level(tdscmadbm): + lvl = NetworkStrength.unknown + if tdscmadbm > -25: + lvl = NetworkStrength.unknown + elif tdscmadbm >= -49: + lvl = NetworkStrength.great + elif tdscmadbm >= -73: + lvl = NetworkStrength.good + elif tdscmadbm >= -97: + lvl = NetworkStrength.moderate + elif tdscmadbm >= -110: + lvl = NetworkStrength.poor + return lvl + + def get_gsm_level(asu): + if asu <= 2 or asu == 99: + lvl = NetworkStrength.unknown + elif asu >= 12: + lvl = NetworkStrength.great + elif asu >= 8: + lvl = NetworkStrength.good + elif asu >= 5: + lvl = NetworkStrength.moderate + else: + lvl = NetworkStrength.poor + return lvl + + def get_evdo_level(evdodbm, evdosnr): + lvl_evdodbm = NetworkStrength.unknown + lvl_evdosnr = NetworkStrength.unknown + if evdodbm >= -65: + lvl_evdodbm = NetworkStrength.great + elif evdodbm >= -75: + lvl_evdodbm = NetworkStrength.good + elif evdodbm >= -90: + lvl_evdodbm = NetworkStrength.moderate + elif evdodbm >= -105: + lvl_evdodbm = NetworkStrength.poor + if evdosnr >= 7: + lvl_evdosnr = NetworkStrength.great + elif evdosnr >= 5: + lvl_evdosnr = NetworkStrength.good + elif evdosnr >= 3: + lvl_evdosnr = NetworkStrength.moderate + elif evdosnr >= 1: + lvl_evdosnr = NetworkStrength.poor + return max(lvl_evdodbm, lvl_evdosnr) + + def get_cdma_level(cdmadbm, cdmaecio): + lvl_cdmadbm = NetworkStrength.unknown + lvl_cdmaecio = NetworkStrength.unknown + if cdmadbm >= -75: + lvl_cdmadbm = NetworkStrength.great + elif cdmadbm >= -85: + lvl_cdmadbm = NetworkStrength.good + elif cdmadbm >= -95: + lvl_cdmadbm = NetworkStrength.moderate + elif cdmadbm >= -100: + lvl_cdmadbm = NetworkStrength.poor + if cdmaecio >= -90: + lvl_cdmaecio = NetworkStrength.great + elif cdmaecio >= -110: + lvl_cdmaecio = NetworkStrength.good + elif cdmaecio >= -130: + lvl_cdmaecio = NetworkStrength.moderate + elif cdmaecio >= -150: + lvl_cdmaecio = NetworkStrength.poor + return max(lvl_cdmadbm, lvl_cdmaecio) + + if network_type == NetworkType.none: + return network_strength + if network_type == NetworkType.wifi: + out = subprocess.check_output('dumpsys connectivity', shell=True).decode('utf-8') + network_strength = NetworkStrength.unknown + for line in out.split('\n'): + signal_str = "SignalStrength: " + if signal_str in line: + lvl_idx_start = line.find(signal_str) + len(signal_str) + lvl_idx_end = line.find(']', lvl_idx_start) + lvl = int(line[lvl_idx_start : lvl_idx_end]) + if lvl >= -50: + network_strength = NetworkStrength.great + elif lvl >= -60: + network_strength = NetworkStrength.good + elif lvl >= -70: + network_strength = NetworkStrength.moderate + else: + network_strength = NetworkStrength.poor + return network_strength + else: + # check cell strength + out = subprocess.check_output('dumpsys telephony.registry', shell=True).decode('utf-8') + for line in out.split('\n'): + if "mSignalStrength" in line: + arr = line.split(' ') + ns = 0 + if ("gsm" in arr[14]): + rsrp = int(arr[9]) + rssnr = int(arr[11]) + ns = get_lte_level(rsrp, rssnr) + if ns == NetworkStrength.unknown: + tdscmadbm = int(arr[13]) + ns = get_tdscdma_level(tdscmadbm) + if ns == NetworkStrength.unknown: + asu = int(arr[1]) + ns = get_gsm_level(asu) + else: + cdmadbm = int(arr[3]) + cdmaecio = int(arr[4]) + evdodbm = int(arr[5]) + evdosnr = int(arr[7]) + lvl_cdma = get_cdma_level(cdmadbm, cdmaecio) + lvl_edmo = get_evdo_level(evdodbm, evdosnr) + if lvl_edmo == NetworkStrength.unknown: + ns = lvl_cdma + elif lvl_cdma == NetworkStrength.unknown: + ns = lvl_edmo + else: + ns = min(lvl_cdma, lvl_edmo) + network_strength = max(network_strength, ns) + + return network_strength diff --git a/common/hardware_base.py b/common/hardware_base.py new file mode 100644 index 00000000000000..24bb52a5e668c0 --- /dev/null +++ b/common/hardware_base.py @@ -0,0 +1,41 @@ +from abc import abstractmethod + + +class HardwareBase: + @staticmethod + def get_cmdline(): + with open('/proc/cmdline') as f: + cmdline = f.read() + return {kv[0]: kv[1] for kv in [s.split('=') for s in cmdline.split(' ')] if len(kv) == 2} + + @abstractmethod + def get_sound_card_online(self): + pass + + @abstractmethod + def get_imei(self, slot): + pass + + @abstractmethod + def get_serial(self): + pass + + @abstractmethod + def get_subscriber_info(self): + pass + + @abstractmethod + def reboot(self, reason=None): + pass + + @abstractmethod + def get_network_type(self): + pass + + @abstractmethod + def get_sim_info(self): + pass + + @abstractmethod + def get_network_strength(self, network_type): + pass diff --git a/common/hardware_tici.py b/common/hardware_tici.py new file mode 100644 index 00000000000000..223bfc1ccc6bfe --- /dev/null +++ b/common/hardware_tici.py @@ -0,0 +1,58 @@ +import serial + +from common.hardware_base import HardwareBase +from cereal import log + + +NetworkType = log.ThermalData.NetworkType +NetworkStrength = log.ThermalData.NetworkStrength + + +def run_at_command(cmd, timeout=0.1): + with serial.Serial("/dev/ttyUSB2", timeout=timeout) as ser: + ser.write(cmd + b"\r\n") + ser.readline() # Modem echos request + return ser.readline().decode().rstrip() + + +class Tici(HardwareBase): + def get_sound_card_online(self): + return True + + def get_imei(self, slot): + if slot != 0: + return "" + + for _ in range(10): + try: + imei = run_at_command(b"AT+CGSN") + if len(imei) == 15: + return imei + except serial.SerialException: + pass + + raise RuntimeError("Error getting IMEI") + + def get_serial(self): + return self.get_cmdline()['androidboot.serialno'] + + def get_subscriber_info(self): + return "" + + def reboot(self, reason=None): + print("REBOOT!") + + def get_network_type(self): + return NetworkType.wifi + + def get_sim_info(self): + return { + 'sim_id': '', + 'mcc_mnc': None, + 'network_type': ["Unknown"], + 'sim_state': ["ABSENT"], + 'data_connected': False + } + + def get_network_strength(self, network_type): + return NetworkStrength.unknown diff --git a/common/params.py b/common/params.py index e1067050228452..d30f2d0df5717a 100755 --- a/common/params.py +++ b/common/params.py @@ -53,12 +53,12 @@ class UnknownKeyName(Exception): "AccessToken": [TxType.CLEAR_ON_MANAGER_START], "AthenadPid": [TxType.PERSISTENT], "CalibrationParams": [TxType.PERSISTENT], + "CarBatteryCapacity": [TxType.PERSISTENT], "CarParams": [TxType.CLEAR_ON_MANAGER_START, TxType.CLEAR_ON_PANDA_DISCONNECT], "CarParamsCache": [TxType.CLEAR_ON_MANAGER_START, TxType.CLEAR_ON_PANDA_DISCONNECT], "CarVin": [TxType.CLEAR_ON_MANAGER_START, TxType.CLEAR_ON_PANDA_DISCONNECT], "CommunityFeaturesToggle": [TxType.PERSISTENT], "CompletedTrainingVersion": [TxType.PERSISTENT], - "ControlsParams": [TxType.PERSISTENT], "DisablePowerDown": [TxType.PERSISTENT], "DisableUpdates": [TxType.PERSISTENT], "DoUninstall": [TxType.CLEAR_ON_MANAGER_START], @@ -71,7 +71,6 @@ class UnknownKeyName(Exception): "HasCompletedSetup": [TxType.PERSISTENT], "IsDriverViewEnabled": [TxType.CLEAR_ON_MANAGER_START], "IsLdwEnabled": [TxType.PERSISTENT], - "IsGeofenceEnabled": [TxType.PERSISTENT], "IsMetric": [TxType.PERSISTENT], "IsOffroad": [TxType.CLEAR_ON_MANAGER_START], "IsRHD": [TxType.PERSISTENT], @@ -81,10 +80,7 @@ class UnknownKeyName(Exception): "LastAthenaPingTime": [TxType.PERSISTENT], "LastUpdateTime": [TxType.PERSISTENT], "LastUpdateException": [TxType.PERSISTENT], - "LimitSetSpeed": [TxType.PERSISTENT], - "LimitSetSpeedNeural": [TxType.PERSISTENT], "LiveParameters": [TxType.PERSISTENT], - "LongitudinalControl": [TxType.PERSISTENT], "OpenpilotEnabledToggle": [TxType.PERSISTENT], "LaneChangeEnabled": [TxType.PERSISTENT], "PandaFirmware": [TxType.CLEAR_ON_MANAGER_START, TxType.CLEAR_ON_PANDA_DISCONNECT], @@ -94,7 +90,6 @@ class UnknownKeyName(Exception): "RecordFront": [TxType.PERSISTENT], "ReleaseNotes": [TxType.PERSISTENT], "ShouldDoUpdate": [TxType.CLEAR_ON_MANAGER_START], - "SpeedLimitOffset": [TxType.PERSISTENT], "SubscriberInfo": [TxType.PERSISTENT], "TermsVersion": [TxType.PERSISTENT], "TrainingVersion": [TxType.PERSISTENT], @@ -122,14 +117,15 @@ def fsync_dir(path): class FileLock(): - def __init__(self, path, create): + def __init__(self, path, create, lock_ex): self._path = path self._create = create self._fd = None + self._lock_ex = lock_ex def acquire(self): self._fd = os.open(self._path, os.O_CREAT if self._create else 0) - fcntl.flock(self._fd, fcntl.LOCK_EX) + fcntl.flock(self._fd, fcntl.LOCK_EX if self._lock_ex else fcntl.LOCK_SH) def release(self): if self._fd is not None: @@ -157,8 +153,8 @@ def get(self, key): except KeyError: return None - def _get_lock(self, create): - lock = FileLock(os.path.join(self._path, ".lock"), create) + def _get_lock(self, create, lock_ex): + lock = FileLock(os.path.join(self._path, ".lock"), create, lock_ex) lock.acquire() return lock @@ -190,7 +186,7 @@ def _check_entered(self): class DBReader(DBAccessor): def __enter__(self): try: - lock = self._get_lock(False) + lock = self._get_lock(False, False) except OSError as e: # Do not create lock if it does not exist. if e.errno == errno.ENOENT: @@ -228,7 +224,7 @@ def __enter__(self): try: os.chmod(self._path, 0o777) - self._lock = self._get_lock(True) + self._lock = self._get_lock(True, True) self._vals = self._read_values_locked() except Exception: os.umask(self._prev_umask) @@ -317,7 +313,7 @@ def write_db(params_path, key, value): value = value.encode('utf8') prev_umask = os.umask(0) - lock = FileLock(params_path + "/.lock", True) + lock = FileLock(params_path + "/.lock", True, True) lock.acquire() try: diff --git a/common/realtime.py b/common/realtime.py index e7344386469dc7..7f4ad5c0d69ab2 100644 --- a/common/realtime.py +++ b/common/realtime.py @@ -1,12 +1,10 @@ """Utilities for reading real time clocks and keeping soft real time constraints.""" +import gc import os import time -import platform -import subprocess import multiprocessing -from cffi import FFI -from common.android import ANDROID +from common.hardware import PC from common.common_pyx import sec_since_boot # pylint: disable=no-name-in-module, import-error @@ -17,37 +15,26 @@ DT_TRML = 0.5 # thermald and manager -ffi = FFI() -ffi.cdef("long syscall(long number, ...);") -libc = ffi.dlopen(None) - -def _get_tid(): - if platform.machine() == "x86_64": - NR_gettid = 186 - elif platform.machine() == "aarch64": - NR_gettid = 178 - else: - raise NotImplementedError - - return libc.syscall(NR_gettid) +class Priority: + MIN_REALTIME = 52 # highest android process priority is 51 + CTRL_LOW = MIN_REALTIME + CTRL_HIGH = MIN_REALTIME + 1 def set_realtime_priority(level): - if os.getuid() != 0: - print("not setting priority, not root") - return + if not PC: + os.sched_setscheduler(0, os.SCHED_FIFO, os.sched_param(level)) - return subprocess.call(['chrt', '-f', '-p', str(level), str(_get_tid())]) def set_core_affinity(core): - if os.getuid() != 0: - print("not setting affinity, not root") - return - - if ANDROID: - return subprocess.call(['taskset', '-p', str(core), str(_get_tid())]) - else: - return -1 + if not PC: + os.sched_setaffinity(0, [core,]) + + +def config_rt_process(core, priority): + gc.disable() + set_realtime_priority(priority) + set_core_affinity(core) class Ratekeeper(): diff --git a/common/text_window.py b/common/text_window.py index b815d8022a5b6a..1aa3b885ea2298 100755 --- a/common/text_window.py +++ b/common/text_window.py @@ -5,7 +5,7 @@ from common.basedir import BASEDIR -class TextWindow(): +class TextWindow: def __init__(self, s, noop=False): # text window is only implemented for android currently self.text_proc = None diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index af5483562d652a..7124ef3c4f4e42 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -8,6 +8,60 @@ source "$BASEDIR/launch_env.sh" DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" +function two_init { + # Restrict Android and other system processes to the first two cores + echo 0-1 > /dev/cpuset/background/cpus + echo 0-1 > /dev/cpuset/system-background/cpus + echo 0-1 > /dev/cpuset/foreground/boost/cpus + echo 0-1 > /dev/cpuset/foreground/cpus + echo 0-1 > /dev/cpuset/android/cpus + + # openpilot gets all the cores + echo 0-3 > /dev/cpuset/app/cpus + + # Collect RIL and other possibly long-running I/O interrupts onto CPU 1 + echo 1 > /proc/irq/78/smp_affinity_list # qcom,smd-modem (LTE radio) + echo 1 > /proc/irq/33/smp_affinity_list # ufshcd (flash storage) + echo 1 > /proc/irq/35/smp_affinity_list # wifi (wlan_pci) + # USB traffic needs realtime handling on cpu 3 + [ -d "/proc/irq/733" ] && echo 3 > /proc/irq/733/smp_affinity_list # USB for LeEco + [ -d "/proc/irq/736" ] && echo 3 > /proc/irq/736/smp_affinity_list # USB for OP3T + + + # Check for NEOS update + if [ $(< /VERSION) != "$REQUIRED_NEOS_VERSION" ]; then + if [ -f "$DIR/scripts/continue.sh" ]; then + cp "$DIR/scripts/continue.sh" "/data/data/com.termux/files/continue.sh" + fi + + if [ ! -f "$BASEDIR/prebuilt" ]; then + # Clean old build products, but preserve the scons cache + cd $DIR + scons --clean + git clean -xdf + git submodule foreach --recursive git clean -xdf + fi + + "$DIR/installer/updater/updater" "file://$DIR/installer/updater/update.json" + else + if [[ $(uname -v) == "#1 SMP PREEMPT Wed Jun 10 12:40:53 PDT 2020" ]]; then + "$DIR/installer/updater/updater" "file://$DIR/installer/updater/update_kernel.json" + fi + fi + + # One-time fix for a subset of OP3T with gyro orientation offsets. + # Remove and regenerate qcom sensor registry. Only done on OP3T mainboards. + # Performed exactly once. The old registry is preserved just-in-case, and + # doubles as a flag denoting we've already done the reset. + if ! $(grep -q "letv" /proc/cmdline) && [ ! -f "/persist/comma/op3t-sns-reg-backup" ]; then + echo "Performing OP3T sensor registry reset" + mv /persist/sensors/sns.reg /persist/comma/op3t-sns-reg-backup && + rm -f /persist/sensors/sensors_settings /persist/sensors/error_log /persist/sensors/gyro_sensitity_cal && + echo "restart" > /sys/kernel/debug/msm_subsys/slpi && + sleep 5 # Give Android sensor subsystem a moment to recover + fi +} + function launch { # Wifi scan wpa_cli IFNAME=wlan0 SCAN @@ -54,56 +108,9 @@ function launch { fi fi - # Android and other system processes are not permitted to run on CPU 3 - # NEOS installed app processes can run anywhere - echo 0-2 > /dev/cpuset/background/cpus - echo 0-2 > /dev/cpuset/system-background/cpus - [ -d "/dev/cpuset/foreground/boost/cpus" ] && echo 0-2 > /dev/cpuset/foreground/boost/cpus # Not present in < NEOS 15 - echo 0-2 > /dev/cpuset/foreground/cpus - echo 0-2 > /dev/cpuset/android/cpus - echo 0-3 > /dev/cpuset/app/cpus - - # Collect RIL and other possibly long-running I/O interrupts onto CPU 1 - echo 1 > /proc/irq/78/smp_affinity_list # qcom,smd-modem (LTE radio) - echo 1 > /proc/irq/33/smp_affinity_list # ufshcd (flash storage) - echo 1 > /proc/irq/35/smp_affinity_list # wifi (wlan_pci) - # USB traffic needs realtime handling on cpu 3 - [ -d "/proc/irq/733" ] && echo 3 > /proc/irq/733/smp_affinity_list # USB for LeEco - [ -d "/proc/irq/736" ] && echo 3 > /proc/irq/736/smp_affinity_list # USB for OP3T - - - # Check for NEOS update - if [ $(< /VERSION) != "$REQUIRED_NEOS_VERSION" ]; then - if [ -f "$DIR/scripts/continue.sh" ]; then - cp "$DIR/scripts/continue.sh" "/data/data/com.termux/files/continue.sh" - fi - - if [ ! -f "$BASEDIR/prebuilt" ]; then - # Clean old build products, but preserve the scons cache - cd $DIR - scons --clean - git clean -xdf - git submodule foreach --recursive git clean -xdf - fi - - "$DIR/installer/updater/updater" "file://$DIR/installer/updater/update.json" - else - if [[ $(uname -v) == "#1 SMP PREEMPT Wed Jun 10 12:40:53 PDT 2020" ]]; then - "$DIR/installer/updater/updater" "file://$DIR/installer/updater/update_kernel.json" - fi - fi - - # One-time fix for a subset of OP3T with gyro orientation offsets. - # Remove and regenerate qcom sensor registry. Only done on OP3T mainboards. - # Performed exactly once. The old registry is preserved just-in-case, and - # doubles as a flag denoting we've already done the reset. - # TODO: we should really grow per-platform detect and setup routines - if ! $(grep -q "letv" /proc/cmdline) && [ ! -f "/persist/comma/op3t-sns-reg-backup" ]; then - echo "Performing OP3T sensor registry reset" - mv /persist/sensors/sns.reg /persist/comma/op3t-sns-reg-backup && - rm -f /persist/sensors/sensors_settings /persist/sensors/error_log /persist/sensors/gyro_sensitity_cal && - echo "restart" > /sys/kernel/debug/msm_subsys/slpi && - sleep 5 # Give Android sensor subsystem a moment to recover + # comma two init + if [ -f /EON ]; then + two_init fi # handle pythonpath diff --git a/opendbc/can/common_pyx_setup.py b/opendbc/can/common_pyx_setup.py index 72a0cde7c1eced..04f95359ae479f 100644 --- a/opendbc/can/common_pyx_setup.py +++ b/opendbc/can/common_pyx_setup.py @@ -34,7 +34,7 @@ def get_ext_filename(self, ext_name): return get_ext_filename_without_platform_suffix(filename) -extra_compile_args = ["-std=c++14"] +extra_compile_args = ["-std=c++14", "-Wno-nullability-completeness"] ARCH = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() # pylint: disable=unexpected-keyword-arg if ARCH == "aarch64": extra_compile_args += ["-Wno-deprecated-register"] diff --git a/opendbc/can/packer_pyx.pyx b/opendbc/can/packer_pyx.pyx index 00f83eca65ff84..14e2f81d309fba 100644 --- a/opendbc/can/packer_pyx.pyx +++ b/opendbc/can/packer_pyx.pyx @@ -20,9 +20,11 @@ cdef class CANPacker: map[int, int] address_to_size def __init__(self, dbc_name): - self.packer = new cpp_CANPacker(dbc_name) self.dbc = dbc_lookup(dbc_name) - + if not self.dbc: + raise RuntimeError("Can't lookup" + dbc_name) + + self.packer = new cpp_CANPacker(dbc_name) num_msgs = self.dbc[0].num_msgs for i in range(num_msgs): msg = self.dbc[0].msgs[i] @@ -37,7 +39,7 @@ cdef class CANPacker: for name, value in values.iteritems(): n = name.encode('utf8') - names.append(n) # TODO: find better way to keep reference to temp string arround + names.append(n) # TODO: find better way to keep reference to temp string around spv.name = n spv.value = value diff --git a/opendbc/can/parser.cc b/opendbc/can/parser.cc index 5addd4168176e6..c6d85d9eed965a 100644 --- a/opendbc/can/parser.cc +++ b/opendbc/can/parser.cc @@ -187,7 +187,7 @@ void CANParser::UpdateCans(uint64_t sec, const capnp::List::Rea continue; } - if (cmsg.getDat().size() > 8) continue; //shouldnt ever happen + if (cmsg.getDat().size() > 8) continue; //shouldn't ever happen uint8_t dat[8] = {0}; memcpy(dat, cmsg.getDat().begin(), cmsg.getDat().size()); diff --git a/opendbc/can/parser.py b/opendbc/can/parser.py index 107a839b107df0..04722115ce75f8 100644 --- a/opendbc/can/parser.py +++ b/opendbc/can/parser.py @@ -1,2 +1,2 @@ -from opendbc.can.parser_pyx import CANParser # pylint: disable=no-name-in-module, import-error -assert CANParser +from opendbc.can.parser_pyx import CANParser, CANDefine # pylint: disable=no-name-in-module, import-error +assert CANParser, CANDefine diff --git a/opendbc/can/parser_pyx.pyx b/opendbc/can/parser_pyx.pyx index bd5adf6ffed131..913f5823088c30 100644 --- a/opendbc/can/parser_pyx.pyx +++ b/opendbc/can/parser_pyx.pyx @@ -17,7 +17,6 @@ from collections import defaultdict cdef int CAN_INVALID_CNT = 5 - cdef class CANParser: cdef: cpp_CANParser *can @@ -37,10 +36,11 @@ cdef class CANParser: def __init__(self, dbc_name, signals, checks=None, bus=0): if checks is None: checks = [] - self.can_valid = True self.dbc_name = dbc_name self.dbc = dbc_lookup(dbc_name) + if not self.dbc: + raise RuntimeError("Can't lookup" + dbc_name) self.vl = {} self.ts = {} @@ -110,7 +110,7 @@ cdef class CANParser: for cv in can_values: - # Cast char * directly to unicde + # Cast char * directly to unicode name = self.address_to_msg_name[cv.address].c_str() cv_name = cv.name @@ -148,7 +148,9 @@ cdef class CANDefine(): def __init__(self, dbc_name): self.dbc_name = dbc_name self.dbc = dbc_lookup(dbc_name) - + if not self.dbc: + raise RuntimeError("Can't lookup" + dbc_name) + num_vals = self.dbc[0].num_vals address_to_msg_name = {} diff --git a/opendbc/can/process_dbc.py b/opendbc/can/process_dbc.py index 5564021afe0b65..9025331dd48ccb 100755 --- a/opendbc/can/process_dbc.py +++ b/opendbc/can/process_dbc.py @@ -81,7 +81,7 @@ def process(in_fn, out_fn): if sig.start_bit % 8 != checksum_start_bit: sys.exit("%s: CHECKSUM starts at wrong bit" % dbc_msg_name) if little_endian != sig.is_little_endian: - sys.exit("%s: CHECKSUM has wrong endianess" % dbc_msg_name) + sys.exit("%s: CHECKSUM has wrong endianness" % dbc_msg_name) # counter rules if sig.name == "COUNTER": if counter_size is not None and sig.size != counter_size: @@ -90,7 +90,7 @@ def process(in_fn, out_fn): print(counter_start_bit, sig.start_bit) sys.exit("%s: COUNTER starts at wrong bit" % dbc_msg_name) if little_endian != sig.is_little_endian: - sys.exit("%s: COUNTER has wrong endianess" % dbc_msg_name) + sys.exit("%s: COUNTER has wrong endianness" % dbc_msg_name) # pedal rules if address in [0x200, 0x201]: if sig.name == "COUNTER_PEDAL" and sig.size != 4: diff --git a/opendbc/chrysler_pacifica_2017_hybrid.dbc b/opendbc/chrysler_pacifica_2017_hybrid.dbc index 4bd919655b20af..54e4819f23b316 100644 --- a/opendbc/chrysler_pacifica_2017_hybrid.dbc +++ b/opendbc/chrysler_pacifica_2017_hybrid.dbc @@ -409,7 +409,7 @@ CM_ SG_ 571 CHECKSUM "standard checksum"; CM_ SG_ 825 BEEP_339 "sent every 0.5s. 0050 is no beep. To beep send 4355 or 4155. Used by ParkSense warning."; CM_ SG_ 270 ELECTRIC_MOTOR "0x7fff indicates electric motor not in use"; CM_ SG_ 291 ENERGY_GAIN_LOSS "unsure what this actually is"; -CM_ SG_ 291 ENERGY_SMOOTHER_CURVE "unusre what it is, but smoother"; +CM_ SG_ 291 ENERGY_SMOOTHER_CURVE "unsure what it is, but smoother"; CM_ SG_ 308 ACCEL_134 "only set when human presses accel pedal"; CM_ SG_ 532 NOISY_SLOWLY_DECREASING "perhaps battery but do not know"; CM_ SG_ 816 TRACTION_OFF "set when traction off button is enabled"; diff --git a/opendbc/gm_global_a_object.dbc b/opendbc/gm_global_a_object.dbc index 1532e90dadac90..4643a640ac85f4 100644 --- a/opendbc/gm_global_a_object.dbc +++ b/opendbc/gm_global_a_object.dbc @@ -37,7 +37,7 @@ BU_: K109_FCM B233B_LRR NEO VIS_FO VIS2_FO K124_ASCM Vector__XXX EOCM_F_FO EOCM2 VAL_TABLE_ RangeMode 1 "Active" 0 "Inactive" ; VAL_TABLE_ TrkConf 3 "Confident" 2 "Speculative" 1 "Highly speculative" 0 "Invalid" ; VAL_TABLE_ TrkMeasStatus 3 "Measured current cycle" 2 "Latent track not detected" 1 "New object" 0 "No object" ; -VAL_TABLE_ TrkDynProp 4 "Moving in opposite direction" 3 "Moving in same direction" 2 "Has moved but currenty stopped" 1 "Has never moved," 0 "Unkown" ; +VAL_TABLE_ TrkDynProp 4 "Moving in opposite direction" 3 "Moving in same direction" 2 "Has moved but currently stopped" 1 "Has never moved," 0 "Unknown" ; VAL_TABLE_ FrntVsnInPthVehBrkNwSt 10 "Active" 5 "Inactive" ; VAL_TABLE_ FrntVsnClostPedBrkNwSt 10 "Active" 5 "Inactive" ; VAL_TABLE_ LaneSnsLLnPosValid 1 "Invalid" 0 "Valid" ; diff --git a/opendbc/lexus_ct200h_2018_pt_generated.dbc b/opendbc/lexus_ct200h_2018_pt_generated.dbc index 72ce7b1c66a20c..6cc7eba4191b03 100644 --- a/opendbc/lexus_ct200h_2018_pt_generated.dbc +++ b/opendbc/lexus_ct200h_2018_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/lexus_is_2018_pt_generated.dbc b/opendbc/lexus_is_2018_pt_generated.dbc index c08b1fee62a160..e1e009ef0ad5a5 100644 --- a/opendbc/lexus_is_2018_pt_generated.dbc +++ b/opendbc/lexus_is_2018_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/lexus_nx300h_2018_pt_generated.dbc b/opendbc/lexus_nx300h_2018_pt_generated.dbc index 278bb2a2f1309e..7e422ad2a64e28 100644 --- a/opendbc/lexus_nx300h_2018_pt_generated.dbc +++ b/opendbc/lexus_nx300h_2018_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/lexus_rx_350_2016_pt_generated.dbc b/opendbc/lexus_rx_350_2016_pt_generated.dbc index 55b268be843ed4..c8bb8c3872aec6 100644 --- a/opendbc/lexus_rx_350_2016_pt_generated.dbc +++ b/opendbc/lexus_rx_350_2016_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc index c353ab475208c3..4fe9f00aa9f683 100644 --- a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc +++ b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/toyota_avalon_2017_pt_generated.dbc b/opendbc/toyota_avalon_2017_pt_generated.dbc index d6f546e3bc2eb0..295bb102f6bfac 100644 --- a/opendbc/toyota_avalon_2017_pt_generated.dbc +++ b/opendbc/toyota_avalon_2017_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc index 393a47828fb4a1..56fb32ff6cef37 100644 --- a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc +++ b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/toyota_corolla_2017_pt_generated.dbc b/opendbc/toyota_corolla_2017_pt_generated.dbc index 70be61d02f7f96..7ad41ef3a5c40b 100644 --- a/opendbc/toyota_corolla_2017_pt_generated.dbc +++ b/opendbc/toyota_corolla_2017_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; @@ -375,7 +375,7 @@ BO_ 705 GAS_PEDAL: 8 XXX SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (1.0,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.88,0) [-20000|20000] "" XXX SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX diff --git a/opendbc/toyota_highlander_2017_pt_generated.dbc b/opendbc/toyota_highlander_2017_pt_generated.dbc index 4c7d18386fc7f8..8db51ffdb1e52b 100644 --- a/opendbc/toyota_highlander_2017_pt_generated.dbc +++ b/opendbc/toyota_highlander_2017_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc index ccaf677911e521..b9dd821efe08eb 100644 --- a/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc +++ b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/toyota_nodsu_hybrid_pt_generated.dbc b/opendbc/toyota_nodsu_hybrid_pt_generated.dbc index 09fe04b3415a0b..0569da07044d92 100644 --- a/opendbc/toyota_nodsu_hybrid_pt_generated.dbc +++ b/opendbc/toyota_nodsu_hybrid_pt_generated.dbc @@ -328,7 +328,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/toyota_nodsu_pt_generated.dbc b/opendbc/toyota_nodsu_pt_generated.dbc index e6f4a530533d4f..ce38bf50a5884f 100644 --- a/opendbc/toyota_nodsu_pt_generated.dbc +++ b/opendbc/toyota_nodsu_pt_generated.dbc @@ -328,7 +328,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/toyota_prius_2017_pt_generated.dbc b/opendbc/toyota_prius_2017_pt_generated.dbc index 419a88bb98591f..aef24541c74f68 100644 --- a/opendbc/toyota_prius_2017_pt_generated.dbc +++ b/opendbc/toyota_prius_2017_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/toyota_rav4_2017_pt_generated.dbc b/opendbc/toyota_rav4_2017_pt_generated.dbc index 2b7e38b720f8e1..ece2f15ee2b247 100644 --- a/opendbc/toyota_rav4_2017_pt_generated.dbc +++ b/opendbc/toyota_rav4_2017_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc index ae1985f6c51126..4822e1260c196e 100644 --- a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc +++ b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/opendbc/toyota_sienna_xle_2018_pt_generated.dbc b/opendbc/toyota_sienna_xle_2018_pt_generated.dbc index da5337fefd8b65..49735696f60adb 100644 --- a/opendbc/toyota_sienna_xle_2018_pt_generated.dbc +++ b/opendbc/toyota_sienna_xle_2018_pt_generated.dbc @@ -311,7 +311,7 @@ CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; diff --git a/panda/__init__.py b/panda/__init__.py index deeea46eb5e773..09466ddd579f72 100644 --- a/panda/__init__.py +++ b/panda/__init__.py @@ -1,3 +1,3 @@ # flake8: noqa # pylint: skip-file -from .python import Panda, PandaWifiStreaming, PandaDFU, ESPROM, CesantaFlasher, flash_release, BASEDIR, ensure_st_up_to_date, build_st, PandaSerial +from .python import Panda, PandaWifiStreaming, PandaDFU, flash_release, BASEDIR, ensure_st_up_to_date, build_st, PandaSerial diff --git a/panda/board/board.h b/panda/board/board.h index 84fca5469250cb..19392c9eaa2dc6 100644 --- a/panda/board/board.h +++ b/panda/board/board.h @@ -9,6 +9,7 @@ #ifdef PANDA #include "drivers/fan.h" #include "drivers/rtc.h" + #include "drivers/clock_source.h" #include "boards/white.h" #include "boards/grey.h" #include "boards/black.h" @@ -23,7 +24,7 @@ void detect_board_type(void) { // SPI lines floating: white (TODO: is this reliable? Not really, we have to enable ESP/GPS to be able to detect this on the UART) set_gpio_output(GPIOC, 14, 1); set_gpio_output(GPIOC, 5, 1); - if(!detect_with_pull(GPIOB, 1, PULL_UP) && detect_with_pull(GPIOB, 15, PULL_UP)){ + if(!detect_with_pull(GPIOB, 1, PULL_UP) && !detect_with_pull(GPIOB, 7, PULL_UP)){ hw_type = HW_TYPE_DOS; current_board = &board_dos; } else if((detect_with_pull(GPIOA, 4, PULL_DOWN)) || (detect_with_pull(GPIOA, 5, PULL_DOWN)) || (detect_with_pull(GPIOA, 6, PULL_DOWN)) || (detect_with_pull(GPIOA, 7, PULL_DOWN))){ @@ -53,22 +54,10 @@ void detect_board_type(void) { // ///// Configuration detection ///// // bool has_external_debug_serial = 0; -bool is_entering_bootmode = 0; void detect_configuration(void) { // detect if external serial debugging is present has_external_debug_serial = detect_with_pull(GPIOA, 3, PULL_DOWN); - - #ifdef PANDA - if(hw_type == HW_TYPE_WHITE_PANDA) { - // check if the ESP is trying to put me in boot mode - is_entering_bootmode = !detect_with_pull(GPIOB, 0, PULL_UP); - } else { - is_entering_bootmode = 0; - } - #else - is_entering_bootmode = 0; - #endif } // ///// Board functions ///// // diff --git a/panda/board/board_declarations.h b/panda/board/board_declarations.h index d5e9e06a8c5991..963539e00805af 100644 --- a/panda/board/board_declarations.h +++ b/panda/board/board_declarations.h @@ -1,10 +1,10 @@ // ******************** Prototypes ******************** typedef void (*board_init)(void); -typedef void (*board_enable_can_transciever)(uint8_t transciever, bool enabled); -typedef void (*board_enable_can_transcievers)(bool enabled); +typedef void (*board_enable_can_transceiver)(uint8_t transceiver, bool enabled); +typedef void (*board_enable_can_transceivers)(bool enabled); typedef void (*board_set_led)(uint8_t color, bool enabled); typedef void (*board_set_usb_power_mode)(uint8_t mode); -typedef void (*board_set_esp_gps_mode)(uint8_t mode); +typedef void (*board_set_gps_mode)(uint8_t mode); typedef void (*board_set_can_mode)(uint8_t mode); typedef void (*board_usb_power_mode_tick)(uint32_t uptime); typedef bool (*board_check_ignition)(void); @@ -12,16 +12,18 @@ typedef uint32_t (*board_read_current)(void); typedef void (*board_set_ir_power)(uint8_t percentage); typedef void (*board_set_fan_power)(uint8_t percentage); typedef void (*board_set_phone_power)(bool enabled); +typedef void (*board_set_clock_source_mode)(uint8_t mode); +typedef void (*board_set_siren)(bool enabled); struct board { const char *board_type; const harness_configuration *harness_config; board_init init; - board_enable_can_transciever enable_can_transciever; - board_enable_can_transcievers enable_can_transcievers; + board_enable_can_transceiver enable_can_transceiver; + board_enable_can_transceivers enable_can_transceivers; board_set_led set_led; board_set_usb_power_mode set_usb_power_mode; - board_set_esp_gps_mode set_esp_gps_mode; + board_set_gps_mode set_gps_mode; board_set_can_mode set_can_mode; board_usb_power_mode_tick usb_power_mode_tick; board_check_ignition check_ignition; @@ -29,6 +31,8 @@ struct board { board_set_ir_power set_ir_power; board_set_fan_power set_fan_power; board_set_phone_power set_phone_power; + board_set_clock_source_mode set_clock_source_mode; + board_set_siren set_siren; }; // ******************* Definitions ******************** @@ -52,10 +56,10 @@ struct board { #define USB_POWER_CDP 2U #define USB_POWER_DCP 3U -// ESP modes -#define ESP_GPS_DISABLED 0U -#define ESP_GPS_ENABLED 1U -#define ESP_GPS_BOOTMODE 2U +// GPS modes +#define GPS_DISABLED 0U +#define GPS_ENABLED 1U +#define GPS_BOOTMODE 2U // CAN modes #define CAN_MODE_NORMAL 0U @@ -72,4 +76,4 @@ bool board_has_gmlan(void); bool board_has_obd(void); bool board_has_lin(void); bool board_has_rtc(void); -bool board_has_relay(void); \ No newline at end of file +bool board_has_relay(void); diff --git a/panda/board/boards/black.h b/panda/board/boards/black.h index 57305980c48f68..fa5a542d05dd4e 100644 --- a/panda/board/boards/black.h +++ b/panda/board/boards/black.h @@ -2,8 +2,8 @@ // Black Panda + Harness // // ///////////////////// // -void black_enable_can_transciever(uint8_t transciever, bool enabled) { - switch (transciever){ +void black_enable_can_transceiver(uint8_t transceiver, bool enabled) { + switch (transceiver){ case 1U: set_gpio_output(GPIOC, 1, !enabled); break; @@ -17,18 +17,18 @@ void black_enable_can_transciever(uint8_t transciever, bool enabled) { set_gpio_output(GPIOB, 10, !enabled); break; default: - puts("Invalid CAN transciever ("); puth(transciever); puts("): enabling failed\n"); + puts("Invalid CAN transceiver ("); puth(transceiver); puts("): enabling failed\n"); break; } } -void black_enable_can_transcievers(bool enabled) { +void black_enable_can_transceivers(bool enabled) { for(uint8_t i=1U; i<=4U; i++){ // Leave main CAN always on for CAN-based ignition detection if((car_harness_status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){ - black_enable_can_transciever(i, true); + black_enable_can_transceiver(i, true); } else { - black_enable_can_transciever(i, enabled); + black_enable_can_transceiver(i, enabled); } } } @@ -77,24 +77,24 @@ void black_set_usb_power_mode(uint8_t mode) { } } -void black_set_esp_gps_mode(uint8_t mode) { +void black_set_gps_mode(uint8_t mode) { switch (mode) { - case ESP_GPS_DISABLED: + case GPS_DISABLED: // GPS OFF set_gpio_output(GPIOC, 14, 0); set_gpio_output(GPIOC, 5, 0); break; - case ESP_GPS_ENABLED: + case GPS_ENABLED: // GPS ON set_gpio_output(GPIOC, 14, 1); set_gpio_output(GPIOC, 5, 1); break; - case ESP_GPS_BOOTMODE: + case GPS_BOOTMODE: set_gpio_output(GPIOC, 14, 1); set_gpio_output(GPIOC, 5, 0); break; default: - puts("Invalid ESP/GPS mode\n"); + puts("Invalid GPS mode\n"); break; } } @@ -154,6 +154,14 @@ void black_set_phone_power(bool enabled){ UNUSED(enabled); } +void black_set_clock_source_mode(uint8_t mode){ + UNUSED(mode); +} + +void black_set_siren(bool enabled){ + UNUSED(enabled); +} + void black_init(void) { common_init_gpio(); @@ -167,7 +175,7 @@ void black_init(void) { set_gpio_mode(GPIOC, 3, MODE_ANALOG); // Set default state of GPS - current_board->set_esp_gps_mode(ESP_GPS_ENABLED); + current_board->set_gps_mode(GPS_ENABLED); // C10: OBD_SBU1_RELAY (harness relay driving output) // C11: OBD_SBU2_RELAY (harness relay driving output) @@ -190,8 +198,8 @@ void black_init(void) { // Initialize harness harness_init(); - // Enable CAN transcievers - black_enable_can_transcievers(true); + // Enable CAN transceivers + black_enable_can_transceivers(true); // Disable LEDs black_set_led(LED_RED, false); @@ -228,16 +236,18 @@ const board board_black = { .board_type = "Black", .harness_config = &black_harness_config, .init = black_init, - .enable_can_transciever = black_enable_can_transciever, - .enable_can_transcievers = black_enable_can_transcievers, + .enable_can_transceiver = black_enable_can_transceiver, + .enable_can_transceivers = black_enable_can_transceivers, .set_led = black_set_led, .set_usb_power_mode = black_set_usb_power_mode, - .set_esp_gps_mode = black_set_esp_gps_mode, + .set_gps_mode = black_set_gps_mode, .set_can_mode = black_set_can_mode, .usb_power_mode_tick = black_usb_power_mode_tick, .check_ignition = black_check_ignition, .read_current = black_read_current, .set_fan_power = black_set_fan_power, .set_ir_power = black_set_ir_power, - .set_phone_power = black_set_phone_power + .set_phone_power = black_set_phone_power, + .set_clock_source_mode = black_set_clock_source_mode, + .set_siren = black_set_siren }; diff --git a/panda/board/boards/common.h b/panda/board/boards/common.h index 734380962c2a1d..2f35c34febd780 100644 --- a/panda/board/boards/common.h +++ b/panda/board/boards/common.h @@ -23,7 +23,7 @@ void common_init_gpio(void){ set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS); GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; - // A9,A10: USART 1 for talking to the ESP / GPS + // A9,A10: USART 1 for talking to the GPS set_gpio_alternate(GPIOA, 9, GPIO_AF7_USART1); set_gpio_alternate(GPIOA, 10, GPIO_AF7_USART1); @@ -65,7 +65,7 @@ void peripherals_init(void){ RCC->APB1ENR |= RCC_APB1ENR_PWREN; // for RTC config RCC->APB2ENR |= RCC_APB2ENR_USART1EN; RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; - //RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; + RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; // clock source timer RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; @@ -81,4 +81,4 @@ bool detect_with_pull(GPIO_TypeDef *GPIO, int pin, int mode) { bool ret = get_gpio_input(GPIO, pin); set_gpio_pullup(GPIO, pin, PULL_NONE); return ret; -} \ No newline at end of file +} diff --git a/panda/board/boards/dos.h b/panda/board/boards/dos.h index afccd373da2e7d..307ae724713d4e 100644 --- a/panda/board/boards/dos.h +++ b/panda/board/boards/dos.h @@ -2,8 +2,8 @@ // Dos + Harness // // ///////////// // -void dos_enable_can_transciever(uint8_t transciever, bool enabled) { - switch (transciever){ +void dos_enable_can_transceiver(uint8_t transceiver, bool enabled) { + switch (transceiver){ case 1U: set_gpio_output(GPIOC, 1, !enabled); break; @@ -17,18 +17,18 @@ void dos_enable_can_transciever(uint8_t transciever, bool enabled) { set_gpio_output(GPIOB, 10, !enabled); break; default: - puts("Invalid CAN transciever ("); puth(transciever); puts("): enabling failed\n"); + puts("Invalid CAN transceiver ("); puth(transceiver); puts("): enabling failed\n"); break; } } -void dos_enable_can_transcievers(bool enabled) { +void dos_enable_can_transceivers(bool enabled) { for(uint8_t i=1U; i<=4U; i++){ // Leave main CAN always on for CAN-based ignition detection if((car_harness_status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){ - uno_enable_can_transciever(i, true); + uno_enable_can_transceiver(i, true); } else { - uno_enable_can_transciever(i, enabled); + uno_enable_can_transceiver(i, enabled); } } } @@ -54,20 +54,18 @@ void dos_set_gps_load_switch(bool enabled) { } void dos_set_bootkick(bool enabled){ - UNUSED(enabled); + set_gpio_output(GPIOC, 4, !enabled); } -void dos_bootkick(void) {} - void dos_set_phone_power(bool enabled){ UNUSED(enabled); } void dos_set_usb_power_mode(uint8_t mode) { - UNUSED(mode); + dos_set_bootkick(mode == USB_POWER_CDP); } -void dos_set_esp_gps_mode(uint8_t mode) { +void dos_set_gps_mode(uint8_t mode) { UNUSED(mode); } @@ -101,11 +99,6 @@ void dos_set_can_mode(uint8_t mode){ void dos_usb_power_mode_tick(uint32_t uptime){ UNUSED(uptime); - if(bootkick_timer != 0U){ - bootkick_timer--; - } else { - dos_set_bootkick(false); - } } bool dos_check_ignition(void){ @@ -132,6 +125,14 @@ uint32_t dos_read_current(void){ return 0U; } +void dos_set_clock_source_mode(uint8_t mode){ + clock_source_init(mode); +} + +void dos_set_siren(bool enabled){ + set_gpio_output(GPIOC, 12, enabled); +} + void dos_init(void) { common_init_gpio(); @@ -171,8 +172,8 @@ void dos_init(void) { // Initialize RTC rtc_init(); - // Enable CAN transcievers - dos_enable_can_transcievers(true); + // Enable CAN transceivers + dos_enable_can_transceivers(true); // Disable LEDs dos_set_led(LED_RED, false); @@ -189,6 +190,9 @@ void dos_init(void) { // init multiplexer can_set_obd(car_harness_status, false); + + // Init clock source as internal free running + dos_set_clock_source_mode(CLOCK_SOURCE_MODE_FREE_RUNNING); } const harness_configuration dos_harness_config = { @@ -209,16 +213,18 @@ const board board_dos = { .board_type = "Dos", .harness_config = &dos_harness_config, .init = dos_init, - .enable_can_transciever = dos_enable_can_transciever, - .enable_can_transcievers = dos_enable_can_transcievers, + .enable_can_transceiver = dos_enable_can_transceiver, + .enable_can_transceivers = dos_enable_can_transceivers, .set_led = dos_set_led, .set_usb_power_mode = dos_set_usb_power_mode, - .set_esp_gps_mode = dos_set_esp_gps_mode, + .set_gps_mode = dos_set_gps_mode, .set_can_mode = dos_set_can_mode, .usb_power_mode_tick = dos_usb_power_mode_tick, .check_ignition = dos_check_ignition, .read_current = dos_read_current, .set_fan_power = dos_set_fan_power, .set_ir_power = dos_set_ir_power, - .set_phone_power = dos_set_phone_power + .set_phone_power = dos_set_phone_power, + .set_clock_source_mode = dos_set_clock_source_mode, + .set_siren = dos_set_siren }; diff --git a/panda/board/boards/grey.h b/panda/board/boards/grey.h index 1c7278d278561e..bd5b1559eba63d 100644 --- a/panda/board/boards/grey.h +++ b/panda/board/boards/grey.h @@ -8,22 +8,22 @@ void grey_init(void) { white_grey_common_init(); // Set default state of GPS - current_board->set_esp_gps_mode(ESP_GPS_ENABLED); + current_board->set_gps_mode(GPS_ENABLED); } -void grey_set_esp_gps_mode(uint8_t mode) { +void grey_set_gps_mode(uint8_t mode) { switch (mode) { - case ESP_GPS_DISABLED: + case GPS_DISABLED: // GPS OFF set_gpio_output(GPIOC, 14, 0); set_gpio_output(GPIOC, 5, 0); break; - case ESP_GPS_ENABLED: + case GPS_ENABLED: // GPS ON set_gpio_output(GPIOC, 14, 1); set_gpio_output(GPIOC, 5, 1); break; - case ESP_GPS_BOOTMODE: + case GPS_BOOTMODE: set_gpio_output(GPIOC, 14, 1); set_gpio_output(GPIOC, 5, 0); break; @@ -37,16 +37,18 @@ const board board_grey = { .board_type = "Grey", .harness_config = &white_harness_config, .init = grey_init, - .enable_can_transciever = white_enable_can_transciever, - .enable_can_transcievers = white_enable_can_transcievers, + .enable_can_transceiver = white_enable_can_transceiver, + .enable_can_transceivers = white_enable_can_transceivers, .set_led = white_set_led, .set_usb_power_mode = white_set_usb_power_mode, - .set_esp_gps_mode = grey_set_esp_gps_mode, + .set_gps_mode = grey_set_gps_mode, .set_can_mode = white_set_can_mode, .usb_power_mode_tick = white_usb_power_mode_tick, .check_ignition = white_check_ignition, .read_current = white_read_current, .set_fan_power = white_set_fan_power, .set_ir_power = white_set_ir_power, - .set_phone_power = white_set_phone_power -}; \ No newline at end of file + .set_phone_power = white_set_phone_power, + .set_clock_source_mode = white_set_clock_source_mode, + .set_siren = white_set_siren +}; diff --git a/panda/board/boards/pedal.h b/panda/board/boards/pedal.h index c67d39151d8b87..31abe9c5c710fd 100644 --- a/panda/board/boards/pedal.h +++ b/panda/board/boards/pedal.h @@ -2,19 +2,19 @@ // Pedal // // ///// // -void pedal_enable_can_transciever(uint8_t transciever, bool enabled) { - switch (transciever){ +void pedal_enable_can_transceiver(uint8_t transceiver, bool enabled) { + switch (transceiver){ case 1: set_gpio_output(GPIOB, 3, !enabled); break; default: - puts("Invalid CAN transciever ("); puth(transciever); puts("): enabling failed\n"); + puts("Invalid CAN transceiver ("); puth(transceiver); puts("): enabling failed\n"); break; } } -void pedal_enable_can_transcievers(bool enabled) { - pedal_enable_can_transciever(1U, enabled); +void pedal_enable_can_transceivers(bool enabled) { + pedal_enable_can_transceiver(1U, enabled); } void pedal_set_led(uint8_t color, bool enabled) { @@ -35,7 +35,7 @@ void pedal_set_usb_power_mode(uint8_t mode){ puts("Trying to set USB power mode on pedal. This is not supported.\n"); } -void pedal_set_esp_gps_mode(uint8_t mode) { +void pedal_set_gps_mode(uint8_t mode) { UNUSED(mode); puts("Trying to set ESP/GPS mode on pedal. This is not supported.\n"); } @@ -77,6 +77,14 @@ void pedal_set_phone_power(bool enabled){ UNUSED(enabled); } +void pedal_set_clock_source_mode(uint8_t mode){ + UNUSED(mode); +} + +void pedal_set_siren(bool enabled){ + UNUSED(enabled); +} + void pedal_init(void) { common_init_gpio(); @@ -86,8 +94,8 @@ void pedal_init(void) { // DAC outputs on A4 and A5 // apparently they don't need GPIO setup - // Enable transciever - pedal_enable_can_transcievers(true); + // Enable transceiver + pedal_enable_can_transceivers(true); // Disable LEDs pedal_set_led(LED_RED, false); @@ -102,16 +110,18 @@ const board board_pedal = { .board_type = "Pedal", .harness_config = &pedal_harness_config, .init = pedal_init, - .enable_can_transciever = pedal_enable_can_transciever, - .enable_can_transcievers = pedal_enable_can_transcievers, + .enable_can_transceiver = pedal_enable_can_transceiver, + .enable_can_transceivers = pedal_enable_can_transceivers, .set_led = pedal_set_led, .set_usb_power_mode = pedal_set_usb_power_mode, - .set_esp_gps_mode = pedal_set_esp_gps_mode, + .set_gps_mode = pedal_set_gps_mode, .set_can_mode = pedal_set_can_mode, .usb_power_mode_tick = pedal_usb_power_mode_tick, .check_ignition = pedal_check_ignition, .read_current = pedal_read_current, .set_fan_power = pedal_set_fan_power, .set_ir_power = pedal_set_ir_power, - .set_phone_power = pedal_set_phone_power -}; \ No newline at end of file + .set_phone_power = pedal_set_phone_power, + .set_clock_source_mode = pedal_set_clock_source_mode, + .set_siren = pedal_set_siren +}; diff --git a/panda/board/boards/uno.h b/panda/board/boards/uno.h index de430cb572749d..96eb6268bd3dc0 100644 --- a/panda/board/boards/uno.h +++ b/panda/board/boards/uno.h @@ -4,8 +4,8 @@ #define BOOTKICK_TIME 3U uint8_t bootkick_timer = 0U; -void uno_enable_can_transciever(uint8_t transciever, bool enabled) { - switch (transciever){ +void uno_enable_can_transceiver(uint8_t transceiver, bool enabled) { + switch (transceiver){ case 1U: set_gpio_output(GPIOC, 1, !enabled); break; @@ -19,18 +19,18 @@ void uno_enable_can_transciever(uint8_t transciever, bool enabled) { set_gpio_output(GPIOB, 10, !enabled); break; default: - puts("Invalid CAN transciever ("); puth(transciever); puts("): enabling failed\n"); + puts("Invalid CAN transceiver ("); puth(transceiver); puts("): enabling failed\n"); break; } } -void uno_enable_can_transcievers(bool enabled) { +void uno_enable_can_transceivers(bool enabled) { for(uint8_t i=1U; i<=4U; i++){ // Leave main CAN always on for CAN-based ignition detection if((car_harness_status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){ - uno_enable_can_transciever(i, true); + uno_enable_can_transceiver(i, true); } else { - uno_enable_can_transciever(i, enabled); + uno_enable_can_transceiver(i, enabled); } } } @@ -89,21 +89,21 @@ void uno_set_usb_power_mode(uint8_t mode) { } } -void uno_set_esp_gps_mode(uint8_t mode) { +void uno_set_gps_mode(uint8_t mode) { switch (mode) { - case ESP_GPS_DISABLED: + case GPS_DISABLED: // GPS OFF set_gpio_output(GPIOB, 1, 0); set_gpio_output(GPIOC, 5, 0); uno_set_gps_load_switch(false); break; - case ESP_GPS_ENABLED: + case GPS_ENABLED: // GPS ON set_gpio_output(GPIOB, 1, 1); set_gpio_output(GPIOC, 5, 1); uno_set_gps_load_switch(true); break; - case ESP_GPS_BOOTMODE: + case GPS_BOOTMODE: set_gpio_output(GPIOB, 1, 1); set_gpio_output(GPIOC, 5, 0); uno_set_gps_load_switch(true); @@ -175,6 +175,14 @@ uint32_t uno_read_current(void){ return 0U; } +void uno_set_clock_source_mode(uint8_t mode){ + UNUSED(mode); +} + +void uno_set_siren(bool enabled){ + UNUSED(enabled); +} + void uno_init(void) { common_init_gpio(); @@ -188,7 +196,7 @@ void uno_init(void) { set_gpio_mode(GPIOC, 3, MODE_ANALOG); // Set default state of GPS - current_board->set_esp_gps_mode(ESP_GPS_ENABLED); + current_board->set_gps_mode(GPS_ENABLED); // C10: OBD_SBU1_RELAY (harness relay driving output) // C11: OBD_SBU2_RELAY (harness relay driving output) @@ -223,8 +231,8 @@ void uno_init(void) { // Initialize RTC rtc_init(); - // Enable CAN transcievers - uno_enable_can_transcievers(true); + // Enable CAN transceivers + uno_enable_can_transceivers(true); // Disable LEDs uno_set_led(LED_RED, false); @@ -271,16 +279,18 @@ const board board_uno = { .board_type = "Uno", .harness_config = &uno_harness_config, .init = uno_init, - .enable_can_transciever = uno_enable_can_transciever, - .enable_can_transcievers = uno_enable_can_transcievers, + .enable_can_transceiver = uno_enable_can_transceiver, + .enable_can_transceivers = uno_enable_can_transceivers, .set_led = uno_set_led, .set_usb_power_mode = uno_set_usb_power_mode, - .set_esp_gps_mode = uno_set_esp_gps_mode, + .set_gps_mode = uno_set_gps_mode, .set_can_mode = uno_set_can_mode, .usb_power_mode_tick = uno_usb_power_mode_tick, .check_ignition = uno_check_ignition, .read_current = uno_read_current, .set_fan_power = uno_set_fan_power, .set_ir_power = uno_set_ir_power, - .set_phone_power = uno_set_phone_power + .set_phone_power = uno_set_phone_power, + .set_clock_source_mode = uno_set_clock_source_mode, + .set_siren = uno_set_siren }; diff --git a/panda/board/boards/white.h b/panda/board/boards/white.h index 1be0702f9496b4..44d8f512b0fe46 100644 --- a/panda/board/boards/white.h +++ b/panda/board/boards/white.h @@ -2,8 +2,8 @@ // White Panda // // /////////// // -void white_enable_can_transciever(uint8_t transciever, bool enabled) { - switch (transciever){ +void white_enable_can_transceiver(uint8_t transceiver, bool enabled) { + switch (transceiver){ case 1U: set_gpio_output(GPIOC, 1, !enabled); break; @@ -14,15 +14,15 @@ void white_enable_can_transciever(uint8_t transciever, bool enabled) { set_gpio_output(GPIOA, 0, !enabled); break; default: - puts("Invalid CAN transciever ("); puth(transciever); puts("): enabling failed\n"); + puts("Invalid CAN transceiver ("); puth(transceiver); puts("): enabling failed\n"); break; } } -void white_enable_can_transcievers(bool enabled) { - uint8_t t1 = enabled ? 1U : 2U; // leave transciever 1 enabled to detect CAN ignition +void white_enable_can_transceivers(bool enabled) { + uint8_t t1 = enabled ? 1U : 2U; // leave transceiver 1 enabled to detect CAN ignition for(uint8_t i=t1; i<=3U; i++) { - white_enable_can_transciever(i, enabled); + white_enable_can_transceiver(i, enabled); } } @@ -71,21 +71,21 @@ void white_set_usb_power_mode(uint8_t mode){ } } -void white_set_esp_gps_mode(uint8_t mode) { +void white_set_gps_mode(uint8_t mode) { switch (mode) { - case ESP_GPS_DISABLED: + case GPS_DISABLED: // ESP OFF set_gpio_output(GPIOC, 14, 0); set_gpio_output(GPIOC, 5, 0); break; #ifndef EON - case ESP_GPS_ENABLED: + case GPS_ENABLED: // ESP ON set_gpio_output(GPIOC, 14, 1); set_gpio_output(GPIOC, 5, 1); break; #endif - case ESP_GPS_BOOTMODE: + case GPS_BOOTMODE: set_gpio_output(GPIOC, 14, 1); set_gpio_output(GPIOC, 5, 0); break; @@ -242,6 +242,14 @@ void white_set_phone_power(bool enabled){ UNUSED(enabled); } +void white_set_clock_source_mode(uint8_t mode){ + UNUSED(mode); +} + +void white_set_siren(bool enabled){ + UNUSED(enabled); +} + void white_grey_common_init(void) { common_init_gpio(); @@ -291,8 +299,8 @@ void white_grey_common_init(void) { set_gpio_alternate(GPIOC, 11, GPIO_AF7_USART3); set_gpio_pullup(GPIOC, 11, PULL_UP); - // Enable CAN transcievers - white_enable_can_transcievers(true); + // Enable CAN transceivers + white_enable_can_transceivers(true); // Disable LEDs white_set_led(LED_RED, false); @@ -316,12 +324,8 @@ void white_grey_common_init(void) { void white_init(void) { white_grey_common_init(); - // Set default state of ESP - #ifdef EON - current_board->set_esp_gps_mode(ESP_GPS_DISABLED); - #else - current_board->set_esp_gps_mode(ESP_GPS_ENABLED); - #endif + // Set ESP off by default + current_board->set_gps_mode(GPS_DISABLED); } const harness_configuration white_harness_config = { @@ -332,16 +336,18 @@ const board board_white = { .board_type = "White", .harness_config = &white_harness_config, .init = white_init, - .enable_can_transciever = white_enable_can_transciever, - .enable_can_transcievers = white_enable_can_transcievers, + .enable_can_transceiver = white_enable_can_transceiver, + .enable_can_transceivers = white_enable_can_transceivers, .set_led = white_set_led, .set_usb_power_mode = white_set_usb_power_mode, - .set_esp_gps_mode = white_set_esp_gps_mode, + .set_gps_mode = white_set_gps_mode, .set_can_mode = white_set_can_mode, .usb_power_mode_tick = white_usb_power_mode_tick, .check_ignition = white_check_ignition, .read_current = white_read_current, .set_fan_power = white_set_fan_power, .set_ir_power = white_set_ir_power, - .set_phone_power = white_set_phone_power + .set_phone_power = white_set_phone_power, + .set_clock_source_mode = white_set_clock_source_mode, + .set_siren = white_set_siren }; diff --git a/panda/board/drivers/clock_source.h b/panda/board/drivers/clock_source.h new file mode 100644 index 00000000000000..966dee452e0839 --- /dev/null +++ b/panda/board/drivers/clock_source.h @@ -0,0 +1,100 @@ + +#define CLOCK_SOURCE_MODE_DISABLED 0U +#define CLOCK_SOURCE_MODE_FREE_RUNNING 1U +#define CLOCK_SOURCE_MODE_EXTERNAL_SYNC 2U + +#define CLOCK_SOURCE_PERIOD_MS 50U +#define CLOCK_SOURCE_PULSE_LEN_MS 2U + +uint8_t clock_source_mode = CLOCK_SOURCE_MODE_DISABLED; + +void EXTI0_IRQ_Handler(void) { + volatile unsigned int pr = EXTI->PR & (1U << 0); + if (pr != 0U) { + if(clock_source_mode == CLOCK_SOURCE_MODE_EXTERNAL_SYNC){ + // TODO: Implement! + } + } + EXTI->PR = (1U << 0); +} + +void TIM1_UP_TIM10_IRQ_Handler(void) { + if((TIM1->SR & TIM_SR_UIF) != 0) { + if(clock_source_mode != CLOCK_SOURCE_MODE_DISABLED) { + // Start clock pulse + set_gpio_output(GPIOB, 14, true); + set_gpio_output(GPIOB, 15, true); + } + + // Reset interrupt + TIM1->SR &= ~(TIM_SR_UIF); + } +} + +void TIM1_CC_IRQ_Handler(void) { + if((TIM1->SR & TIM_SR_CC1IF) != 0) { + if(clock_source_mode != CLOCK_SOURCE_MODE_DISABLED) { + // End clock pulse + set_gpio_output(GPIOB, 14, false); + set_gpio_output(GPIOB, 15, false); + } + + // Reset interrupt + TIM1->SR &= ~(TIM_SR_CC1IF); + } +} + +void clock_source_init(uint8_t mode){ + // Setup external clock signal interrupt + REGISTER_INTERRUPT(EXTI0_IRQn, EXTI0_IRQ_Handler, 110U, FAULT_INTERRUPT_RATE_CLOCK_SOURCE) + register_set(&(SYSCFG->EXTICR[0]), SYSCFG_EXTICR1_EXTI0_PB, 0xFU); + register_set_bits(&(EXTI->IMR), (1U << 0)); + register_set_bits(&(EXTI->RTSR), (1U << 0)); + register_clear_bits(&(EXTI->FTSR), (1U << 0)); + + // Setup timer + REGISTER_INTERRUPT(TIM1_UP_TIM10_IRQn, TIM1_UP_TIM10_IRQ_Handler, (1200U / CLOCK_SOURCE_PERIOD_MS) , FAULT_INTERRUPT_RATE_TIM1) + REGISTER_INTERRUPT(TIM1_CC_IRQn, TIM1_CC_IRQ_Handler, (1200U / CLOCK_SOURCE_PERIOD_MS) , FAULT_INTERRUPT_RATE_TIM1) + register_set(&(TIM1->PSC), (9600-1), 0xFFFFU); // Tick on 0.1 ms + register_set(&(TIM1->ARR), ((CLOCK_SOURCE_PERIOD_MS*10U) - 1U), 0xFFFFU); // Period + register_set(&(TIM1->CCMR1), 0U, 0xFFFFU); // No output on compare + register_set_bits(&(TIM1->CCER), TIM_CCER_CC1E); // Enable compare 1 + register_set(&(TIM1->CCR1), (CLOCK_SOURCE_PULSE_LEN_MS*10U), 0xFFFFU); // Compare 1 value + register_set_bits(&(TIM1->DIER), TIM_DIER_UIE | TIM_DIER_CC1IE); // Enable interrupts + register_set(&(TIM1->CR1), TIM_CR1_CEN, 0x3FU); // Enable timer + + // Set mode + switch(mode) { + case CLOCK_SOURCE_MODE_DISABLED: + // No clock signal + NVIC_DisableIRQ(EXTI0_IRQn); + NVIC_DisableIRQ(TIM1_UP_TIM10_IRQn); + NVIC_DisableIRQ(TIM1_CC_IRQn); + + // Disable pulse if we were in the middle of it + set_gpio_output(GPIOB, 14, false); + set_gpio_output(GPIOB, 15, false); + + clock_source_mode = CLOCK_SOURCE_MODE_DISABLED; + break; + case CLOCK_SOURCE_MODE_FREE_RUNNING: + // Clock signal is based on internal timer + NVIC_DisableIRQ(EXTI0_IRQn); + NVIC_EnableIRQ(TIM1_UP_TIM10_IRQn); + NVIC_EnableIRQ(TIM1_CC_IRQn); + + clock_source_mode = CLOCK_SOURCE_MODE_FREE_RUNNING; + break; + case CLOCK_SOURCE_MODE_EXTERNAL_SYNC: + // Clock signal is based on external timer + NVIC_EnableIRQ(EXTI0_IRQn); + NVIC_EnableIRQ(TIM1_UP_TIM10_IRQn); + NVIC_EnableIRQ(TIM1_CC_IRQn); + + clock_source_mode = CLOCK_SOURCE_MODE_EXTERNAL_SYNC; + break; + default: + puts("Unknown clock source mode: "); puth(mode); puts("\n"); + break; + } +} \ No newline at end of file diff --git a/panda/board/drivers/uart.h b/panda/board/drivers/uart.h index 4ab791f601759b..e4f23ead011911 100644 --- a/panda/board/drivers/uart.h +++ b/panda/board/drivers/uart.h @@ -50,8 +50,8 @@ void debug_ring_callback(uart_ring *ring); // ******************************** UART buffers ******************************** -// esp_gps = USART1 -UART_BUFFER(esp_gps, FIFO_SIZE_DMA, FIFO_SIZE_INT, USART1, NULL, true) +// gps = USART1 +UART_BUFFER(gps, FIFO_SIZE_DMA, FIFO_SIZE_INT, USART1, NULL, true) // lin1, K-LINE = UART5 // lin2, L-LINE = USART3 @@ -68,7 +68,7 @@ uart_ring *get_ring_by_number(int a) { ring = &uart_ring_debug; break; case 1: - ring = &uart_ring_esp_gps; + ring = &uart_ring_gps; break; case 2: ring = &uart_ring_lin1; @@ -185,8 +185,8 @@ void uart_interrupt_handler(uart_ring *q) { // Reset IDLE flag UART_READ_DR(q->uart) - if(q == &uart_ring_esp_gps){ - dma_pointer_handler(&uart_ring_esp_gps, DMA2_Stream5->NDTR); + if(q == &uart_ring_gps){ + dma_pointer_handler(&uart_ring_gps, DMA2_Stream5->NDTR); } else { #ifdef DEBUG_UART puts("No IDLE dma_pointer_handler implemented for this UART."); @@ -197,7 +197,7 @@ void uart_interrupt_handler(uart_ring *q) { EXIT_CRITICAL(); } -void USART1_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_esp_gps); } +void USART1_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_gps); } void USART2_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_debug); } void USART3_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_lin2); } void UART5_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_lin1); } @@ -219,7 +219,7 @@ void DMA2_Stream5_IRQ_Handler(void) { } // Re-calculate write pointer and reset flags - dma_pointer_handler(&uart_ring_esp_gps, DMA2_Stream5->NDTR); + dma_pointer_handler(&uart_ring_gps, DMA2_Stream5->NDTR); DMA2->HIFCR = DMA_HIFCR_CTCIF5 | DMA_HIFCR_CHTIF5; EXIT_CRITICAL(); @@ -229,7 +229,7 @@ void DMA2_Stream5_IRQ_Handler(void) { void dma_rx_init(uart_ring *q) { // Initialization is UART-dependent - if(q == &uart_ring_esp_gps){ + if(q == &uart_ring_gps){ // DMA2, stream 5, channel 4 // Disable FIFO mode (enable direct) diff --git a/panda/board/faults.h b/panda/board/faults.h index 2c031cf29e1ef6..0825586d1683d2 100644 --- a/panda/board/faults.h +++ b/panda/board/faults.h @@ -3,26 +3,28 @@ #define FAULT_STATUS_PERMANENT 2U // Fault types -#define FAULT_RELAY_MALFUNCTION (1U << 0) -#define FAULT_UNUSED_INTERRUPT_HANDLED (1U << 1) -#define FAULT_INTERRUPT_RATE_CAN_1 (1U << 2) -#define FAULT_INTERRUPT_RATE_CAN_2 (1U << 3) -#define FAULT_INTERRUPT_RATE_CAN_3 (1U << 4) -#define FAULT_INTERRUPT_RATE_TACH (1U << 5) -#define FAULT_INTERRUPT_RATE_GMLAN (1U << 6) -#define FAULT_INTERRUPT_RATE_INTERRUPTS (1U << 7) -#define FAULT_INTERRUPT_RATE_SPI_DMA (1U << 8) -#define FAULT_INTERRUPT_RATE_SPI_CS (1U << 9) -#define FAULT_INTERRUPT_RATE_UART_1 (1U << 10) -#define FAULT_INTERRUPT_RATE_UART_2 (1U << 11) -#define FAULT_INTERRUPT_RATE_UART_3 (1U << 12) -#define FAULT_INTERRUPT_RATE_UART_5 (1U << 13) -#define FAULT_INTERRUPT_RATE_UART_DMA (1U << 14) -#define FAULT_INTERRUPT_RATE_USB (1U << 15) -#define FAULT_INTERRUPT_RATE_TIM1 (1U << 16) -#define FAULT_INTERRUPT_RATE_TIM3 (1U << 17) -#define FAULT_REGISTER_DIVERGENT (1U << 18) -#define FAULT_INTERRUPT_RATE_KLINE_INIT (1U << 19) +#define FAULT_RELAY_MALFUNCTION (1U << 0) +#define FAULT_UNUSED_INTERRUPT_HANDLED (1U << 1) +#define FAULT_INTERRUPT_RATE_CAN_1 (1U << 2) +#define FAULT_INTERRUPT_RATE_CAN_2 (1U << 3) +#define FAULT_INTERRUPT_RATE_CAN_3 (1U << 4) +#define FAULT_INTERRUPT_RATE_TACH (1U << 5) +#define FAULT_INTERRUPT_RATE_GMLAN (1U << 6) +#define FAULT_INTERRUPT_RATE_INTERRUPTS (1U << 7) +#define FAULT_INTERRUPT_RATE_SPI_DMA (1U << 8) +#define FAULT_INTERRUPT_RATE_SPI_CS (1U << 9) +#define FAULT_INTERRUPT_RATE_UART_1 (1U << 10) +#define FAULT_INTERRUPT_RATE_UART_2 (1U << 11) +#define FAULT_INTERRUPT_RATE_UART_3 (1U << 12) +#define FAULT_INTERRUPT_RATE_UART_5 (1U << 13) +#define FAULT_INTERRUPT_RATE_UART_DMA (1U << 14) +#define FAULT_INTERRUPT_RATE_USB (1U << 15) +#define FAULT_INTERRUPT_RATE_TIM1 (1U << 16) +#define FAULT_INTERRUPT_RATE_TIM3 (1U << 17) +#define FAULT_REGISTER_DIVERGENT (1U << 18) +#define FAULT_INTERRUPT_RATE_KLINE_INIT (1U << 19) +#define FAULT_INTERRUPT_RATE_CLOCK_SOURCE (1U << 20) +#define FAULT_INTERRUPT_RATE_TIM9 (1U << 21) // Permanent faults #define PERMANENT_FAULTS 0U diff --git a/panda/board/gpio.h b/panda/board/gpio.h index 2b937eced4cfdd..b50de50c333640 100644 --- a/panda/board/gpio.h +++ b/panda/board/gpio.h @@ -64,13 +64,9 @@ void early(void) { if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) { #ifdef PANDA - current_board->set_esp_gps_mode(ESP_GPS_DISABLED); + current_board->set_gps_mode(GPS_DISABLED); #endif current_board->set_led(LED_GREEN, 1); jump_to_bootloader(); } - - if (is_entering_bootmode) { - enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; - } -} \ No newline at end of file +} diff --git a/panda/board/main.c b/panda/board/main.c index 497ea5dcdcd0fb..c6e4f0fceed116 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -400,24 +400,24 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) // **** 0xd9: set ESP power case 0xd9: if (setup->b.wValue.w == 1U) { - current_board->set_esp_gps_mode(ESP_GPS_ENABLED); + current_board->set_gps_mode(GPS_ENABLED); } else if (setup->b.wValue.w == 2U) { - current_board->set_esp_gps_mode(ESP_GPS_BOOTMODE); + current_board->set_gps_mode(GPS_BOOTMODE); } else { - current_board->set_esp_gps_mode(ESP_GPS_DISABLED); + current_board->set_gps_mode(GPS_DISABLED); } break; // **** 0xda: reset ESP, with optional boot mode case 0xda: - current_board->set_esp_gps_mode(ESP_GPS_DISABLED); + current_board->set_gps_mode(GPS_DISABLED); delay(1000000); if (setup->b.wValue.w == 1U) { - current_board->set_esp_gps_mode(ESP_GPS_BOOTMODE); + current_board->set_gps_mode(GPS_BOOTMODE); } else { - current_board->set_esp_gps_mode(ESP_GPS_ENABLED); + current_board->set_gps_mode(GPS_ENABLED); } delay(1000000); - current_board->set_esp_gps_mode(ESP_GPS_ENABLED); + current_board->set_gps_mode(GPS_ENABLED); break; // **** 0xdb: set GMLAN (white/grey) or OBD CAN (black) multiplexing mode case 0xdb: @@ -493,7 +493,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) } // TODO: Remove this again and fix boardd code to hande the message bursts instead of single chars - if (ur == &uart_ring_esp_gps) { + if (ur == &uart_ring_gps) { dma_pointer_handler(ur, DMA2_Stream5->NDTR); } @@ -606,6 +606,14 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) } } break; + // **** 0xf5: set clock source mode + case 0xf5: + current_board->set_clock_source_mode(setup->b.wValue.w); + break; + // **** 0xf6: set siren enabled + case 0xf6: + siren_enabled = (setup->b.wValue.w != 0U); + break; default: puts("NO HANDLER "); puth(setup->b.bRequest); @@ -663,87 +671,97 @@ void __attribute__ ((noinline)) enable_fpu(void) { #define EON_HEARTBEAT_IGNITION_CNT_ON 5U #define EON_HEARTBEAT_IGNITION_CNT_OFF 2U -// called at 1Hz +// called at 8Hz +uint8_t loop_counter = 0U; void TIM1_BRK_TIM9_IRQ_Handler(void) { if (TIM9->SR != 0) { - can_live = pending_can_live; + // siren + current_board->set_siren((loop_counter & 1U) && siren_enabled); - current_board->usb_power_mode_tick(uptime_cnt); + // decimated to 1Hz + if(loop_counter == 0U){ + can_live = pending_can_live; - //puth(usart1_dma); puts(" "); puth(DMA2_Stream5->M0AR); puts(" "); puth(DMA2_Stream5->NDTR); puts("\n"); + current_board->usb_power_mode_tick(uptime_cnt); - // reset this every 16th pass - if ((uptime_cnt & 0xFU) == 0U) { - pending_can_live = 0; - } - #ifdef DEBUG - puts("** blink "); - puth(can_rx_q.r_ptr); puts(" "); puth(can_rx_q.w_ptr); puts(" "); - puth(can_tx1_q.r_ptr); puts(" "); puth(can_tx1_q.w_ptr); puts(" "); - puth(can_tx2_q.r_ptr); puts(" "); puth(can_tx2_q.w_ptr); puts("\n"); - #endif + //puth(usart1_dma); puts(" "); puth(DMA2_Stream5->M0AR); puts(" "); puth(DMA2_Stream5->NDTR); puts("\n"); - // Tick drivers - fan_tick(); + // reset this every 16th pass + if ((uptime_cnt & 0xFU) == 0U) { + pending_can_live = 0; + } + #ifdef DEBUG + puts("** blink "); + puth(can_rx_q.r_ptr); puts(" "); puth(can_rx_q.w_ptr); puts(" "); + puth(can_tx1_q.r_ptr); puts(" "); puth(can_tx1_q.w_ptr); puts(" "); + puth(can_tx2_q.r_ptr); puts(" "); puth(can_tx2_q.w_ptr); puts("\n"); + #endif - // set green LED to be controls allowed - current_board->set_led(LED_GREEN, controls_allowed); + // Tick drivers + fan_tick(); - // turn off the blue LED, turned on by CAN - // unless we are in power saving mode - current_board->set_led(LED_BLUE, (uptime_cnt & 1U) && (power_save_status == POWER_SAVE_STATUS_ENABLED)); + // set green LED to be controls allowed + current_board->set_led(LED_GREEN, controls_allowed); - // increase heartbeat counter and cap it at the uint32 limit - if (heartbeat_counter < __UINT32_MAX__) { - heartbeat_counter += 1U; - } + // turn off the blue LED, turned on by CAN + // unless we are in power saving mode + current_board->set_led(LED_BLUE, (uptime_cnt & 1U) && (power_save_status == POWER_SAVE_STATUS_ENABLED)); - #ifdef EON - // check heartbeat counter if we are running EON code. - // if the heartbeat has been gone for a while, go to SILENT safety mode and enter power save - if (heartbeat_counter >= (check_started() ? EON_HEARTBEAT_IGNITION_CNT_ON : EON_HEARTBEAT_IGNITION_CNT_OFF)) { - puts("EON hasn't sent a heartbeat for 0x"); - puth(heartbeat_counter); - puts(" seconds. Safety is set to SILENT mode.\n"); - if (current_safety_mode != SAFETY_SILENT) { - set_safety_mode(SAFETY_SILENT, 0U); - } - if (power_save_status != POWER_SAVE_STATUS_ENABLED) { - set_power_save_state(POWER_SAVE_STATUS_ENABLED); + // increase heartbeat counter and cap it at the uint32 limit + if (heartbeat_counter < __UINT32_MAX__) { + heartbeat_counter += 1U; } - // Also disable IR when the heartbeat goes missing - current_board->set_ir_power(0U); + #ifdef EON + // check heartbeat counter if we are running EON code. + // if the heartbeat has been gone for a while, go to SILENT safety mode and enter power save + if (heartbeat_counter >= (check_started() ? EON_HEARTBEAT_IGNITION_CNT_ON : EON_HEARTBEAT_IGNITION_CNT_OFF)) { + puts("EON hasn't sent a heartbeat for 0x"); + puth(heartbeat_counter); + puts(" seconds. Safety is set to SILENT mode.\n"); + if (current_safety_mode != SAFETY_SILENT) { + set_safety_mode(SAFETY_SILENT, 0U); + } + if (power_save_status != POWER_SAVE_STATUS_ENABLED) { + set_power_save_state(POWER_SAVE_STATUS_ENABLED); + } - // If enumerated but no heartbeat (phone up, boardd not running), turn the fan on to cool the device - if(usb_enumerated()){ - current_board->set_fan_power(50U); - } else { - current_board->set_fan_power(0U); + // Also disable IR when the heartbeat goes missing + current_board->set_ir_power(0U); + + // If enumerated but no heartbeat (phone up, boardd not running), turn the fan on to cool the device + if(usb_enumerated()){ + current_board->set_fan_power(50U); + } else { + current_board->set_fan_power(0U); + } } - } - // enter CDP mode when car starts to ensure we are charging a turned off EON - if (check_started() && (usb_power_mode != USB_POWER_CDP)) { - current_board->set_usb_power_mode(USB_POWER_CDP); - } - #endif + // enter CDP mode when car starts to ensure we are charging a turned off EON + if (check_started() && (usb_power_mode != USB_POWER_CDP)) { + current_board->set_usb_power_mode(USB_POWER_CDP); + } + #endif - // check registers - check_registers(); + // check registers + check_registers(); - // set ignition_can to false after 2s of no CAN seen - if (ignition_can_cnt > 2U) { - ignition_can = false; - }; + // set ignition_can to false after 2s of no CAN seen + if (ignition_can_cnt > 2U) { + ignition_can = false; + }; - // on to the next one - uptime_cnt += 1U; - safety_mode_cnt += 1U; - ignition_can_cnt += 1U; + // on to the next one + uptime_cnt += 1U; + safety_mode_cnt += 1U; + ignition_can_cnt += 1U; + + // synchronous safety check + safety_tick(current_hooks); + } - // synchronous safety check - safety_tick(current_hooks); + loop_counter++; + loop_counter %= 8U; } TIM9->SR = 0; } @@ -753,8 +771,8 @@ int main(void) { // Init interrupt table init_interrupts(true); - // 1s timer - REGISTER_INTERRUPT(TIM1_BRK_TIM9_IRQn, TIM1_BRK_TIM9_IRQ_Handler, 2U, FAULT_INTERRUPT_RATE_TIM1) + // 8Hz timer + REGISTER_INTERRUPT(TIM1_BRK_TIM9_IRQn, TIM1_BRK_TIM9_IRQ_Handler, 10U, FAULT_INTERRUPT_RATE_TIM9) // shouldn't have interrupts here, but just in case disable_interrupts(); @@ -778,7 +796,6 @@ int main(void) { puts("Config:\n"); puts(" Board type: "); puts(current_board->board_type); puts("\n"); puts(has_external_debug_serial ? " Real serial\n" : " USB serial\n"); - puts(is_entering_bootmode ? " ESP wants bootmode\n" : " No bootmode\n"); // init board current_board->init(); @@ -794,10 +811,10 @@ int main(void) { } if (board_has_gps()) { - uart_init(&uart_ring_esp_gps, 9600); + uart_init(&uart_ring_gps, 9600); } else { // enable ESP uart - uart_init(&uart_ring_esp_gps, 115200); + uart_init(&uart_ring_gps, 115200); } if(board_has_lin()){ @@ -820,14 +837,14 @@ int main(void) { set_safety_mode(SAFETY_SILENT, 0); // enable CAN TXs - current_board->enable_can_transcievers(true); + current_board->enable_can_transceivers(true); #ifndef EON spi_init(); #endif - // 1hz - timer_init(TIM9, 1464); + // 8hz + timer_init(TIM9, 183); NVIC_EnableIRQ(TIM1_BRK_TIM9_IRQn); #ifdef DEBUG diff --git a/panda/board/main_declarations.h b/panda/board/main_declarations.h index 363a992dbfe8a7..7fa2c4bbb3f8f9 100644 --- a/panda/board/main_declarations.h +++ b/panda/board/main_declarations.h @@ -13,3 +13,4 @@ const board *current_board; bool is_enumerated = 0; uint32_t heartbeat_counter = 0; uint32_t uptime_cnt = 0; +bool siren_enabled = false; diff --git a/panda/board/power_saving.h b/panda/board/power_saving.h index 3df750c1027356..2cb79cb61820ac 100644 --- a/panda/board/power_saving.h +++ b/panda/board/power_saving.h @@ -28,13 +28,13 @@ void set_power_save_state(int state) { enable = true; } - current_board->enable_can_transcievers(enable); + current_board->enable_can_transceivers(enable); // Switch EPS/GPS if (enable) { - current_board->set_esp_gps_mode(ESP_GPS_ENABLED); + current_board->set_gps_mode(GPS_ENABLED); } else { - current_board->set_esp_gps_mode(ESP_GPS_DISABLED); + current_board->set_gps_mode(GPS_DISABLED); } if(board_has_gmlan()){ diff --git a/panda/board/safety/safety_hyundai.h b/panda/board/safety/safety_hyundai.h index 93a43752381917..a4a6d4c2a32c2b 100644 --- a/panda/board/safety/safety_hyundai.h +++ b/panda/board/safety/safety_hyundai.h @@ -1,4 +1,4 @@ -const int HYUNDAI_MAX_STEER = 255; // like stock +const int HYUNDAI_MAX_STEER = 384; // like stock const int HYUNDAI_MAX_RT_DELTA = 112; // max delta torque allowed for real time checks const uint32_t HYUNDAI_RT_INTERVAL = 250000; // 250ms between real time checks const int HYUNDAI_MAX_RATE_UP = 3; diff --git a/panda/board/spi_flasher.h b/panda/board/spi_flasher.h index b0511c14efd2ca..2636bf535a40d8 100644 --- a/panda/board/spi_flasher.h +++ b/panda/board/spi_flasher.h @@ -290,7 +290,7 @@ void soft_flasher_start(void) { // B8,B9: CAN 1 set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1); set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1); - current_board->enable_can_transciever(1, true); + current_board->enable_can_transceiver(1, true); // init can llcan_set_speed(CAN1, 5000, false, false); diff --git a/panda/certs/debugesp b/panda/certs/debugesp deleted file mode 100644 index 789beaac195639..00000000000000 --- a/panda/certs/debugesp +++ /dev/null @@ -1,15 +0,0 @@ ------BEGIN RSA PRIVATE KEY----- -MIICXAIBAAKBgQCjIHvrSCWN0Nec6ozbImYik30PIF7JSWgdwDKTxSJ05RM3pj5E -LQEGt3qcaVrTokO68tpt5Gu1p6ZsNqWg7iVTW9M7Qj7IH45YDzQP/PSRjgSosQA6 -6f5Gokba5QrW38myqimvj+0p+YH+CNGCBRlTUQGCO8uLCspMZneRSLPW9QIDAQAB -AoGADaUn+HRef9BaWMvd4G6uMHI54cwJYbj8NpDfKjExQqnuw5bqWnWRQmiSnwbJ -DC7kj3zE/LBAuj890ot3q1CAWqh47ZICZfoX9Qbi5TpvIHFCGy6YkOliF6iIQhR2 -4+zNKTAA0zNKskOM25PdI+grK1Ni/bEofSA6TrqvEwsmxnkCQQDVp9FUUor2Bo/h -/3oAIP51LTw7vfpztYbJr+BDV63czV2DLXzSwzeNrwH4sA3oy1mjUgMBBgAarNGE -DYlc4H5jAkEAw3UCHzzXPlxkw2QGp7nBly5y3p80Uqc31NuYz8rdX/U8KTngi2No -Ft/SGCEXNpeYbToj+WK3RJJ2Ey0mK8+IxwJAcpGd/5CPsaQNLcw4WK9Yo+8Q2Jxk -G/4gfDCSmqn+smNxnLEcuUwzkwdgkEGgA9BfjeOhdsAH+EXpx90WZrZ/LwJBAK0k -jq+rTqUQZbZsejTEKYjJ/bnV4BzDwoKN0Q1pkLc7X4LJoW74rTFuLgdv8MdMfRtt -IIb/eoeFEpGkMicnHesCQHgR7BTUGBM6Uxam7RCdsgVsxoHBma21E/44ivWUMZzN -3oVt0mPnjS4speOlqwED5pCJ7yw7jwLPFMs8kNxuIKU= ------END RSA PRIVATE KEY----- diff --git a/panda/certs/debugesp.pub b/panda/certs/debugesp.pub deleted file mode 100644 index 3afcf3988ea651..00000000000000 --- a/panda/certs/debugesp.pub +++ /dev/null @@ -1 +0,0 @@ -ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAAAgQCjIHvrSCWN0Nec6ozbImYik30PIF7JSWgdwDKTxSJ05RM3pj5ELQEGt3qcaVrTokO68tpt5Gu1p6ZsNqWg7iVTW9M7Qj7IH45YDzQP/PSRjgSosQA66f5Gokba5QrW38myqimvj+0p+YH+CNGCBRlTUQGCO8uLCspMZneRSLPW9Q== batman@y840 diff --git a/panda/certs/releaseesp.pub b/panda/certs/releaseesp.pub deleted file mode 100644 index 1d1d54bb7e73f4..00000000000000 --- a/panda/certs/releaseesp.pub +++ /dev/null @@ -1 +0,0 @@ -ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAAAgQDN4pVyGuJJSde1l3Fjay8qPxog09DsAJZtYPk+armoYO1L6YKReUTcMNyHQYZZMZFmhCdgjCgTIF2QYWMoP4KSe8l6JF04YPP51dIgefc6UXjtlSI8Pyutr0v9xXjSfsVm3RAJxDSHgzs9AoMsluKCL+LhAR1nd7cuHXITJ80O4w== batman@y840 diff --git a/panda/python/__init__.py b/panda/python/__init__.py index 605977db095a5a..936c975f07a4c5 100644 --- a/panda/python/__init__.py +++ b/panda/python/__init__.py @@ -10,7 +10,6 @@ import subprocess import sys from .dfu import PandaDFU # pylint: disable=import-error -from .esptool import ESPROM, CesantaFlasher # noqa pylint: disable=import-error from .flash_release import flash_release # noqa pylint: disable=import-error from .update import ensure_st_up_to_date # noqa pylint: disable=import-error from .serial import PandaSerial # noqa pylint: disable=import-error @@ -148,6 +147,10 @@ class Panda(object): HW_TYPE_PEDAL = b'\x04' HW_TYPE_UNO = b'\x05' + CLOCK_SOURCE_MODE_DISABLED = 0 + CLOCK_SOURCE_MODE_FREE_RUNNING = 1 + CLOCK_SOURCE_MODE_EXTERNAL_SYNC = 2 + def __init__(self, serial=None, claim=True): self._serial = serial self._handle = None @@ -458,7 +461,7 @@ def set_can_loopback(self, enable): self._handle.controlWrite(Panda.REQUEST_OUT, 0xe5, int(enable), 0, b'') def set_can_enable(self, bus_num, enable): - # sets the can transciever enable pin + # sets the can transceiver enable pin self._handle.controlWrite(Panda.REQUEST_OUT, 0xf4, int(bus_num), int(enable), b'') def set_can_speed_kbps(self, bus, speed): @@ -665,3 +668,11 @@ def get_fan_rpm(self): # ****************** Phone ***************** def set_phone_power(self, enabled): self._handle.controlWrite(Panda.REQUEST_OUT, 0xb3, int(enabled), 0, b'') + + # ************** Clock Source ************** + def set_clock_source_mode(self, mode): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xf5, int(mode), 0, b'') + + # ****************** Siren ***************** + def set_siren(self, enabled): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xf6, int(enabled), 0, b'') diff --git a/panda/python/dfu.py b/panda/python/dfu.py index 658b6a9e8e3b5b..a7f51ecdad6afe 100644 --- a/panda/python/dfu.py +++ b/panda/python/dfu.py @@ -24,7 +24,7 @@ def __init__(self, dfu_serial): self._handle = device.open() self.legacy = "07*128Kg" in self._handle.getASCIIStringDescriptor(4) return - raise Exception("failed to open " + dfu_serial) + raise Exception("failed to open " + dfu_serial if dfu_serial is not None else "DFU device") @staticmethod def list(): diff --git a/panda/python/esptool.py b/panda/python/esptool.py deleted file mode 100755 index 4a7dabfa298803..00000000000000 --- a/panda/python/esptool.py +++ /dev/null @@ -1,1317 +0,0 @@ -#!/usr/bin/env python -# NB: Before sending a PR to change the above line to '#!/usr/bin/env python3', please read https://github.com/themadinventor/esptool/issues/21 -# -# ESP8266 ROM Bootloader Utility -# https://github.com/themadinventor/esptool -# -# Copyright (C) 2014-2016 Fredrik Ahlberg, Angus Gratton, other contributors as noted. -# -# 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 2 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, write to the Free Software Foundation, Inc., 51 Franklin -# Street, Fifth Floor, Boston, MA 02110-1301 USA. - -# pylint: skip-file -# flake8: noqa - -import argparse -import hashlib -import inspect -import json -import os -#import serial -import struct -import subprocess -import sys -import tempfile -import time -#import traceback -import usb1 - -__version__ = "1.2" - -class FakePort(object): - def __init__(self, serial=None): - from panda import Panda - self.panda = Panda(serial) - - # will only work on new st, old ones will stay @ 921600 - self.baudrate = 230400 - - @property - def baudrate(self): - return self.baudrate - - @baudrate.setter - def baudrate(self, x): - print("set baud to", x) - self.panda.set_uart_baud(1, x) - - def write(self, buf): - SEND_STEP = 0x20 - for i in range(0, len(buf), SEND_STEP): - self.panda.serial_write(1, buf[i:i+SEND_STEP]) - - def flushInput(self): - self.panda.serial_clear(1) - - def flushOutput(self): - self.panda.serial_clear(1) - - def read(self, llen): - ret = self.panda._handle.controlRead(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xe0, 1, 0, 1) - if ret == '': - time.sleep(0.1) - ret = self.panda._handle.controlRead(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xe0, 1, 0, 1) - return str(ret) - - def reset(self): - self.panda.esp_reset(1) - - def inWaiting(self): - return False - -class ESPROM(object): - # These are the currently known commands supported by the ROM - ESP_FLASH_BEGIN = 0x02 - ESP_FLASH_DATA = 0x03 - ESP_FLASH_END = 0x04 - ESP_MEM_BEGIN = 0x05 - ESP_MEM_END = 0x06 - ESP_MEM_DATA = 0x07 - ESP_SYNC = 0x08 - ESP_WRITE_REG = 0x09 - ESP_READ_REG = 0x0a - - # Maximum block sized for RAM and Flash writes, respectively. - ESP_RAM_BLOCK = 0x1800 - ESP_FLASH_BLOCK = 0x400 - - # Default baudrate. The ROM auto-bauds, so we can use more or less whatever we want. - ESP_ROM_BAUD = 115200 - - # First byte of the application image - ESP_IMAGE_MAGIC = 0xe9 - - # Initial state for the checksum routine - ESP_CHECKSUM_MAGIC = 0xef - - # OTP ROM addresses - ESP_OTP_MAC0 = 0x3ff00050 - ESP_OTP_MAC1 = 0x3ff00054 - ESP_OTP_MAC3 = 0x3ff0005c - - # Flash sector size, minimum unit of erase. - ESP_FLASH_SECTOR = 0x1000 - - def __init__(self, port=None, baud=ESP_ROM_BAUD): - self._port = FakePort(port) - self._slip_reader = slip_reader(self._port) - - """ Read a SLIP packet from the serial port """ - def read(self): - return next(self._slip_reader) - - """ Write bytes to the serial port while performing SLIP escaping """ - def write(self, packet): - buf = '\xc0' \ - + (packet.replace('\xdb','\xdb\xdd').replace('\xc0','\xdb\xdc')) \ - + '\xc0' - self._port.write(buf) - - """ Calculate checksum of a blob, as it is defined by the ROM """ - @staticmethod - def checksum(data, state=ESP_CHECKSUM_MAGIC): - for b in data: - state ^= ord(b) - return state - - """ Send a request and read the response """ - def command(self, op=None, data=None, chk=0): - if op is not None: - pkt = struct.pack('> 16) & 0xff, (mac3 >> 8) & 0xff, mac3 & 0xff) - elif ((mac1 >> 16) & 0xff) == 0: - oui = (0x18, 0xfe, 0x34) - elif ((mac1 >> 16) & 0xff) == 1: - oui = (0xac, 0xd0, 0x74) - else: - raise FatalError("Unknown OUI") - return oui + ((mac1 >> 8) & 0xff, mac1 & 0xff, (mac0 >> 24) & 0xff) - - """ Read Chip ID from OTP ROM - see http://esp8266-re.foogod.com/wiki/System_get_chip_id_%28IoT_RTOS_SDK_0.9.9%29 """ - def chip_id(self): - id0 = self.read_reg(self.ESP_OTP_MAC0) - id1 = self.read_reg(self.ESP_OTP_MAC1) - return (id0 >> 24) | ((id1 & 0xffffff) << 8) - - """ Read SPI flash manufacturer and device id """ - def flash_id(self): - self.flash_begin(0, 0) - self.write_reg(0x60000240, 0x0, 0xffffffff) - self.write_reg(0x60000200, 0x10000000, 0xffffffff) - flash_id = self.read_reg(0x60000240) - return flash_id - - """ Abuse the loader protocol to force flash to be left in write mode """ - def flash_unlock_dio(self): - # Enable flash write mode - self.flash_begin(0, 0) - # Reset the chip rather than call flash_finish(), which would have - # write protected the chip again (why oh why does it do that?!) - self.mem_begin(0,0,0,0x40100000) - self.mem_finish(0x40000080) - - """ Perform a chip erase of SPI flash """ - def flash_erase(self): - # Trick ROM to initialize SFlash - self.flash_begin(0, 0) - - # This is hacky: we don't have a custom stub, instead we trick - # the bootloader to jump to the SPIEraseChip() routine and then halt/crash - # when it tries to boot an unconfigured system. - self.mem_begin(0,0,0,0x40100000) - self.mem_finish(0x40004984) - - # Yup - there's no good way to detect if we succeeded. - # It it on the other hand unlikely to fail. - - def run_stub(self, stub, params, read_output=True): - stub = dict(stub) - stub['code'] = unhexify(stub['code']) - if 'data' in stub: - stub['data'] = unhexify(stub['data']) - - if stub['num_params'] != len(params): - raise FatalError('Stub requires %d params, %d provided' - % (stub['num_params'], len(params))) - - params = struct.pack('<' + ('I' * stub['num_params']), *params) - pc = params + stub['code'] - - # Upload - self.mem_begin(len(pc), 1, len(pc), stub['params_start']) - self.mem_block(pc, 0) - if 'data' in stub: - self.mem_begin(len(stub['data']), 1, len(stub['data']), stub['data_start']) - self.mem_block(stub['data'], 0) - self.mem_finish(stub['entry']) - - if read_output: - print('Stub executed, reading response:') - while True: - p = self.read() - print(hexify(p)) - if p == '': - return - - -class ESPBOOTLOADER(object): - """ These are constants related to software ESP bootloader, working with 'v2' image files """ - - # First byte of the "v2" application image - IMAGE_V2_MAGIC = 0xea - - # First 'segment' value in a "v2" application image, appears to be a constant version value? - IMAGE_V2_SEGMENT = 4 - - -def LoadFirmwareImage(filename): - """ Load a firmware image, without knowing what kind of file (v1 or v2) it is. - - Returns a BaseFirmwareImage subclass, either ESPFirmwareImage (v1) or OTAFirmwareImage (v2). - """ - with open(filename, 'rb') as f: - magic = ord(f.read(1)) - f.seek(0) - if magic == ESPROM.ESP_IMAGE_MAGIC: - return ESPFirmwareImage(f) - elif magic == ESPBOOTLOADER.IMAGE_V2_MAGIC: - return OTAFirmwareImage(f) - else: - raise FatalError("Invalid image magic number: %d" % magic) - - -class BaseFirmwareImage(object): - """ Base class with common firmware image functions """ - def __init__(self): - self.segments = [] - self.entrypoint = 0 - - def add_segment(self, addr, data, pad_to=4): - """ Add a segment to the image, with specified address & data - (padded to a boundary of pad_to size) """ - # Data should be aligned on word boundary - l = len(data) - if l % pad_to: - data += b"\x00" * (pad_to - l % pad_to) - if l > 0: - self.segments.append((addr, len(data), data)) - - def load_segment(self, f, is_irom_segment=False): - """ Load the next segment from the image file """ - (offset, size) = struct.unpack(' 0x40200000 or offset < 0x3ffe0000 or size > 65536: - raise FatalError('Suspicious segment 0x%x, length %d' % (offset, size)) - segment_data = f.read(size) - if len(segment_data) < size: - raise FatalError('End of file reading segment 0x%x, length %d (actual length %d)' % (offset, size, len(segment_data))) - segment = (offset, size, segment_data) - self.segments.append(segment) - return segment - - def save_segment(self, f, segment, checksum=None): - """ Save the next segment to the image file, return next checksum value if provided """ - (offset, size, data) = segment - f.write(struct.pack(' 16: - raise FatalError('Invalid firmware image magic=%d segments=%d' % (magic, segments)) - - for i in range(segments): - self.load_segment(load_file) - self.checksum = self.read_checksum(load_file) - - def save(self, filename): - with open(filename, 'wb') as f: - self.write_v1_header(f, self.segments) - checksum = ESPROM.ESP_CHECKSUM_MAGIC - for segment in self.segments: - checksum = self.save_segment(f, segment, checksum) - self.append_checksum(f, checksum) - - -class OTAFirmwareImage(BaseFirmwareImage): - """ 'Version 2' firmware image, segments loaded by software bootloader stub - (ie Espressif bootloader or rboot) - """ - def __init__(self, load_file=None): - super(OTAFirmwareImage, self).__init__() - self.version = 2 - if load_file is not None: - (magic, segments, first_flash_mode, first_flash_size_freq, first_entrypoint) = struct.unpack(' 16: - raise FatalError('Invalid V2 second header magic=%d segments=%d' % (magic, segments)) - - # load all the usual segments - for _ in range(segments): - self.load_segment(load_file) - self.checksum = self.read_checksum(load_file) - - def save(self, filename): - with open(filename, 'wb') as f: - # Save first header for irom0 segment - f.write(struct.pack(' 0: - esp._port.baudrate = baud_rate - # Read the greeting. - p = esp.read() - if p != 'OHAI': - raise FatalError('Failed to connect to the flasher (got %s)' % hexify(p)) - - def flash_write(self, addr, data, show_progress=False): - assert addr % self._esp.ESP_FLASH_SECTOR == 0, 'Address must be sector-aligned' - assert len(data) % self._esp.ESP_FLASH_SECTOR == 0, 'Length must be sector-aligned' - sys.stdout.write('Writing %d @ 0x%x... ' % (len(data), addr)) - sys.stdout.flush() - self._esp.write(struct.pack(' length: - raise FatalError('Read more than expected') - p = self._esp.read() - if len(p) != 16: - raise FatalError('Expected digest, got: %s' % hexify(p)) - expected_digest = hexify(p).upper() - digest = hashlib.md5(data).hexdigest().upper() - print() - if digest != expected_digest: - raise FatalError('Digest mismatch: expected %s, got %s' % (expected_digest, digest)) - p = self._esp.read() - if len(p) != 1: - raise FatalError('Expected status, got: %s' % hexify(p)) - status_code = struct.unpack(', ) or a single -# argument. - -def load_ram(esp, args): - image = LoadFirmwareImage(args.filename) - - print('RAM boot...') - for (offset, size, data) in image.segments: - print('Downloading %d bytes at %08x...' % (size, offset), end=' ') - sys.stdout.flush() - esp.mem_begin(size, div_roundup(size, esp.ESP_RAM_BLOCK), esp.ESP_RAM_BLOCK, offset) - - seq = 0 - while len(data) > 0: - esp.mem_block(data[0:esp.ESP_RAM_BLOCK], seq) - data = data[esp.ESP_RAM_BLOCK:] - seq += 1 - print('done!') - - print('All segments done, executing at %08x' % image.entrypoint) - esp.mem_finish(image.entrypoint) - - -def read_mem(esp, args): - print('0x%08x = 0x%08x' % (args.address, esp.read_reg(args.address))) - - -def write_mem(esp, args): - esp.write_reg(args.address, args.value, args.mask, 0) - print('Wrote %08x, mask %08x to %08x' % (args.value, args.mask, args.address)) - - -def dump_mem(esp, args): - f = open(args.filename, 'wb') - for i in range(args.size / 4): - d = esp.read_reg(args.address + (i * 4)) - f.write(struct.pack('> 16 - args.flash_size = {18: '2m', 19: '4m', 20: '8m', 21: '16m', 22: '32m'}.get(size_id) - if args.flash_size is None: - print('Warning: Could not auto-detect Flash size (FlashID=0x%x, SizeID=0x%x), defaulting to 4m' % (flash_id, size_id)) - args.flash_size = '4m' - else: - print('Auto-detected Flash size:', args.flash_size) - - -def write_flash(esp, args): - detect_flash_size(esp, args) - flash_mode = {'qio':0, 'qout':1, 'dio':2, 'dout': 3}[args.flash_mode] - flash_size_freq = {'4m':0x00, '2m':0x10, '8m':0x20, '16m':0x30, '32m':0x40, '16m-c1': 0x50, '32m-c1':0x60, '32m-c2':0x70}[args.flash_size] - flash_size_freq += {'40m':0, '26m':1, '20m':2, '80m': 0xf}[args.flash_freq] - flash_params = struct.pack('BB', flash_mode, flash_size_freq) - - flasher = CesantaFlasher(esp, args.baud) - - for address, argfile in args.addr_filename: - image = argfile.read() - argfile.seek(0) # rewind in case we need it again - if address + len(image) > int(args.flash_size.split('m')[0]) * (1 << 17): - print('WARNING: Unlikely to work as data goes beyond end of flash. Hint: Use --flash_size') - # Fix sflash config data. - if address == 0 and image[0] == '\xe9': - print('Flash params set to 0x%02x%02x' % (flash_mode, flash_size_freq)) - image = image[0:2] + flash_params + image[4:] - # Pad to sector size, which is the minimum unit of writing (erasing really). - if len(image) % esp.ESP_FLASH_SECTOR != 0: - image += '\xff' * (esp.ESP_FLASH_SECTOR - (len(image) % esp.ESP_FLASH_SECTOR)) - t = time.time() - flasher.flash_write(address, image, not args.no_progress) - t = time.time() - t - print('\rWrote %d bytes at 0x%x in %.1f seconds (%.1f kbit/s)...' - % (len(image), address, t, len(image) / t * 8 / 1000)) - print('Leaving...') - if args.verify: - print('Verifying just-written flash...') - _verify_flash(flasher, args, flash_params) - flasher.boot_fw() - - -def image_info(args): - image = LoadFirmwareImage(args.filename) - print('Image version: %d' % image.version) - print(('Entry point: %08x' % image.entrypoint) if image.entrypoint != 0 else 'Entry point not set') - print('%d segments' % len(image.segments)) - print() - checksum = ESPROM.ESP_CHECKSUM_MAGIC - for (idx, (offset, size, data)) in enumerate(image.segments): - if image.version == 2 and idx == 0: - print('Segment 1: %d bytes IROM0 (no load address)' % size) - else: - print('Segment %d: %5d bytes at %08x' % (idx + 1, size, offset)) - checksum = ESPROM.checksum(data, checksum) - print() - print('Checksum: %02x (%s)' % (image.checksum, 'valid' if image.checksum == checksum else 'invalid!')) - - -def make_image(args): - image = ESPFirmwareImage() - if len(args.segfile) == 0: - raise FatalError('No segments specified') - if len(args.segfile) != len(args.segaddr): - raise FatalError('Number of specified files does not match number of specified addresses') - for (seg, addr) in zip(args.segfile, args.segaddr): - data = open(seg, 'rb').read() - image.add_segment(addr, data) - image.entrypoint = args.entrypoint - image.save(args.output) - - -def elf2image(args): - e = ELFFile(args.input) - if args.version == '1': - image = ESPFirmwareImage() - else: - image = OTAFirmwareImage() - irom_data = e.load_section('.irom0.text') - if len(irom_data) == 0: - raise FatalError(".irom0.text section not found in ELF file - can't create V2 image.") - image.add_segment(0, irom_data, 16) - image.entrypoint = e.get_entry_point() - for section, start in ((".text", "_text_start"), (".data", "_data_start"), (".rodata", "_rodata_start")): - data = e.load_section(section) - image.add_segment(e.get_symbol_addr(start), data) - - image.flash_mode = {'qio':0, 'qout':1, 'dio':2, 'dout': 3}[args.flash_mode] - image.flash_size_freq = {'4m':0x00, '2m':0x10, '8m':0x20, '16m':0x30, '32m':0x40, '16m-c1': 0x50, '32m-c1':0x60, '32m-c2':0x70}[args.flash_size] - image.flash_size_freq += {'40m':0, '26m':1, '20m':2, '80m': 0xf}[args.flash_freq] - - irom_offs = e.get_symbol_addr("_irom0_text_start") - 0x40200000 - - if args.version == '1': - if args.output is None: - args.output = args.input + '-' - image.save(args.output + "0x00000.bin") - data = e.load_section(".irom0.text") - if irom_offs < 0: - raise FatalError('Address of symbol _irom0_text_start in ELF is located before flash mapping address. Bad linker script?') - if (irom_offs & 0xFFF) != 0: # irom0 isn't flash sector aligned - print("WARNING: irom0 section offset is 0x%08x. ELF is probably linked for 'elf2image --version=2'" % irom_offs) - with open(args.output + "0x%05x.bin" % irom_offs, "wb") as f: - f.write(data) - f.close() - else: # V2 OTA image - if args.output is None: - args.output = "%s-0x%05x.bin" % (os.path.splitext(args.input)[0], irom_offs & ~(ESPROM.ESP_FLASH_SECTOR - 1)) - image.save(args.output) - - -def read_mac(esp, args): - mac = esp.read_mac() - print('MAC: %s' % ':'.join(['%02x' % x for x in mac])) - - -def chip_id(esp, args): - chipid = esp.chip_id() - print('Chip ID: 0x%08x' % chipid) - - -def erase_flash(esp, args): - flasher = CesantaFlasher(esp, args.baud) - print('Erasing flash (this may take a while)...') - t = time.time() - flasher.flash_erase_chip() - t = time.time() - t - print('Erase took %.1f seconds' % t) - - -def run(esp, args): - esp.run() - - -def flash_id(esp, args): - flash_id = esp.flash_id() - esp.flash_finish(False) - print('Manufacturer: %02x' % (flash_id & 0xff)) - print('Device: %02x%02x' % ((flash_id >> 8) & 0xff, (flash_id >> 16) & 0xff)) - - -def read_flash(esp, args): - flasher = CesantaFlasher(esp, args.baud) - t = time.time() - data = flasher.flash_read(args.address, args.size, not args.no_progress) - t = time.time() - t - print('\rRead %d bytes at 0x%x in %.1f seconds (%.1f kbit/s)...' - % (len(data), args.address, t, len(data) / t * 8 / 1000)) - open(args.filename, 'wb').write(data) - - -def _verify_flash(flasher, args, flash_params=None): - differences = False - for address, argfile in args.addr_filename: - image = argfile.read() - argfile.seek(0) # rewind in case we need it again - if address == 0 and image[0] == '\xe9' and flash_params is not None: - image = image[0:2] + flash_params + image[4:] - image_size = len(image) - print('Verifying 0x%x (%d) bytes @ 0x%08x in flash against %s...' % (image_size, image_size, address, argfile.name)) - # Try digest first, only read if there are differences. - digest, _ = flasher.flash_digest(address, image_size) - digest = hexify(digest).upper() - expected_digest = hashlib.md5(image).hexdigest().upper() - if digest == expected_digest: - print('-- verify OK (digest matched)') - continue - else: - differences = True - if getattr(args, 'diff', 'no') != 'yes': - print('-- verify FAILED (digest mismatch)') - continue - - flash = flasher.flash_read(address, image_size) - assert flash != image - diff = [i for i in range(image_size) if flash[i] != image[i]] - print('-- verify FAILED: %d differences, first @ 0x%08x' % (len(diff), address + diff[0])) - for d in diff: - print(' %08x %02x %02x' % (address + d, ord(flash[d]), ord(image[d]))) - if differences: - raise FatalError("Verify failed.") - - -def verify_flash(esp, args, flash_params=None): - flasher = CesantaFlasher(esp) - _verify_flash(flasher, args, flash_params) - - -def version(args): - print(__version__) - -# -# End of operations functions -# - - -def main(): - parser = argparse.ArgumentParser(description='esptool.py v%s - ESP8266 ROM Bootloader Utility' % __version__, prog='esptool') - - parser.add_argument( - '--port', '-p', - help='Serial port device', - default=os.environ.get('ESPTOOL_PORT', None)) - - parser.add_argument( - '--baud', '-b', - help='Serial port baud rate used when flashing/reading', - type=arg_auto_int, - default=os.environ.get('ESPTOOL_BAUD', ESPROM.ESP_ROM_BAUD)) - - subparsers = parser.add_subparsers( - dest='operation', - help='Run esptool {command} -h for additional help') - - parser_load_ram = subparsers.add_parser( - 'load_ram', - help='Download an image to RAM and execute') - parser_load_ram.add_argument('filename', help='Firmware image') - - parser_dump_mem = subparsers.add_parser( - 'dump_mem', - help='Dump arbitrary memory to disk') - parser_dump_mem.add_argument('address', help='Base address', type=arg_auto_int) - parser_dump_mem.add_argument('size', help='Size of region to dump', type=arg_auto_int) - parser_dump_mem.add_argument('filename', help='Name of binary dump') - - parser_read_mem = subparsers.add_parser( - 'read_mem', - help='Read arbitrary memory location') - parser_read_mem.add_argument('address', help='Address to read', type=arg_auto_int) - - parser_write_mem = subparsers.add_parser( - 'write_mem', - help='Read-modify-write to arbitrary memory location') - parser_write_mem.add_argument('address', help='Address to write', type=arg_auto_int) - parser_write_mem.add_argument('value', help='Value', type=arg_auto_int) - parser_write_mem.add_argument('mask', help='Mask of bits to write', type=arg_auto_int) - - def add_spi_flash_subparsers(parent, auto_detect=False): - """ Add common parser arguments for SPI flash properties """ - parent.add_argument('--flash_freq', '-ff', help='SPI Flash frequency', - choices=['40m', '26m', '20m', '80m'], - default=os.environ.get('ESPTOOL_FF', '40m')) - parent.add_argument('--flash_mode', '-fm', help='SPI Flash mode', - choices=['qio', 'qout', 'dio', 'dout'], - default=os.environ.get('ESPTOOL_FM', 'qio')) - choices = ['4m', '2m', '8m', '16m', '32m', '16m-c1', '32m-c1', '32m-c2'] - default = '4m' - if auto_detect: - default = 'detect' - choices.insert(0, 'detect') - parent.add_argument('--flash_size', '-fs', help='SPI Flash size in Mbit', type=str.lower, - choices=choices, - default=os.environ.get('ESPTOOL_FS', default)) - - parser_write_flash = subparsers.add_parser( - 'write_flash', - help='Write a binary blob to flash') - parser_write_flash.add_argument('addr_filename', metavar='
', help='Address followed by binary filename, separated by space', - action=AddrFilenamePairAction) - add_spi_flash_subparsers(parser_write_flash, auto_detect=True) - parser_write_flash.add_argument('--no-progress', '-p', help='Suppress progress output', action="store_true") - parser_write_flash.add_argument('--verify', help='Verify just-written data (only necessary if very cautious, data is already CRCed', action='store_true') - - subparsers.add_parser( - 'run', - help='Run application code in flash') - - parser_image_info = subparsers.add_parser( - 'image_info', - help='Dump headers from an application image') - parser_image_info.add_argument('filename', help='Image file to parse') - - parser_make_image = subparsers.add_parser( - 'make_image', - help='Create an application image from binary files') - parser_make_image.add_argument('output', help='Output image file') - parser_make_image.add_argument('--segfile', '-f', action='append', help='Segment input file') - parser_make_image.add_argument('--segaddr', '-a', action='append', help='Segment base address', type=arg_auto_int) - parser_make_image.add_argument('--entrypoint', '-e', help='Address of entry point', type=arg_auto_int, default=0) - - parser_elf2image = subparsers.add_parser( - 'elf2image', - help='Create an application image from ELF file') - parser_elf2image.add_argument('input', help='Input ELF file') - parser_elf2image.add_argument('--output', '-o', help='Output filename prefix (for version 1 image), or filename (for version 2 single image)', type=str) - parser_elf2image.add_argument('--version', '-e', help='Output image version', choices=['1','2'], default='1') - add_spi_flash_subparsers(parser_elf2image) - - subparsers.add_parser( - 'read_mac', - help='Read MAC address from OTP ROM') - - subparsers.add_parser( - 'chip_id', - help='Read Chip ID from OTP ROM') - - subparsers.add_parser( - 'flash_id', - help='Read SPI flash manufacturer and device ID') - - parser_read_flash = subparsers.add_parser( - 'read_flash', - help='Read SPI flash content') - parser_read_flash.add_argument('address', help='Start address', type=arg_auto_int) - parser_read_flash.add_argument('size', help='Size of region to dump', type=arg_auto_int) - parser_read_flash.add_argument('filename', help='Name of binary dump') - parser_read_flash.add_argument('--no-progress', '-p', help='Suppress progress output', action="store_true") - - parser_verify_flash = subparsers.add_parser( - 'verify_flash', - help='Verify a binary blob against flash') - parser_verify_flash.add_argument('addr_filename', help='Address and binary file to verify there, separated by space', - action=AddrFilenamePairAction) - parser_verify_flash.add_argument('--diff', '-d', help='Show differences', - choices=['no', 'yes'], default='no') - - subparsers.add_parser( - 'erase_flash', - help='Perform Chip Erase on SPI flash') - - subparsers.add_parser( - 'version', help='Print esptool version') - - # internal sanity check - every operation matches a module function of the same name - for operation in list(subparsers.choices.keys()): - assert operation in globals(), "%s should be a module function" % operation - - args = parser.parse_args() - - print('esptool.py v%s' % __version__) - - # operation function can take 1 arg (args), 2 args (esp, arg) - # or be a member function of the ESPROM class. - - operation_func = globals()[args.operation] - operation_args,_,_,_ = inspect.getargspec(operation_func) - if operation_args[0] == 'esp': # operation function takes an ESPROM connection object - initial_baud = min(ESPROM.ESP_ROM_BAUD, args.baud) # don't sync faster than the default baud rate - esp = ESPROM(args.port, initial_baud) - esp.connect() - operation_func(esp, args) - else: - operation_func(args) - - -class AddrFilenamePairAction(argparse.Action): - """ Custom parser class for the address/filename pairs passed as arguments """ - def __init__(self, option_strings, dest, nargs='+', **kwargs): - super(AddrFilenamePairAction, self).__init__(option_strings, dest, nargs, **kwargs) - - def __call__(self, parser, namespace, values, option_string=None): - # validate pair arguments - pairs = [] - for i in range(0,len(values),2): - try: - address = int(values[i],0) - except ValueError: - raise argparse.ArgumentError(self,'Address "%s" must be a number' % values[i]) - try: - argfile = open(values[i + 1], 'rb') - except IOError as e: - raise argparse.ArgumentError(self, e) - except IndexError: - raise argparse.ArgumentError(self,'Must be pairs of an address and the binary filename to write there') - pairs.append((address, argfile)) - setattr(namespace, self.dest, pairs) - -# This is "wrapped" stub_flasher.c, to be loaded using run_stub. -_CESANTA_FLASHER_STUB = """\ -{"code_start": 1074790404, "code": "080000601C000060000000601000006031FCFF71FCFF\ -81FCFFC02000680332D218C020004807404074DCC48608005823C0200098081BA5A9239245005803\ -1B555903582337350129230B446604DFC6F3FF21EEFFC0200069020DF0000000010078480040004A\ -0040B449004012C1F0C921D911E901DD0209312020B4ED033C2C56C2073020B43C3C56420701F5FF\ -C000003C4C569206CD0EEADD860300202C4101F1FFC0000056A204C2DCF0C02DC0CC6CCAE2D1EAFF\ -0606002030F456D3FD86FBFF00002020F501E8FFC00000EC82D0CCC0C02EC0C73DEB2ADC46030020\ -2C4101E1FFC00000DC42C2DCF0C02DC056BCFEC602003C5C8601003C6C4600003C7C08312D0CD811\ -C821E80112C1100DF0000C180000140010400C0000607418000064180000801800008C1800008418\ -0000881800009018000018980040880F0040A80F0040349800404C4A0040740F0040800F0040980F\ -00400099004012C1E091F5FFC961CD0221EFFFE941F9310971D9519011C01A223902E2D1180C0222\ -6E1D21E4FF31E9FF2AF11A332D0F42630001EAFFC00000C030B43C2256A31621E1FF1A2228022030\ -B43C3256B31501ADFFC00000DD023C4256ED1431D6FF4D010C52D90E192E126E0101DDFFC0000021\ -D2FF32A101C020004802303420C0200039022C0201D7FFC00000463300000031CDFF1A333803D023\ -C03199FF27B31ADC7F31CBFF1A3328030198FFC0000056C20E2193FF2ADD060E000031C6FF1A3328\ -030191FFC0000056820DD2DD10460800000021BEFF1A2228029CE231BCFFC020F51A33290331BBFF\ -C02C411A332903C0F0F4222E1D22D204273D9332A3FFC02000280E27B3F721ABFF381E1A2242A400\ -01B5FFC00000381E2D0C42A40001B3FFC0000056120801B2FFC00000C02000280EC2DC0422D2FCC0\ -2000290E01ADFFC00000222E1D22D204226E1D281E22D204E7B204291E860000126E012198FF32A0\ -042A21C54C003198FF222E1D1A33380337B202C6D6FF2C02019FFFC000002191FF318CFF1A223A31\ -019CFFC00000218DFF1C031A22C549000C02060300003C528601003C624600003C72918BFF9A1108\ -71C861D851E841F83112C1200DF00010000068100000581000007010000074100000781000007C10\ -0000801000001C4B0040803C004091FDFF12C1E061F7FFC961E941F9310971D9519011C01A662906\ -21F3FFC2D1101A22390231F2FF0C0F1A33590331EAFFF26C1AED045C2247B3028636002D0C016DFF\ -C0000021E5FF41EAFF2A611A4469040622000021E4FF1A222802F0D2C0D7BE01DD0E31E0FF4D0D1A\ -3328033D0101E2FFC00000561209D03D2010212001DFFFC000004D0D2D0C3D01015DFFC0000041D5\ -FFDAFF1A444804D0648041D2FF1A4462640061D1FF106680622600673F1331D0FF10338028030C43\ -853A002642164613000041CAFF222C1A1A444804202FC047328006F6FF222C1A273F3861C2FF222C\ -1A1A6668066732B921BDFF3D0C1022800148FFC0000021BAFF1C031A2201BFFFC000000C02460300\ -5C3206020000005C424600005C5291B7FF9A110871C861D851E841F83112C1200DF0B0100000C010\ -0000D010000012C1E091FEFFC961D951E9410971F931CD039011C0ED02DD0431A1FF9C1422A06247\ -B302062D0021F4FF1A22490286010021F1FF1A223902219CFF2AF12D0F011FFFC00000461C0022D1\ -10011CFFC0000021E9FFFD0C1A222802C7B20621E6FF1A22F8022D0E3D014D0F0195FFC000008C52\ -22A063C6180000218BFF3D01102280F04F200111FFC00000AC7D22D1103D014D0F010DFFC0000021\ -D6FF32D110102280010EFFC0000021D3FF1C031A220185FFC00000FAEEF0CCC056ACF821CDFF317A\ -FF1A223A310105FFC0000021C9FF1C031A22017CFFC000002D0C91C8FF9A110871C861D851E841F8\ -3112C1200DF0000200600000001040020060FFFFFF0012C1E00C02290131FAFF21FAFF026107C961\ -C02000226300C02000C80320CC10564CFF21F5FFC02000380221F4FF20231029010C432D010163FF\ -C0000008712D0CC86112C1200DF00080FE3F8449004012C1D0C9A109B17CFC22C1110C13C51C0026\ -1202463000220111C24110B68202462B0031F5FF3022A02802A002002D011C03851A0066820A2801\ -32210105A6FF0607003C12C60500000010212032A01085180066A20F2221003811482105B3FF2241\ -10861A004C1206FDFF2D011C03C5160066B20E280138114821583185CFFF06F7FF005C1286F5FF00\ -10212032A01085140066A20D2221003811482105E1FF06EFFF0022A06146EDFF45F0FFC6EBFF0000\ -01D2FFC0000006E9FF000C022241100C1322C110C50F00220111060600000022C1100C13C50E0022\ -011132C2FA303074B6230206C8FF08B1C8A112C1300DF0000000000010404F484149007519031027\ -000000110040A8100040BC0F0040583F0040CC2E00401CE20040D83900408000004021F4FF12C1E0\ -C961C80221F2FF097129010C02D951C91101F4FFC0000001F3FFC00000AC2C22A3E801F2FFC00000\ -21EAFFC031412A233D0C01EFFFC000003D0222A00001EDFFC00000C1E4FF2D0C01E8FFC000002D01\ -32A004450400C5E7FFDD022D0C01E3FFC00000666D1F4B2131DCFF4600004B22C0200048023794F5\ -31D9FFC0200039023DF08601000001DCFFC000000871C861D85112C1200DF000000012C1F0026103\ -01EAFEC00000083112C1100DF000643B004012C1D0E98109B1C9A1D991F97129013911E2A0C001FA\ -FFC00000CD02E792F40C0DE2A0C0F2A0DB860D00000001F4FFC00000204220E71240F7921C226102\ -01EFFFC0000052A0DC482157120952A0DD571205460500004D0C3801DA234242001BDD3811379DC5\ -C6000000000C0DC2A0C001E3FFC00000C792F608B12D0DC8A1D891E881F87112C1300DF00000", "\ -entry": 1074792180, "num_params": 1, "params_start": 1074790400, "data": "FE0510\ -401A0610403B0610405A0610407A061040820610408C0610408C061040", "data_start": 10736\ -43520} -""" - -if __name__ == '__main__': - try: - main() - except FatalError as e: - print('\nA fatal error occurred: %s' % e) - sys.exit(2) diff --git a/panda/python/flash_release.py b/panda/python/flash_release.py index 961a83a0d8de97..6e77d6a7f61a6d 100755 --- a/panda/python/flash_release.py +++ b/panda/python/flash_release.py @@ -7,7 +7,7 @@ import io def flash_release(path=None, st_serial=None): - from panda import Panda, PandaDFU, ESPROM, CesantaFlasher + from panda import Panda, PandaDFU from zipfile import ZipFile def status(x): @@ -23,33 +23,28 @@ def status(x): st_serial = panda_list[0] print("Using panda with serial %s" % st_serial) - if path is not None: + if path is None: print("Fetching latest firmware from github.com/commaai/panda-artifacts") r = requests.get("https://raw.githubusercontent.com/commaai/panda-artifacts/master/latest.json") url = json.loads(r.text)['url'] r = requests.get(url) print("Fetching firmware from %s" % url) - path = io.StringIO(r.content) + path = io.BytesIO(r.content) zf = ZipFile(path) zf.printdir() - version = zf.read("version") - status("0. Preparing to flash " + version) + version = zf.read("version").decode() + status("0. Preparing to flash " + str(version)) code_bootstub = zf.read("bootstub.panda.bin") code_panda = zf.read("panda.bin") - code_boot_15 = zf.read("boot_v1.5.bin") - code_boot_15 = code_boot_15[0:2] + "\x00\x30" + code_boot_15[4:] - - code_user1 = zf.read("user1.bin") - code_user2 = zf.read("user2.bin") - # enter DFU mode status("1. Entering DFU mode") panda = Panda(st_serial) - panda.enter_bootloader() + panda.reset(enter_bootstub=True) + panda.reset(enter_bootloader=True) time.sleep(1) # program bootstub @@ -64,29 +59,8 @@ def status(x): panda.flash(code=code_panda) panda.close() - # flashing ESP - if panda.is_white(): - status("4. Flashing ESP (slow!)") - - def align(x, sz=0x1000): - x + "\xFF" * ((sz - len(x)) % sz) - - esp = ESPROM(st_serial) - esp.connect() - flasher = CesantaFlasher(esp, 230400) - flasher.flash_write(0x0, align(code_boot_15), True) - flasher.flash_write(0x1000, align(code_user1), True) - flasher.flash_write(0x81000, align(code_user2), True) - flasher.flash_write(0x3FE000, "\xFF" * 0x1000) - flasher.boot_fw() - del flasher - del esp - time.sleep(1) - else: - status("4. No ESP in non-white panda") - # check for connection - status("5. Verifying version") + status("4. Verifying version") panda = Panda(st_serial) my_version = panda.get_version() print("dongle id: %s" % panda.get_serial()[0]) diff --git a/rednose/helpers/__init__.py b/rednose/helpers/__init__.py index 1588a4338dbb67..aba6b41fe902b9 100644 --- a/rednose/helpers/__init__.py +++ b/rednose/helpers/__init__.py @@ -1,4 +1,5 @@ import os +import platform from cffi import FFI TEMPLATE_DIR = os.path.abspath(os.path.join(os.path.dirname(__file__), '..', 'templates')) @@ -13,7 +14,8 @@ def write_code(folder, name, code, header): def load_code(folder, name): - shared_fn = os.path.join(folder, f"lib{name}.so") + shared_ext = "dylib" if platform.system() == "Darwin" else "so" + shared_fn = os.path.join(folder, f"lib{name}.{shared_ext}") header_fn = os.path.join(folder, f"{name}.h") with open(header_fn) as f: diff --git a/selfdrive/assets/offroad/circled-checkmark.png b/selfdrive/assets/offroad/circled-checkmark.png new file mode 100644 index 0000000000000000000000000000000000000000..bc6b49585d098ca7d82d62a0fb64fa5f3642954c GIT binary patch literal 2236 zcmV;t2t)UYP)+E3`p7_>8uK3-jlRb(hm6oT$lXA1<5bzXmEB^DIUO?~ktk12PjG+?x zM}gHqd&4oHJ0o3`?9;$Cz)1J^`GZic5@WAH^nsVPGAwpbgyS0`~%k z3h>(oe6Vg}^MKcK5*i171k9;dGIQ5MqOn33OH>$u%s3u#W-IGyi~w> zeW?j_lkf99il6dx5B7Bfn1&CP^1OZ9fSy!}9r-4LcYx0(QCb6lE66tkKS7Gw79VoN z@Gs!}1oqVmU=gr8hdtk@s%U`t6u$%ba3b4k2hb0^5wU3$SXNd+FR&}3;GZXw(;CQ} z_h!VloxrRz!oMF8{2yRZ4R*B!_|->j%v)1b=(*UR=uu9D?V1RH&tp3&&4NtLRcT_ zI6Knuf!eH04B+~J4f`Vfeqh*tm{zGreBLvJQDA;;mL>!~xDCZ;Z$V_gmz8;$;(CO7WE&QM)bo3#mn-#!XqFF7_VfmMc#5hiXs0iQ7% z50NlOP#1uUf%gJ7j02bFlyfrhuHlc%B&jQFZv}XR&bg7QhSdrDp#2L;9|$yAfoCsC`gTEin~i79cn)~Wcr`y!P-$BM+-z_^ z0GwSy=3+zUo<^fnjYeZkq5Q#Q03QMN8~kr5DR)L@dkB33mKzQJlG@l*z%R~UFu4D$ zqWr%avX^#A`jF9oM-}BY;~q(&4Trx;`g%qA)=M+LOTOkd1apbfDFC06bVuOvn4}w= zbNef*`M2?`H|Dql6_qCkaGIn?)r<%x<1Xji3kg(NwnrUzFad$octp~ffoIQ2x<8Q~ z>y4cq`maq%0AG{z`M~3SlD_1eJK7E|U9#UQ>uqc+@ENsG)(J_sIOp~xRB2Ui?(b6M zTTV!%H1KQX^^&>+O&)O0J(F0iIrdMJ?YN=`HzY~;8j@A=Gu&g&xvI;y`y_=*EdD6z zn-%4^!fD2{1F-}Ekhna%SAe^6Uhy10Ycm3Nr0WK83wv1ci3!nc)A1u2dp<_jx(uL41drg zgm-`{$DZ=?wm#G2^A`9+vLTF8;(!PKwYN4K-=ArL`S@bR5DJGgCHS6&oshn+vF*3l}uIReZpNoWanUCP_Wv)5?Dc`M2m z-DI6(WnMq7Kx`#;*=Q>qp>84BV0i^{-zn(0ua?zSkk?YG6c%Pe zE{hoRG9^=n_?gxk4kqH4WptF_G#&Uugv*M&!nQ;N6)R&uR(3b=VnqIK>OKnD>j;gVJuCr`0*0$^`hfnVMgt7O2}%vuVf z)PFwk--wOhEhBgqKE|@}CeUAj{9=5S`(b?8acx;y1@$h(AKbI>cgh?|$`mXkehBUj zU}0k0YD4C<*de$PU};rFcSMu`>;V=hvaL4Yx4iNkySy!hG6y`FL)j2;Wdi$Z0dO_( zF%95xQeCToU#!PM6lfkTFO;XK6BIjIK1k~29sV+dS92%_A0%Ixlt4Mo%ZUfK4ZK2K zSE%84G4eWZ9DmGbZY^ZuJRc_i^%<{F*Yz0_NcEBLvu$7)_&M;=T8ZiX{j{~%yBw1- zNV_iU!;g7+CX9&~#qX|OOTuv^~H6xX0FlfMS7zk--?HLpS2CtpF;sG^#c{Z5y^xwT*6^9*^g zQ_^+Lx$PBXqyaulb~h)+#d}kt0_zyyBlE$Ix~DZZ10V0Sf1=?3my1>da1lPYS|mKE zibI*sTFWHb0(|Q6CSVhG#XwmM1J43C(xx%26IXWkNV-V=#A4&h?xL%Uz4BE<&&wau z`<-*{NJ^eDwB2#7fREf8m&DJS@RORM$w5i~kiR7U-A?eFi2niTscqCbm)89N0000< KMNUMnLSTaR3^_Ic literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_app_store.png b/selfdrive/assets/offroad/icon_app_store.png new file mode 100644 index 0000000000000000000000000000000000000000..ae0dd95ceee604d971ef01e037f1f26100b8cc63 GIT binary patch literal 12277 zcmXY%Wmp?sw1sgk(Bj1@6nFRFPH}g4cL-j}hX$9RMT@&@ad&rjcju<}-sk+8%;cFl znUk~k+UwonNHs0T+(`2T#Cr--ZK$1KtVW^JYuG ztmc{&BZI4oHx;K|zlFbl^=g*}r7|*65Z)EH0s3)V*i$S#)e#8-%&5stT5Z#hJER|f z3@%7~4u7vZ3Vu8UU>jl>B{s(n!sBX@z1$YR&r{5!Qchfe_a*_Z4a*Y;nFvV3eBc4GK(hk^TPmTchOtuWH8xN+Fm`^HYj z%`Z)_*CTSy;&rc)hVR!YFH|i4uU;G2l$EyV$Cye0ris>#H-|9S^X3B|0#`Ws5UEc3c2R))dAvrPYC7##637J^pyNw(EtzyeYA!wqz zdhaTv4|~i3yq%Dl0JprDnl^(W=RmcPr@y$3AjKIsGq+ueGU+SgU+^8X)HrL=iy32o z#$C4eIs~{6=csY`76{mG9bqzzIY_^ON0S#Nejbc66%c{1k*i+~H zWlTcgiHSa`>`qmX&nqIUqI(u)dR%)OJhUu$1CBaB-Y)c0$Dbi9)1;{DKBu0!;T{nu zR8`V8ZTM=ko(p_Tj={!$-!2?|I{FjF4-VF5n4!8K$5zK^LaRR)}dZB zwSvf76Pu2w*TbqSNRH~<*6;-!`LfXYzNfeCg@QQ?mKFU@6Qgv`gCX>ob2HNQcVG*8 zKvoIsD+NrY-Upzo`Ua@Z+YgqTOO*uF!${si4?Rhf)oX*(s zxSi(Ts&6)?NU>GkyboTg9w0dxQu>YIcPO@mqp7!r7Yj7$b)8e!Py@q;TwMh=&+5=v9NEt(^8AlUpZd>m@&OJL_-IB)ZtY=V+VZigujZ^dtp_(vb zoj6r(6SmLgj((++7|MWWy5~$s$mVA{Yr7eD-Id;He%y|%l_K%Zk5wEAp>mp%a1f7c zzsbCC+xtwN;7oKe?6fiUxJwO48%t%)6IL8)xtrJ3C+RkP8rH0#014Ct9$-=ck}6qF zh7?2&B|pxz-qE;MC%59MNW(>iwsQ(9rq>{EUd|a@curtjrrcG{QAP?p>J+R{aE*&2 zWu(~F=NOMOk~&_te6nU8uRTZ1|X0vfw64Z4VU zRhthX_V$g$NOcT;i?qT8iTwmx={?@gD0&{rF;xFd_rX%qnP+wdgf*`Fob0jPxcfgf zdFzdt>T#o&i5=<^tX6XyrC#|@n_TtardWKt2D!mLe^D0k5VI}Ydka$Yy0*woiW$m4LrkiqY7%irI^;f zPqdAs>^dj->qCru`Fv98$RYK!Q4F1zvUMM9Ta*2|OKo54Gs-%^F;20f8tp6sbk2B> zU(wi4i9K+x%UQVP-AhzWrR1>!BMJzwG5cRd@>+Is{Ae(^@w;CdC>ZJfvvOdHLIrc{ z&9!Wm_qv;)IF6_1^cQ$D#{J-ZH5m7^JBz$E&$hfi8K8Cx3GDoq1^w4@LO(d5FMJkS zGvrz_JV!que#`F+%A! z&+gJA!VfxClWh#K`$Bjo+S~xO^P_s z8Yp&&@(XZuT`!FDUz`q?8<*Evzd}MI@5{@^N7kCxPPF@ytaZ|u`uwrQ2kG57y}?z4 zEP={$Mux^3j0DXR+X#bdya$8mbE?*D>VKuc&?P-<7@y=K^pr75gEfCBx4XC<-Zz@u z?_-Db8XwagiFC7hPxfslu3U@#o+n`ycJN-{pW3~lOkKgYjplWOhHp3?L>!OS%7K+p z8QGq*3>_K5u1A)c?ivoDJl9RR8M9AmBe*tdpFh{#;y(|*J9msQwKmn@W6}~|?o#YF zeBND6nviO-vu+`ezuzNDGfAu(=R5Hd(2cqBWbW#GzpJbdmCqIuOkpnUL8d>op#?iBqj&aQxF{R+OZLpjl#SJb_79KU7I|jU@1CEf_13q3h^g0f`-kw-qGwRYgZ8hFY zG}|L`V1JevStGvNKzF>IIWD|1u2E-sCjGew*ao*xcRMIw@dv{%bQHMX&El9BTFMD z7215q>OS1iDufuJXRA9d7sgHnuls4dn5TfQQIIb94SJIBs2@(WE+kHJG6$GgG8G- zpM1a7i9)N^a%`Vpy$jX1sC!~J5i$)WeVtDMKesC^Rl_x6bJ&ra1mis2lDYRpVODdS z46~50+eEV9#=dv0oG2cx*k!m&5cjbJn!4cQe<8Uw6E!|#>ff9W7EsL!{q^&zw?BhC zNGhM8bmXR~JchV0#~}!VP2a=@s3AMFfr`w)Bu&WmG@J}fNHP>wthrSnDS_KiaT{gO5@xDAEO3mhFX$a6vC}!d9*@jMgUyepEn@avytC=s3h6TApK(Q4A|$8Gw1}EMN*~|V`fda4 zQAP`1_`@s(t|iKypXhrz@XA|n7XblO{0mZH;Z zW`X7C57P9?`pf!%}~d>yC=&iXDl!v+$i)K6E7{9tskVk6DpS&pPT0#@OzN>Y<%5j_~QF z&j$qzuf`WwR=q#3ZVa*U<|mXlEZZX7!+H)8D zMTFrYh#{CyB<~Caln|EmM_k>k~bY6iXWf(9|yFlWEDQk zE?VBF(Y-%H>fom9H1~tUW_e};IG1y0+m=tndL&PF2Y>X-`FDf(M3l|qM^N`~#1K1@ z3>fTYc*?^Vcy2!Tpjn?mbbB)q9y8Hu)osgV>kSeyXBX+)p_KYr@y=uIgitG4FB4tz zA;+P>FX4_%zhK9fBdW@EDY_}n9P0Fm8!ZGXA^OU;nisW^yFU!~Pw7~DGgJ6V?s9js zWbHP<={sDl;{mS%CE*n4{?KwSvwH`eSQSc?kidZVo9r~ALC^Q8*O__h)E8j;PwH%7 z4Ry9$zX8gsf?6z~kowkFLFy?1`N#Kwh!ES61uwyS`x(i!&RW(SlpIY5FZ@P*^5M~` z+FWl=(b*K7_coTyYKDh&lN>n)u++qGFn#u@7A_v%y4uw1e0`cdFf%){L*3}c8MYP0 z4A(F|Y&(KL_Kq(loo!MbUMo}_tIE9b=%Ng|Wn47grPkE7OhX&=iXmF^&YaZW{Zi%?{fT<6#wLSFFWx&24YX!Rtah)$mT>=(>i$$ zOwR(@VwrmfoYbBI5)l4d{{$~riUn9G#(CVOM~g-!%vsEsqy&|E&zg^x=QtBo*ap%F zD!-DntZ@qCi@?e;cNus)=!h_Se!M+YV#gSqAb2k5d)|40@g5#`Ko3_sTxc31J9e;? z3OjR2=GbG~j2c#8_cKPb1_XQXo$k`I7voPiLXaVO;Ss{gSCp1HtD9Z|vXnTS?i!>U z7}zaTlAh>Z_YElWVSk%XlUX4;6j7yv%f_GjZ0EvRG%+jslue@M?0}=pEy*}*J2r4T zOSYBm8X@r9uOarZWhLxzi;yh;rC;!FRyFk61p3U+-e4qbzxqi1E_^Fqk$fIXrg6a( zXQAa#p=z&j>p}t6F0bpy*E4S+9HXTEO|8sRQc^iZXM1LEzsw!2fFx>>_%3Pb&9CP_ zohUzA;%Eeuc=x|o*|j8c?5}kFhaBkJ%{+rO#nF2r6_uoRsg=-GpknMvpyMk{55-hC z5o?*_DZv0c1dx&?^I;X7hw53*V{&KpHmDmXEG%@27uJTEki+%}`B3>$0uuS_Gm#>I zImXI7Gp)e1a^s9l&e%8GnMzyli`*tF{ff%A{8+^p%6alH)x<)DWgAZR4`6G(h0q8j zu{L}UtZve*+GR7yn!W7zFvWK}tB$PuWXm+O`;}TTm@-I2)`-zZz@h;;9u9#CdhH0` z>u+%vWzg)S3L!o#a(+LzNvnth2k~o{=;@OeF+cF4$Pw~dq4;i&jp}T_ z*ISOZCXdFifX5!v`QNvU_D0c;1xXs)42`vobSR!aD!;iqpT^QwQ=B*gAjO0^A}O$n z9=6>Rc^h*RprnB89QC*V-j7tXd_ks<_&@jQtVC~!!aca&$F&MSW-U5V6hGWyeV0sw zD2+-`Le})r4y+=9^AD{Xr;SI!3vUoA)`UK~yti@T=bNPnDf3y-2(b>+>R@DS3CQc<^z}HnCMl^B?`(9aGxfFq&!!UVPK3E{Pn*YmqNZx!BW1ORqjM znYM90_E=9c69=Edy0d8(7@GKZT_Dq6?ek&=ZX7^)YF8<#l7TH46EqyW!Tudt+#fj5!p5(DfDEY&am zv&vF?y7u)+a;o%o$-h2%>k%~UDu0n8h{nM2`V+L`|8l0^QsT5z!704Pz2>HRpjnQX z?11n)5Pas#iA`z}}v zH*XH+3LE_{<`REF0OXPl5fhr0A#OJZZePLG?=K=()i464{hvtZz4QXJRCcU@^U3rr zpNkaI_ouznP8YTzB|?X99H(O=6JeVleD(6lkz6}_UHCoL?#$*8JC!(pBFrAWv}3|j zH90VMA5DMYdP%*mL9aAat<2UU5o6H3Po8Nk#p?G%Gwpu_k@BB@__#d*eE}q_M5jHu z$Bj9iOVny!lgQ;{$Dx_~n%!)agZbRm8qbqFIdF}ygX>9 zoR!{3N?a&iVxPwfE1YvSb^E!~+K$q!Zaz&BgxYK8uFc+v^oWHLfabcGvyWl)-%sgc z0+oe3`Y%2}uq6>yd;D9i>Py>6F_uV&sm`Ue#diRe~C39Ys;3 zn4J|F{!`R1f51I}WjNS`<8LR#pIA%f$hY3>PQA{JWO8Bt%x$Y3) z6|Lsd(TY+vn927p(TU1Ys#b!%APlhC#E> z0xl}}!SQL@nHcJTu*K^@QT?SWEiQ_dUW&oqF=ru8romY#&8Jcg2z>*seIC2+|>D zVcq8{xAB$GGd7i1)qB%&hwA2gu6v83+6AJORu3UD*ZRZRPdm>^|s=CUX z+PFuTTBB=2GU^o;GOjpP*U;{}2~3+chVwmFnm=ChNNAuT(*vv)z?-MoYuh z5q|QGM=B!DOE-9~8H}hIv<_z^8F48_NT^yUPn%?Yq@^P(1#%7b;))tlYrw`qx^dFd zyy8Gh5z9SHNyg&m;xn`hkl#^CJC@_yM38A0S$%8qDW>kd;TFy9y z{=0{DbL}Lb>8R1*;bQh+fD){=oUz-1MLb#M@`Kd;6wA6dg zk=f<_C3rOs-6G5-PzG8JgO<0jeLWAu7R{p9Yr~auoq#;Ge4hHG8`_RdhWl3lts1dQ)#Ib}s{3bfMTsp?wrKb< znzJkqxY%FheC*J?mn_SsV|ak_T^n6l zGEkqbGFEz9LdCX8yQn$PE?R|khy9W}TIG|{dHC!!uoebEu2lv}*F>hG4x#NVf=0`g&Ot5;v z$LLzWQ$>TEbGE}Ore`INTly^lrQpipJt9*rjZ&wT6QJm15Pp=Zb?(T9H(gUk7u{K-&^lNUT;Y7ybnjEFcW+H?OM!a*un`a-2mWV&4{U8pt@Wq} z{m41Pr4MZqPJf~A_my5+%!S8YFq^Z;=IC~EW62T^p-N*B z^$(_o{&&Z=D@j8);w&bfkTS1-zh9vd?PXrq@$Ly2w7q1R?FVez-$6(V?(fs{eI|7M z!#UD?0mBBAzoJzq6rk+P)XDo*ilmWPIq3yM^NoJRysQRs^I zPRJ#sD&F~eI6D*kH#iVSb0mThg9g1q->GncjL8l-X_6NZilgC#OP9n|k=bY6c24SA z2fUlpoY;6-e`qO<1XpNcFp|zQ<3(f7HS4J?)bqt`yMA;BkI99ocIED2$}z;PULI$xogY^wijilhVWtwpkO>ACPoGib1`{L9HW!?$%brbJ_{ z93ik!zH^88;<9fsbg$$!0tnIXNd%;On$U7+$%Wfj&AZ=zd@`BuVnn-BOl2WYZpX$; zj}DW*fB$8`f#S?T6aqc3zQ^;TKREGuYoga{?*~E z_ShhFhR%O~H0=o%LtryYqbWb^vEg9m)#v5YUzc?HdzC+v?q&TgSrxZ=bHepdG-Fgu zBf?veGO!j6`YG9a*z-4sQ~2qjO?vklXh@f1co7A~pFuZi3T8v)ocy!DMLc|8l)R1< zb_f;ROrk51Ka6*5vWqsndi*EuLg&fZpusDlY)GXI9rB&Jc_eX0P)Pzdga^|gG`fw#Ag zsQ$q~iie^%dNQ@bf4UKDGV$t zaPg2KSp>)QrC|f(#OChOESii>BwiRYx`^n4a0(1EXfnqKL7YN`Es#a{H~NF&cx>yT zZ2d>Wu>SwaILM>)IQj|Wj`h_lJ8Bb@khlELFw+VdcWkDFEWy9QN)=?zJ18)LU+PwJ z{#jaBp5DTwiT)oRtA+fdoRD}TYRURH*`^HB|5bZwR!1=u(btO;5RYLAY+I4G<~E~{ zrj_z_uiko82)6Uo&YK5XP)g9MAsN7l7lK{lJlhPxs0Wj?wc*;HYMXhsJcTzN93Peg zM6OXU040CH(K{XpJ0i|L#3iv1D)rhC6dqs&EnlNK&q?ZzLK*(Yj~EJaY0p-(ih(Xe zy-LDWI9|FMAkAiMznuhI0!C;+s zhl`LK3Rc&F!|m}>nEF}#1V{=2;0p*vW6TdP(9E_t3Wt`%W2Vw(6Jh{ogFw&Bov+t0 zhe*n98PV~!_c8CrXTy@@X2QHzyB3>9|?igx(P*JK#gfm_~lY|fRP@6Ymf@JZJk z;h*WPmu3_JXGb~)z3~!M4a0I~kJ+>j5GUN3)M2l0_!`3HY*)j>3%I$FCWC(f-rOcY z_%+jq!Swfm0x`)T`r1Uh^JeYu^xe3+c3TL95w<5XPbU5?sm6n%dH&0-5EhOrpEpRV z40B2qz8ZEsWnEeCYtTorZv|!D)qy^%%h;0%F%*RitXamCyFRD(lR^*&la2u!=|CL; zJ13jXcwa-IT;qI9^$Q{90o{K;Zg zc-@r*s!MUS+C}46K`~zI>#&L86w65>=h7vaF@Wd%&vxeOqz+G@ezA-P-&nOYI5l|M zOYez?e|ixr1d!fvm>apjY+=5yB3O5b?b9$1uGR0a8bqv%LX#|`i}Get{AU!n-LDLvr&EX+8BmYqKyNJ9RtF-y zs7y^cMPgtNe|6#}f-6;>VKMcCqDOa9`n@%Oq(r7h3>Ae zZ}$Y5Gv0J)CpMNVbvLToB3=*y6f@mhlHc7MjwKl5;SUme{sXFQ8)SVmQGvTy*?zBMcz!*?T&eD)!C0O8RcP>2Y&3RuWy}I}kpeBqG&E!i4r1aotQ4bo zf)XMxLXpk+Fe&qL?g3_ML# z{V{aE5%3{T;7*nI_w;_naUws#g|ZM*&d5l`gKfk|4D zi%QxW9B>V-`?fjCvmMl%t3M|Ds~g7Mno&v)HMTI={M8hFpI}&RmLM)&MuEncRTh8q zT!Fdh*VJHQmqBvgJVs#xr6IZ_7*vMXlmC?FSFR^Bm?g(>%%!t1ZJx2{_ zLqHdhz+4UylUVB{>oAg3-p=C$m}T#_$2*^R2XjFhjV>a%T8qNag&L8K;X z16Q`&HB&Sx|FvmdRJ6VD{PgvtQX3Foj{u+`<)7$#TwK%weD$o+(D?%^2VH}EIK9`S zCp{CFP4q$AYpc)q^(juXeD9YWhOA~$yB6X+&q9m z{bdY-lpkpH`-sUsc?#RxddpBJp-zNxFZ87}IVD8?s|h^g6E%S0G%=J)aL0~eAFR0S z`XD=dJ$}p!S++>GxA9&vPtku}Hk3YrRFuQ!u4LeV((;DuLpKs*3W1BZ8{jhpmTAZ$ zb}nR+azxzKRYU+(o2S|t3GmS5fHw2Q>Az-op zOR9o#U0oi&)QVXd|4^Nvaf_k&5B{?{`55ZkNMLR{Wh^C&I3~XIL1RCGtr>)=?0;5o zg^)m9$IPL$CYNrczCq}nD6A*)RiBe`v2rA`T~CgmDY_24o@JIjXxyXyAkyrieVK53 z2U{oK!wC8cCvKZ8;PnvZj|hA}%)=LDysyg9o4ArExe)oi`CGSYzh4BWs+E3>K~R5C z*y7tcf@D%udao;=$aq@e$M47wW4M(oBM;v@J=FvRPE4MAf(4}aukYXaUN3ueBSa+W zNdoY_NEijm>gRQm27-S)DnYp4lg~J%)mhOj2%~Utb@=t_1DYI~UX>h>CaXCBsp8(QM6rUtk_I zUxp?!By}C>w0N`rbxaL8LDXn+)XfM^D^2)^O9qKtk%9bYCf13Xf>eciW_EiI!L+>bXfa6UCZSSTK?tH_-t*E|zsP3z+W zobSx*W7KDoYQicmQ+BeDHmOq|!snw3}rzS_lv+3A!m zfWfisruG9BZ=nbEc+%LcH!&uK20=qAE1B@*)y{zFE^>NWg}8Zvo=Y${4^5H`f{lOoEZ4>yJ#RNux28OqKYXXc2M)R6Jkm@(Luk`KP;Stwr*x8* ztF;b_%-Pr~2s6v;re&wlD9=+Q>li2cXQ-VlE(Aldu@gt@6RXP+j$A&AmxsX?+jNn zvj}LJImeQ9;*(BT!!+|x$^%Ng_NgHL%Pqt!NQ>BDdRA7fYf>`jfuoeN?Vw`%)?au3 z*RQn}V|3~sixjCfjkL23m)ee>$Y-|+lR*sX%K2lh$0eon$@+6oQ%F5*$K608QDNTV zG1a-J-)Fts_1C4tw7LcW4%obEuP|bd!On;F3tm$|Lz{*_uUA$=X9-iLn?G<=vVXGJ{dzyc*jU7wam~eNZU@m1Vz7YNYh_h_9PSw7Z17w z_isf&)l@>C&p0v$ah8D8B=lS}O_&0V+)}0<5((nLZNFc}6sWo33ri=$^9s;2ajHc> z>?6)EX`~88Lj~AmX?~gpLE4G_zI{~JmGGRVI#I8RCe$$aV*xzJB|=ktMS<9QMm^$c zV&=I=Ewlc6c?r%tuvjVWDp~Zz!h@1jdATZj`f$Tyy?h2#sxvSIb>^<+pYagDb-&TL z7Rg5E6P_s)9cFF`5nS38=*cMno_=vVg zz2hQO9!Pu*QReV-7y#S}Gc<-0+z!pXtGxo)x~@MM?mB0IW%@YhxsZNC9Rj*$Fcg8u zfXS`A#UDz#L=5NEHVks7Yd^-&DZ@HEtt9c{CV2dj9_RCVaj zusJf`_@Zb^>;YXZB0T=ZLQAqX5QQhrX8Df}Ao+;p<}*y4FZ3%$X=R5`5Vqv{lXMjB z;mexA7jbKJkjECCLgN-e7gWdbQ|lh%24TYo)38D96(+*wNsK(V+y%hot|2OUWgm1 zHfJjo!(6>XB+7rlH+LCZ@b?Q5quAOac*A*sShHId=w7f>o1aN)zYJdQHCKhlLcK4Z z7FhpjK*$raa{0%EZvIOmC0`(t0o~WBy1N1OxnicQJZRRcu(XrwfoYSl>`F)%qKbYA zA7BqLAvt3yA_+R+x5(SloRFyfv9MGR+>IrBenL#jW zENH7RlZ;|fL&}RUj?{8WYx|F_t$WR;`9QxjzxmAi@o=QOzijpgB0S!im2`aOdfU)c zf&)KbFHUT%W^11jeSS!B#tef@DlKdpKZoC(i8hL}6JsR72t6gx&A%WTP1|#9ks}_ zvEqF39p?=2wI)8Lq3Ct+&)Smm`OiP2lo_L&c!a$!cdRFU7IM^WYJ0!^PXlLS7QHRF z@%e|vphEZ$xZ#o%80u)D4e~|W<*j7*zseZlwXCs&)~@MKvWXLNDE5I{EVfC7{%mXR ziUT-jiv1rZU59|T-n z4x;c9F||_09i6>NNM!FZRsYFC8JPBzE>}?(=)!i;psUTr5p~4>ofe}FszlbDV82#v zG7xZ_6L$GO|7Bko`BnV5SH-Y@P|;Zb3aAM?q<|?68L2&#PEE4|?!eiRnAf_j$OucY zfW&trFnIO<>RK?+S(-8b!XIy+P}f#RR3-vjfro9EbzU} zPlx2Wsc}U0@R5>;_~{F2h^8!M#OgXNhHc0xCNtH<>ow*7f4vUwoe7>z%U7C2(sO24 hM8uQ=t^ET7JB0tt|B}Q9(#H=aBk@DLLewbue*p6(T1Nl? literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_calibration.png b/selfdrive/assets/offroad/icon_calibration.png new file mode 100644 index 0000000000000000000000000000000000000000..c4ee0d63d46210deafe0797f182e563c50e9f042 GIT binary patch literal 8910 zcmV;5fD*=xekj*lpc za3nYC~>R=7#;_=bLXnQx8a{4|=AI4*41g z{IR1Wg#h2dVovGmBzZF?hUSjTWk?82Hl5?09Z3l}ZClQGi}!A;-b-~u6f77Cu(d_R z9x6tjZFvvk(uW2)YBZ&@%%du&eR&x*aRHc5%labF{}POgN(J=~t2B@^Zmuku4b!{> zU`A5Xm;2>#DbQHO{0El2sG24?O_2D2)uMq}6&UXd*i$|>$sLlDxsbe8|~cvI5Ih@d=59`|?R<^bIXwmBu;2mJ?ZSxP2@$ zyvfoQtiH%{!CuCLIiTRSBs;VVgC0JTea<$#ntr_ph!>cW6d2187+!?oks?Ps~^%d?+pO901f{uY9A+R{vnKdAdH_iGEi;D;~O47!} z1g9~W!FgqJtbPnBGtNtP;r zouqV1Y&oC+rL*}_jkV&ASsZp8?k6V3^{6d0){|_=`UHGPJPBG)9!l6WOWluHXo^K zp$BXF)XtiTsfI%grmmW8%Tym4J}+fM!d;o8YVO3wwPj~u2Bm&CrsqrnLnXro4Yk{0 zeWd~-J6J;*(2N+d9bzUVocICFiGpOeWejq^ctQ3(`|6ZeN+9(O zJPmluKAf`HMA1if?(`N4l(8rH2sFxl%TVS-@!Q7xj*sz4fFMTfV`EHP@VR1PHD++( zfjtf|dMTIm7G(x`4=9K*%>oO1_K)_x+kj^>uq2|HVVr6wVdYSNe~ZB>*$3R%@UfZy9EsRYl;yMCTZQu z*EnSTcOY*p&~qmEnCv4v$%BwZB*;Yg$|OTxo3XFL^Lhr~(vH5X zrP$HuBopLU)M*UHkj=qj@-- zI?@=sNr9!1_k5la9m>WC3o&+fvd_p;gs)0=strTrOj>^yO~z*R=kzJBcgW;1)*B|; z>x$MbSaP}*p>flU9F?J<0|Hvu2!3f$|7h55LNOyWHhMfKSQKNKaz?xJI{h6irUrpd z7>mdreb1s*yu#TaBhyS-2Xp^wrnNMNUTE9f!RSSh87pH|k0Pu_Sy48|mL(6<-j2** zZciHg44o5Xd@oS8!A72JiWw|I8Bs9`%9JJB1RXhSl#O-Q{@Jku)nRaG;$pR%I&R!i z1n&uNJ2;$c=#bU~KXDn_k;674#_9;nv1t|5_aw5vbm_@7*bGvXO}#)l6W&z|@S6+v znL}JT92*pV5s!@#GaBLtCS|ZByJl)Yl9<-^VzLJkY(49m`Dl_+?sH@eudSmmb&T0u z26YKX^~ICF9Ba1!`_(03NqhSlDD-+x9q_&`uM%gnX8bI+u|@7w9< zH~@S(!*bw3PttDm>%AL27o}6<_yS2O_ar82SIINk7^g~_)^Oz7Cn;P=?N1>mXT$Kp+ zGF|zNkmS9t|I?MAAss|~mPiEpm_n{HIQb(&ztmbti9jOI52Ubkk{Gm}J+PCbr6eOj zy#8s$Oxt~KfN^x9}nFA#Sf*v2!nJEhbfiyCa7@Hl@0kh+pvfwwMAKUb2|Z zh;_CNuLuyo*gbTyL3G9z+p*5JQ78h$a+;N_S88yupA1nquvEIYT*z{ZS=W8A_e@Ct zZjl>XmA$&zMqmec@))VM&lS=9!yN4$_uE?hzoB0D&;7HoA=u*}Ar8`w6?&f1fNpiI z98msAV?bUhlys9YP6~>Fbn9FBcQI3aVZ(*u@Z}}?HB`V1FW^~7mwCThAsrV%wuYvZw z?=PS~obRy$zB>W$>w(vv=q;8X8(H<9syLxb^2!_?xUvHLiq6)^o7$6c@xd3#PC&bj zW!V|ipdj0O!+XSf3pOw^+L>bLwgrd#uqGI+2n`Z`w>WZUeCsLxuTN4&OevRTuGV3V;T_{>~kAYf?;5x`wpfGzv# zsy;C0_1v##83518R{vwFyE0>64!{K#v%a3&(AF(eb;2^(^^6RV!*v>h?%T0tgQN|% zUGxX>HJO~8i_eESV4yrS99VaN>e)3HU>_ zYs+xkmOj*%Be;6%s%t1TUAVMh#LA!!*s?C366nESLQ0PSd8d{j(g*hp!M*;NU`@i&R z0WuZ_KMy7!?1U5p{rlb0z3QudJWkj*M8`a&@ff&szl}u4Tfs{~7w8oYI;jp8VDx8Q z9zj30E^pASKmM>E+px{dycMD@n>+Mk@dVKPPrL1a>RWXTsEL3r3xcj+qo1zHtbDZ? zeLR>3+vkt2hXZ5vg6JnwjE*kz*JD|VR*ZZq#n2z7ur`u}?VG09FVe)?4aNvf4@uCS zkv+XoyDrDD`7kj?xhG@ldy z%)QFS)jKM)8jbrHtyVesi~5uZ;@^{&kE#ZDX{NB2M?#6VC6iF;PxJD;@sotJze_lL ztKY~jxKOlmLYaLBV;2$!X9#}(A>q6387vo2us}k|$OPC#691F$jXTWrl~ST0c@h}O zeOlrW-5(t$T{#zy5q3i;&=h^U;8;pV^jU}rf+>4ehoBvdu&_L&XQ2ZwfH)+l&IfyP zDG}hudlEK8gNe)TiP-GWm3s)e#TL|+kRcvKZ0_kPJ`C1Iw+)*PalE>A%?=Rt%L@rg z41S@|;1OabPJ1U}wTPGd4B99$a3FWoyqqn8iCEbeDQ0+yWRSfkzS3*Z2s06{l*{!21YQ#u`A>{0edwH+T6K+&KwNmY>Qd{h|q#Z1c=$1R@}0;9BfAF*=g^ge3V!c zu{$=^cbHDH7~327QlsQ161#(}_@!sF%|QL5ZgFjoD*}la#+P$+E^0HlgtYYR2oS@E ztvFs3}_B4Edo zx^C$Wo}1S0{*yie8o+Z1_Z5Ffjx@j)9}}*}-YvBj9;B7TOFo`8h-VAgqHA?}_{G2l zRL(Vxn#yy~JISG2kA~%eHqc+oW9oDN^q73UdG?0THnGkM8`!ZGm}+G3dXN+{sC1g0Q<`R3YFdogp<$U;DidCbg5Vc8}!Xxovgm! z#Z&_QF-yjZm1Hu0O$?o@Gr*SL48dpv-$z{ z{o2p=b-KWbr|@8zet1!m%;1?9WUb2dQRaNTl4ai`eVHx@Zt#v}6qOy|Dac&Pa-giL z9uYpOEMdrr1-bMk9LDaB67Sb}6>*Gg3znGZ&`E1jk+Gh#iQwwh2U>gDXH-jMU#k5KvN8A(+}h7HdMOp;ODq9}f{YQ9 z7^|0jR1MEor0_g^Jimx8_*Y5tE65jFMDJZIgy~G*&tFZJSwVGz$_I zQGU|m34WA}XU@3UB6?L(dLoRMdNG&Bq&2sJDuXPY>)`V&qdccP(&`W1?Ws(T0m6cd ze=(xfp#M6WU$#h9RqG70d|U$Gb?(W7Xyc0n4qjVtg8VCM#8>E#egYfk7gMdV6|szB8FD z`);+2yvEeSflUaoOp?7#39#(>2l3fR70UHh8ZZG?+s@>-(zf?O<&ZL`h5QI;`Z@S0Sv&%7Cdej&7b5c(#`ZqXwr#&i8>z|t5BqswbX&sp?Vneg}I2<@y_6Ztl<9671)tH6z zK9h5@>G^`GG^l*CLAIos@>*Je#h4mom`|b4{&A8fv})S(RVys0Z-R?IHOL{e*3C_V zs(0Rs_pH7*R*>DS;54qvnlqk zIIy-lT`G&Fu9|~92V1;%CcT3!Z*lB;3eD4XKyr^e3V7AV5a2>_^O=()ACRp}PctJz zwUxgcbsTJ6$gKk?oWI!Loo7HQ1jRaT|6bx zXO<*KVy0uWp!5Jscuyxj32*@hPnFg5@9*O2kzU4zk^Waz@ctfc$sFFdARDbXaIUFNpe zXSb`DZ1!M_BOuE1ZNXDPJ;3M-dh6>{a6fQD)1nYt7B$VdI_=?LEsOqlgL-d;jVsgc zcii;D?p{zkj|TOW+HIUiUZrdy5rKXmkc7JCG)Yt~q+O4|>p z!BII&xx!gJouKQ_Y0d|Wf?jlf5vacx9ACZV)o8@GH-QI&w}VCD1qK`fmT@Ml#^FKI zLSWwu-U1eZ=`imO4%!d6(hm(W&`a6$2D}-dFX#++4yfIm7P^f90o2U-IOq#Ez}VO8 zN8S3;v~k2qFO2#eX#XJ!%}h{yS819rjkJeAtqfkD8P0i~&r;PXbZD0eRUIT^s5epS zQlQW84Dp-0IkoZAO{Ehh?pr+W3ngih~#;*VoU>1C@@y=nrw$ZZSEIQjCaE(8by&1?ceha9r zQWt0!L~odA7GTuMVAe81uN7XpSys2!^g99^^U0ugpj>bT9nF~7FywfbmC*Ig+o9h9 zYvngP0_4Ey89Aav*8>jq0Lrx%&bk+(FApWx<87<8*9ed+%Y#pXF3{^Fss$|3-Dp|& zz)q>wqE_3WM1Z`}?<5y!30lq028urGvI4sH6c-QEwsVbyzU@dxv~{|+2#|BGn~k2QZ+@p?blwc6 zL3;y`Giq%|zal^)E(W@m7L-3$n!P=Px9v)g!0V9pZ(DjXyA5g|0Uj%2u$4iO zx2OIa5n3oU0tb=Er%NI+K9%C2Ql+=TULpib5aZ~*X`}txqy8m?W)cHs{Mnb0)s|xs zSd2nvx-nq3cmPa;e=|IzRuYT_!9zixcc7)kPPFJA0qS3JF?rDSAm_XTHfje0fARlP zN1Sw~8>e@B>9zi@*M(jwrcnW6u`GBls2>FSXQgj}OZ4D>Su?WU*mI@q0`xNOgTYaI z3#ls?gVltB;aXPQ&D!IE9uDF_3?(7-ww!A~CGV5qCrUKjeo1y&Pm#X~`@Re6Q8PVd zaT2Ig?689?ktgE+`kJzT0H(ni!x|Z!T_3z9&FKNBorV2F`vO6HbKN?zhi2pz90~h~ zgFcXCg78i-cnb~=+zxIykd9;fm$})0qXa_sKEX>s!O?o?}E|Ag8>eJD<@aXO611}(P0jlb{n*ARPxRM^*?o^ z4hIte{gpccI7_OWQ5;=Lr#Q6EDsSHBN0h$6njjh^k_~IbgT!W2TKTjo2g5QIa zYOtXfm9CszR5P+`-LXgYz6}n-pWC={ z@{z1WcCDRjJpcq;H~yahzJVbRg72%ujd8x(PKgl8O>Zl`vviC+FPSsIhmQr z`g8AEfk4g&9s_Fj)vm+pwHj1R`OP*v$^1O+du&?6>w99~i^TpZaB|(YVuN;FT>qIJ zB=Xe`BR>!hc69fTjNa8jC9V?qSg`4{FD7=tQyr9XI*aske0~$;WrGRA6@3L zxZ^5vXg7zROGMX&Sf%s4F$kfLq424o5?K+DRD1rA5+*Wcx^t zqd?1#HzzyGXd_que7l50RxFW!1k=kYjQZ7jND94c5=I>eYWeU-aJjApHGAMJ&U9(Z zwP8$Tb0qYG@HvjHmL2ah#FEOR9CD@-=in?C%*Zr!#l&@r_!@@wbe*2@3xgMeT0VRa z9G2ySBfjI(mKEY1=0rBJ(6Zw;4)tvC07LAyM26n>x`ku>k%n%T7HWSBoMk$!QnPY2 zz@q0?F=93FE*M_{Kb$*Yco;@Gk=?P@^KcCDz9kS|{c*b1zW0G^cSsw4g1)$Epfl1a!ag{yo0fDt!BV~ffOl_r*LCp6 zCf6vDL*`Q`A5IylZ`UtV=rIzCcL869sEYv;Vx6Pa*n&7{CuUW-O}QX=G}SXlD-0dp zz7LA-z|%8`D|hr-1p2jqeXd2at7kCrYLbkgV@Co3>(F~=#1XF?gMhEaNx^~o6tpwI zz)?c2$UIt*$BG;+}|Pe04CbA)B3U!c@YLY0KO${U`uNwP;mq2xNt z1~4mYr(!1P{Yz8hT4*Csas+hY38sJ0{tPqwW{b{`w$1R+Kcqj`nYf<2F8u zGiPKY0AboD(ab!{(AqLH0@KraiKEVJe@N?VX&n)`+Bbyt1n~NNOc`gzHM8?WA8+kP=vn@u20o<#ifYuVdl-cIVh`dm}BDW+iv985x&fZ zuTUbJK`7dv`e#hLEjuERHS1>ebqE?Ef^KbCjoiAV8=t#MWGOdbTEqJ^=v7b17AEyL+j5?O{|&`eOf8s8|xumP8m zHS1>e4Y=E0=IdVVEyxw!_4bC>2oI*x64~g&INk89`Q1CT+Sv2`r+b&QNBw0 zDPprIc!MiA-O@`>WEp~?bHLrGP5|!|ZG=EK(SJG3U+B7$dU#sjkkd{h9|Yg;m!Ar3 z-+=?DKXcJqXt};CYnFnGG3WQ7E=}(YY7c&t;5RtCD+#RoPWlR!B(m{;d@X$-BcQFcPjh?)`p4JGl33BI zbVg1)Jj~LELDx>lu)pgf&HZ7Z>4vfok+`M*fGZN5N@wIW!wA5MpmsU*B+9STcv@QH zBB0s#XmEax-3oOlv7%FZBFhK?!FUSX5!6{?bMPV22Na&b?w#a|0ou9;`53ULD_D%L z6LcwgIec0GJPxdM`H;!8O$$0QfBjcpI0U__Gv!dck31CJ~pd zA^kGS|G=jiIefKtH$IpIP)}Q|1?o$uWY(@nlVNI>ak!yN)YoM3)ZC}7vg1MB#3R@R zoKdq)x#}CA$hHRr^jKn0lx=M0ySG}*W;t$9X4MLb)S1Fe0ch0y4L7AYiy{vg|H2!ZsHkOPy!4s zupZTOh93`c^@<$59zFV@`l^MRF!bLWLhYe%2+Fp8gOXPEoDcqtWPPFE3hRbvw}mCFGT+);N%cBb1nup0koxe zBRE}1vi`LRMm5ETHj%qL5+uD6d@WEHa^7U2ZVPx`F-b&0RCodHT@7#*)fHAMNk~Ac0s(&@Aqjy1K}~5oL$TmcesoHKDU8yN6x%_{ zU_}d#AZ?j3Ep(toEMSp3g`yzLAW+Z_AOU2A0s>+w5FmvAAb%1_LP$vH_wBsH+^jGA z-oAI=%O>xhnKQd@f6l%4e0%RX_uRAl?!L>A7c_9UQVDfmIegb`<%ha|=kPsu_RLOw zXh49IZ4*?2`|?}rMDWNpa=^Fs3##oJ^D_z>5YPx9J5^j^VPVgTii*EgS63gpef#z` za2fUwCtxST+UKN*|oScLq zbfXGZF#7=i;GjW+?xhT$EXp(#Werg292%Q~6E9!BJS`aT{9SYU^yyzxhEJ9mZlQ>1 zk^o6(rx}LICjnBWKcIp+R#sN_G32m!#)H|@P49#fqCr$NnMzN{%gcM{)~#D7g8{9s zYjFQL$a(vtTE$xB<)QT10;?jT$xT3CL~_z8~BSY^Ekqf^Mp1Cv$Rg?n7{VhZ8t1&(&af z9g9k5fH}mf&JW8rq)`LXD`~@$u3Wh?(63dr1YM90O+t5>gn*}8S>MFZq&Ye4Z z1DOg(bX=Uge*OB9w6wGw$nFScP@Mq+b;-*NuTY2%q9V!Gveu+YliI?z9d&_~yb{rOO=Aad|R7KmT`-YoCU2C^tarL=mzG zB$Z0#CZ0Tba*Ru?94|j}=FB?C?FLQ(w+0(K2_-~=1W3zHZrHHlQH1NRJEG&_WO;e{ z$=uxB@1f$1z0ywFQ$tw3Aq^U!BFVIq@dE}7xF5?}L8nOu!W0k1&6zW2J_FgEz+xvQ z_G*S#C`Bhpue9tWqB8RX0p#ZVjvYJxgvyGYl>8oJCv_s|lO;e}cJk=aqdx&qHEzIi zy7v6}^P5qQKRd}$fMpxfqyYhvb~54p_utRJ)ZwBNIBw1%5xRKbz=7X~>~yfKhM4)J zCh$}-1d?po$yTjewSe-sxB)A`wN>xD^Ulv9KNI{AnBh8OC!vH$kn~CpuSu6KUCIjp zj;quA_U)SsxmjQ?Hq%b3nFB1_kR}ZXkk&K=ivJ;ys&a*v!^L<#;XiS4aothZR4|vd zB%jCFNlgHX7y?PQ>||bE-XjRtopQj&)hSGAE+b>_NyryFsV-}oX^5bpX-gp4L#$;j zWTCHdg_iThHOrPQWBLc}q%3P0I|*e(f(WF9>ynV8`ie6)?#>=MbcpF6w3D)|W$a`m zP=rhY(z27=wr$G=R9dpo2{{4{`+eyj9Z{CpNiz+J0GI?)hS&Jfqer)fZR7U^v=Gxj z#*G^{5M^Y5?dc!JPHF~JdZiVvLl*iXEhzegtXZ>0P5&_2b(+Cb#R-sBxDM$W&*=mb z@|L48lm4M)e%IX)S9Z3w^3CASnmwA2U$dE?~Z`Wzs)%B4?8& zKw9CtUAuPu0Q$d45OfgIKk`wYN&m1ZJrX|&qztbKQ>IL5hY(w#4iG5=83^b4_3PJQ z(mzBQkx+CrWD1bhGz3}b%XI+>IaLc5EEt7GcryJ%fMWnym=kNV{FZCD^*XVRthW`e zL)Q4OGy-{h@7}$Cg>28Ie+WQqIDw;WiQBw+b6c$I3wb7>XvM;RUva!_?f`g_z^`S6_XVc`JO{ zRZzWzrrM_Xp+kp0fMu;OZS4v9CuCh3F=9ktG&mj1G)Xo6L&}c2K3K5y#<=zC*Qeq$ zB|8JP5)G$FR-4;@#{M-cdQ!;k!*a4880rph-hk(ha zss)^yu;yNH2zCq~KAb5L1hl@MQngLYLZ9vjlaLP~{o@t1tut8CBondk34ehNXGItY z=KF@nLvE$-MtHyxgZSj&@MX^k?)#l;gtsBfLOApPUFXooCoNt$FdM;#O&n51V~U?L@OUY#up z;RK%O^J~|xrLz#pr&xfr?Bu7Pe%cFFy%9on{oaD~kF}^j(Cp8ooW*i44y+D@1- zp_eYZDVl*(^7|$W-&$@09#T!eTcm#!HKg+&VUVw2 zKa3YZyC9V!-(Lg6IaX3q!et`6D<2M^yjMn+#8anEjSi=N_ItN)-##7k#ZESe^bb*p z^<<;+3{7?H(WA$A;fiZ}X+{)djFl;iHc}>W-dNBISg;Mf%4k$Zc@x zA5;q2QVO!f&Au)mb;Bf4l{`S>Oi!^$#jZ0HuQIdD4ESg1hk(C!s^<|4y!C3>h+n z-%(``Q>WBU3>EoDJ*3?wiWq9Zt)?@qW^ zk@Fo0%KsCxgAK~FewLl|Wua^HxZxXkGW`SX4U6o6vgdHkF1>yG_BpUm+P>l_Fr!CI zh5SGsuGGs4*WoXeelPcH*m^SkBPE_>1eEX#wAGuU(KAE;AAh=9s;fC{FE%M}oMxZROP@qtbS zQx;Y#R^!7*^l(`oM}4uLX zD8F5ol0^<|*`FbwbKU01LT`f}dqB>GyJgI|Lx&EJLpC2sKA0?r4-Q8G8I7>pcu576 zUMHt4Rt&dy@7}$jAZ@S430Q@Nh2v00YXJMM91C{~yIg8Z|4?5i;0VNa#smqVb`Lib zcJ68P9&P{N>I1C;cJi%o0aWkbxN#%rw6v3qJ$p9&BN|VW3_*N?Y0GG5xXx#JxCl^> z#uP)_TgWO1I`*;N`7hL!b}|L*>GTiOFDfK}-kC0-R4Rs!L|43Ur1kp%IzXfhOlgX; zv$Jzi$22hQBptb!vXf}9Us3_3LTUx&4;(nKP!|X~bUrvr>|WE2+{H^}sls3YksPyiJV_fAlLf(tuYHE-U$=TPZPu=(>BC-iLR2qszea3v_8 zh3~h%3=p(^U@#a!k^V6U^=Z`0S~d){{!{@~J=_$O(hbX7vx5Oa$2C~&-fm0(uxB!8 zZFpl9Cc~|GxV3`v`0l|f9bh@hKosiYuwldcLcv^0qn%X4b@IS9R{d*lmmN?l(@HyO z*REX--rL;m1V)(Ws+TNT@&d{;c2Xm(DxjRQ(8J|qy;J}G{h#1p@rDVS-`kP?u@Gg% ztevF85)Ha7guM2-47o={GMNgf;@=yk7ba<3kp!gT$`ZWyrAqSoxE*m`wku7c^0*3aA>CPjA|^X%9F? zD{CPY;7370!BVcyK(4>}q_LAxKv@7)gYulR5Rh!7KE4(x^#sB5vx^rmW^RxG$@@9= z;R8as21qC&8bmPb0yGWhy7lbY^NIZY{6FAblFtF$S6o=ey!15IN4Fxz`&x2xGP4D` zfqA_EnTY+E2a<}7Hc6T6L3D~}N9h=mxyUX1JTASA^TcZKEimVfoI_Uln7^yQoKKQT zF*&cK!lF%7Gyzo=FJKWc0z>h1OTgrF?D$Q~^RR?JRW@K-DeJ#XN|jAW@?HuJ5f{A9Y{qr2?n!%lVkz{vU?LX8qxuX>tGn002ov JPDHLkV1lIvc3uDg literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_chevron_right.png b/selfdrive/assets/offroad/icon_chevron_right.png new file mode 100644 index 0000000000000000000000000000000000000000..a3aaa76486170d8659bb9acd948893ac6842ae40 GIT binary patch literal 1420 zcmV;71#|j|P)%Px)MoC0LRCod1n_GxgWf+Fto=@56h^JB+LPteYRG6qnGRgypNCQ%a2Z)rSyfBPN z>%uOIx+uD^@WP<9E-EMl3r}T{q6OMikcv@xD2udk@_^d-ytacuCUw1wf9-Gk!OP6- zz25nrcdfnmTI>J+-JwIdT3cId(DP_FI*GnPYf;^Q+f?08;O{}dqxPzW2bWZ1sKJ2$ zU#PZ0AFHZxkgsk_e}&)w;kkuX6AsvKuMp<)r_S@heN_<-&_6Gyzslcdd45{>a6s<7 zN|5%R{+kEyh#amXa2pK3o_IDAZld8W#sXXy^fhuypQfXWAvL-HSC5W4$?zOTaZlpF zjYr3kQwK2(Huh;T7T_9?E~lK*X`{9nQlkrSccD{GGCW_RK1SPOEWph~I$t@p9aE2D zNR2MQH6dMTIHglT7o%-47T^{jT_Za6E~ZY!kQ!Zpd&Egq_UL}DWV9{D0^E~1!o5-q zrP+mGt8#>U&TLzZjbJb52=_!Wlx7!#t;rGYVY6*|8=*R)x6N=D@ZF!D((C|SXY_#? z?i{{ZX6y7e;JTqrX1LS%rlzMfI{?=ceQt)+#dd?)I=v0JKIkhmoNklGrKdDI09T8$ zjCQr%55Mxq2(xv18*qcrfwsgMe*cMWho+}AI{-Hf3DT*3mfqrq4;n|C7 z(o>opfE$bcKu&3#vzOUAy$!g@=r1Q3o-L?bdP=hcaE(Z##!h{Rsk7NSy$!f&$Q?gf zk5{ABF$=gkNY{u?y&f}FnTkXYB3<1(^{Bz`5qzPii*EpMml;me#X};$=lTKYu434Ow`=5Z0|C@ffm5r(1``;GZbm;E$$kqR ztQ_tZf@ydzYuyz0Chp(eKAayn8b{!);VH(#A!ve&2d3Zk89M+q0J-O`pYaaM*fRa*K-C}(Z#$)z?a1_$ z89M;g3+-?c;n4@otr=UU-yA4S_ijc`=~QrAddiF)fXXvLe+K{E8C#~`94HM5yoH?7 zi1O_8ltu@@Ry&FCXe4=_(K5XSuouiwvc>%J5MWQ|2(>)@ZZ|p*=+PXZV%|IwXg<>L zv{SDd`!T(RB$^v@*A~BlH{J?WpzcLF=Q#BqrjS?aw*%JVB*ODCiZ|K>)C6<_IrSMP zecLHk0acHVIf?LSv01!tS^za19YRihhpB(8!vqabgU|sd5uP7Vyy0n}G%VeWoQgT2 zK$70bok-9W(3prXzwUr-Lr!VZZc@Zhx>4NVB*LR<*2ajTwD$fTGgRD(aRRL|L&aUn zKp=O0hOX`xg?sr42(V|&BPCnRonacV23cuUKH8jW;u>Xg0=&^z2GAW(Hkw-HWhHBH}$ zp@sl<&`E?xGm#;uNoxVqt+`X0GmiNcDZup6?3AWSV}7X(uqjR=JTa$9%Wra>KxY_l z_!c}fOQlk?;Vs0XU|Gi;&fu9%s9l8+noSh!Xa?_jww+6;PcnEavnlVD`PcX!yTEo2 zREE;%3akcYu4VXavGMOKYay5xJbsVbt5ZDqP-O{obO&B*-=9KXAkCC$xOyELmE+%5 a%z6?0(E|2_u(%}v0000(*Y+R42zQT)1$fr=EIh$(n1f*_oP}%7M&|di?RnJ5N6O z>*uHF8H57B^%;{Wn%{5c=z_8_(TUz>Z2=2P;u8?WoAM*2(m%Jno zB*dA#1v_x!m9Kndpn${>6Wc)EbI&~?L6yJ1{N*p5b=O@tHwk&o0fLPAktnta8-xJx z!fw(Ef0jLOt+m$LNQ7W}bML+Pdhft)YYCkfzxc(;W)5M<#1cwd)xgFF9(bUeZ1vSw z4<+vgL=J0~fsiOTc&9eoY_nw`^akpF^PAuJpdR;w4?fuAmxu68H{Dd;r2V27y{Iod z$b@7;b(TlKHrs5|heQEr*0tAOTi&Go%x6BcPe!JUa?5*pi%=@hW`)Vl;)3F_Atukf z-~}(}iJk`+s1C`+Lk~UF128I&@&*4KRe|hLW$N+XfB*emRRA%82pnaJ_~(EAXOA!G ze(6hJnhaMU`a}6)_i%!~pvZjXD__vwkU zEd&IA{_~$Zzy0lRaduW+b=6>(`6FZh>&k>r3@6}7p7B)x2cGt{r{#fn<0z!(1QBzd zc;bm3ssNy;%QGSX#Z|TnJU-6_+%(aH?RTQ&LN=pl2uzvhKmYmNQFbamD-3SMTmY8Q z%#;l@{-VsiO|@u5oQ1e-c$NYqKPo<`OfrN@Zva@PnHC)KhS#HP?DbFKnScFhk5wnhr4-q9X{jv^XJz}2?eA2u>bU@ zKdt?TKm4I*R+S_|1Z}+W#s^u`I`J9Lc!q-dY@dNLk_|A5&05FCcieHuEq#es1oRML zbB1kgx^{UMa9!bAmk_=#5tCXVfsjDNYhLr3WwhHWhH9XXf%P<5tLw~Wn}zqj%U}Ky z{N2?W;m@*r2D*}JZx6aa0uguLeK%Hjk{lBeBJHndWF>trdl&+g0XB;y!Wr8v()7&0 zpj5x2RT^gQ=m37l9CM7%GwDt(8$pnnB~zPkzImTOFk#Iy5ScZ@DjH?6q8AU8z}Lr# ztjrajMF8<|CC?xu;xzUOPV^Iz$A!2QsSG#SWRp~IH_XpDL{KG8SYOgbmgTtQl1s9p zLin$K^{XCkKuBn!N<~1Px%uXs^P)?~sTxoPxO?UuMe7P>=N3iOFy>_Drb72rM^R$p z8SW2jqzscXQ3g5l5t`yhKl;(IWXxhoQPYg^GIbOI*i-ATzkXK`%5+XKLiv63EFy}* zu(l{jU%5Jzski;ie6`h9^HE8+4Icw15K1`F6-=>*`l@O)GbdfvOv~d0UMqNn&k;2c z!Akrv#zyOtiwN00 zf=M8fTVzATm!jzW(*EcgLAzUbMBKjIp&!;|ZWsOcG&Jv@Xj$ z65QvXe|{)=)zYU3pz7H@W`U${=SLaC>axP7G%5SJ&wXwfeaCTd#D)%Y0w6BRv$DBo;4FENv25ICmd#<2!q-vkmSU+&2z`nalFwKK$OiA6|NYQs zp>nef=`<^2WjBS#hZ#)RQ0waG#w?Op{darRtkTvMp1Vk5%4#jsYQL^4vlx$!-n!gZ zTwj19ylqvr)`A5KMn;&=t4=pEY>P8%+cc$TWhj+LCL^}qdh5zd7O4!H6o$sQ`s%Bb zW$p{qq7khbj+V74Ft9R8Th=eQL2Tt!#m-zcvtH~qwoq{OFoa~KWybXAqmPEe7G+0E zFqMJLdh4y%F_oU#i>mNhdFO@O+Q-(`dtL)fkO&(Wyl9{vT)P0%c_GRueLXqBPeQ}VrD-~YH6yzVqF0-qUg`b*N?fde1cb5^KI{@GxcH7G@ zX=V{wHoVNy?>t;I?^GGZjPCL&NW_3{q>U1XHN&=V<)3# zgZ>DN5Cc5z!}Jy&PZf8H4$>cS#1U1{WWv&m!HhT`{5=xkF-(FHS=;=loN|gMZ76rl z1R~pe(aYrm`dz8aA0ApYT`>J)02Lj?1f3(-s1~hq=*-G`e^4u^XCE32RyAqMrt)MIF ztQiQlh2gMo7&8F|kXM~dKtXDciGpX9v**YNL`oWPWAHP~X4{VG>Y(Pl^UmwoVZOfP z+itsU=eFB!3*mJ#0ED&%+hOdW;kD1)mlOAtowZ-a$)2)?F~3JrCf$V>Uf6m0%U>Qq z_uFs3&czpBTqfC2FwB$6>bS5tY?^c_QfB8jW0yNZAWLaD78bZ*_<7CPUU--iAu}A2yYG9n` z?G6-d701F?Mu4=cUum$>{w#w#^YVq3IG!+@;C0L2br2yFU!s5+ zA_kb0pYS4>ym-8@Wj~i{kHZib&Vm#oVorbf!bHJ*jd<8mxnVRvnwK@LgKfxur49NrFRSFy zF(@ORW}~)!4DsLD7-R=lv$Wvhnc>9|B8vQZgvN2;Vs^~%*~S4J!#>V-x6d&9&oOL~ zzZ4T}1Lz_v=#FGOT@00B47&Iizxc)CBARoVz}*^Y>>@->j%RGaU7ai%lM(hf$s!v| zT$+_=x`x|0VS9Tm=CYXnJ|=9m(MA{A_9+jfW?_^2d$I@>_4V(8{=~O~t>z9MWLrAf3H}RDEFX5R`F3JbEVX zS_!AS8`osbE*7#&6*PU92|NP@A)_!1k6B=$OQVL$7?jyUJNg6sAd{w|Jix0PmZ3S= zG<$y&k^M*rBRrvH{T>cCV+RV(>J_U%KE8-R;-P`1I!@d1W0|fhj-q@F-_170_(iCe zDsOQWA!fNw%W6figT(VPg;iKjMGb<7G%z|`bHxLPhcTq5=1uF?LR=m#NC!WfN_;>q zmXtDn@|tUhG(Tu<_Dy*i7sauS&d)caqBO(CtC>`Jvm}+LN$&5bY?1Uy)7EoU07*qz zKX*k1o62MyVK%m5{!lq9=r*PM)EryX2+EPdiveIO^0Umwp^!;409t8==%T8IGTOv% zZuh{43SGt~Lmk+xn(?UMIljnDwha9qhVD1)R#hR4jD|Tcsk|Tr#m3m7F2gI5DCjB% zI=WkSo;z7?xTZG+s$?Ws@EQDM7|JL~L;vY5)@4t|4(v~bI&duDK!Rfbe}_tt-z zw#}CNpi^rOa#^1&T666>HgGv4ilJN-T*muV=I$x46o-5mif~W{9CXk@r5OORNQhRY zMSNA8hw(6;0kL1@3y)+5X!qy2rQp0bD+QCXnJA?WZKPo1Fvb9+AJlBH!3JSDzbJiI z542%sMkU<>`0M9UoNJ!7vAxjDf?+%vmU_5Y@ z10Esqi2gqQ@sAIM`OZ7<>`Cv-O2m{sF|)E0?EzhWhhorf5mZ?xT%&9Xy^JjLo;fH) zU;uefU}QFjFs2^zu=p@d$rns#BYap@w?>hq^U{tx*+l|KqG8SA#fyhUQCoVp{xNC_ z9&x55c%VVud8gk8#W`p?<|?rS$ls?Jl?jRJFinyMl}FMbJ2VG*#2M_m4u{`#(@mYr zF6-O*5C3F0llAsw@9aQeM*Iu1{_F*SK+vL5}mYu3v49Xr8Ga^$Gs-Z82 z<|Q{qe!Tj2u^srNxm|F<1;J1E#evYQC+F&9P|N`QJqN-iGQ~w29D-puCttmh)Wu8a zg5f!|I*b_Lagleoiv%DAoVH2 zR3)pd*j>daC8$XJxD{R(F)2JOv8T+iYm6Qzx+N}){5{P<3?MP?VVAW$5qa)gZ@slI zT8F~>A_fRRAE>}SIc4P6Z4L_Xwx*vxVcqW3Xz-11d}Gg3tHb8W#*Z&o?CwfJDkFe3 z-cH328}_3g{iu5!Sh%=YcEb%f$Xko8XNxIM%1jxT(lINbc@d|sWin5IeYdX@_Xs!M zcw;9uR`BVny6F|NhU3E3CkZjP=q2iu25`aDm;oo8a6;`2ppaZxl~FU0Uv{5PAVR=m zNS5{%lCt*O-uAX|k}Zbkq{)#-9vKG@?MJbr5LF%_lwWq}BBeQ1Xn>U%Hw!H633{#) zUeiGrl~e@nxPzfG<3LOe$=7Ott?k259?z6byhubb;U5 zj?3fyea(T$)DOfc$*RU@#u+E>IU}Z{oS?Bsfz+nTkqVnKam?)<;zF|uRP^l#pN33f z9@llpVL0vL8DA#PDdSotCV-R~W@?aACc{y}(9Q>uuw)nMIVtfG@%T}4!)}WSUtKn{ zO&H*52X~Pl#&Lx2Nfp#5P?(5}{q*%*-)(|nhUm4wXjOUg{I*s2`C)uX2axKw>>7fV)n^$dEQW$XNvngz_E5H3BNj@P_htnLxp9Bxm_9R}T`E zs($d0M(Mqu86>sIStdqw%pC{=mbnSi!?YKsmCYCYsk{isWYJ>1Tes{zOUkC{S2c0l zc6svp{~?yb)2qM$3XFvCQ+Qpw;d#_sUdLGe$t!^&ohh9QjTwvckfh=UsSS@uHBT70 zs`#snK}aIu28JUTL$NvxTEY=E-L2cx-xQ5CalDecCBg~sqZpI z9c1?;USYqG4@C28O)&=~RI+W3v&?=!w~GF{UBCL8VfbA!mTC|~3xmBmvA?aeeA9Z? zuv%9w`xbgw4j?Sn^Z&(8LLFci3r-&f-$24(=god?2Wi%7Tlp}oA5B_>!^YnC+MeFp zRdXmU40aHaH%E?W1)wU6CkKyU*na9U_MG|$%TQ4$4Dri55(f2U_~ji9kz6NEe1S;F9@HHp|V##Bi!oIahx;#MQPalGJIz+(xRwJR3z*d1lxngu?L z(gjcS=W#P#C9QYMkL~l3dzg6R$^G_J-;2TFO`kCE zu{xO8bOYnG*3TtvDti)is{(nyfU}4k10<~JhDO1M`8=IH9utJeP4b>D>B}nAsN+3> za??WD59N&)-zpW~G#h4fNQHAA2&#A{I_1yevEW8!lfTjUCliS7ozSi@*g)|TTO`_k zRGC-B3zN9U&1v9CF{~=hdGH7ao9k?`vK`}vLGHZtql&XdtV`|nrX9c^gux{EId<;# z_Ye$WlVU!3qv~n>lTi7iVt5KKFW7M11+6g&qk4wV_MXynZPW6xAPjb4@p|ijUztY~ z0wM(1u^BX;bZ7uREjH5yAm*9;lpn3Z0M{Gw)Q5TZF!4UEX{w*u#rIc*T7A{4UN!bF zo-+pE&82Z)Me@vSnj6i`O=5VGYH*{XmqvK~_1A}^O{*X!GG1bQ815|1p!8+pnE}uZ zD2?)HZTpI>RSK^!!kYyP7KEc65(?R#Po9TW<4LPDEAXr`*G>=ZZ)$2^pUEiP%=?)F z>e9|A@|Y<&sU+4$&=AZ@pvu!K=Y`)Wm3OAL!o={YIYeco1qD^!NOeRfg2EnJ0X@W(w(T(oFW=d82N>Z5lQ z0nCC-qt<#0yegf1Yz|F<$U_&7K4ZaY zth{ZAqJ zmz#5%lQzt>Sofi#RoSr{8soUGFvP&}$2R>E+pA462n3rqU;7$&Q73OEIgV24(VCiB z5EfT@T&Iffb`wG*K>1@E=2w}1#_31lr|=*C@P~tz`1ZHIJ&G(!;~ezEbfq&W3CPN* zuS-?9PwvBT_h<$H1%RFUF>pibnrPU#Iqa~*!Vz^&A%F6dpRCk{oOt4i;lVog9(cj; z)1UryrDD=Z#_`}x8KQK5BUOi_Pu263E#8DVC6T_8W4{PsO36&Z!z!-nHf54lgMR(8 z=%)YIcP+DEeE5I;*MD^mIpmN=@P>xLxFN2mxL&=#`&>MQBEp;4pMvr5O?ShXDrYy? zfU076)Hr5-mGpJO(siclk38aV`9n96M+ATZ#^yYp{CVkSLfpwY6`;PBD3{Auk2-w!HdO@de z07?Fm8f^U(PJvl;n(2o73uOi210VQ6qXdCEqp_;)uvLFqZsL2UmP)LI*fK&wCXBXc zvSHDt?1vQDx<2KUQyRq%#tZRjbk!e(rrd<}3?R#vNORbk*i|swxY)j%SZ1JUZybcr z3zmT`%iB8Ocu6-Fh8V9jhY#=33_ilUy(AINAd)_ErWpj`^wUr8Y`Nu@g+)Un?6AWQ zrG%ysS&abHmDU*Y(8hHNY-!C9C)RzyI6RMlCdV-rVn)E53PtAd!w>K9?M&2h(+tyL zZ5LFnn;;BQ8QxYQL73_e2Eh;40uBvx-+;PWn6yBG+FyR;h80(<1 z^41k%AxV`bx%r+F5MMSQ4^jp!++FaWLi6xVano{GNJ5=8B#?acDs3Dm7oO$M%oyCh6mnlZrXgd4svqQhzWFeq1 z2m%A%K^kGIo~PDXXPutqXe1`3LdtNGv<$|o?DUnvTLp$wPkagUhd=yb=}!xO=R4mC zx3!yI`7s~zjvp4)V;mp+wuW8%yN`4k9P$|F)Qhe4Dwlaa`q7VeKL7d8PxM+`T)Aca zoYkOf9<@4*|;#F1l)bj>4F|I-V6ojrI&m4X9(Vb6y z>Qg~LRlez_3E(vwP zp(V6qi12;(v!Cr8cieH|)R8}++O%b3@u`fBHn2AvyMo};3{pRF8suQgRQlWOzT`I* ziNwh5Gn6Ey;(*JGCk;X|6BejEPsZU!fYGuDdlv7-|0?mmo^jh=#sM5=T*VfS{wze; zs@S>*K(BEZc96R2($ zNqGHjoP*4|%QFgmXaRUaA3nDO~K9%eSV z;W-OO2m$LN2*RihT3SZ+uQTt@F=Bo{4nYtBu}$6@Y{qdj(NB396jJdT{7#~rG)(KZ zpKEzPrajoljHvGCOubOxmS1l9AzoqLJ!t$x4?Psl2S6Z#G1D{#d|}LlMr2?}H{i8^ z=NtUQ_%QEY9y@qExcIH8_s75|%@A-~KmNEmRvxPjp_BhZeR8RVuEndj$y1h30kqQk z86!32eriPVpX>>u{_jl)$XX-AI$12N74N)6}H zT$Gn^quSZ=1V4KqthAC(jC)c%C@P2It?}Guv$~hbFFPp=M4E)Z&Zaq+i4jULN_#{t zppWD-Wr{1f4@pe{ahYR(oXs%tq_w-Ci)_35Cox|9nZh7oQ^yzDKyI=8VkC$$aVr=$ zUirj!oKM~H9^bHKsFL27%ey^2at{-4-PT2RGHoZ}O4)_NphUJFaI}qr+b`aVA=AV* zAvngmvwFUGn<}#%V!7GI6dMy4ODld%Rn1Wso{+iyRiUFPdDlgU;aOq>>rKRqvUX|B zkcH637K?1^bg@-_y-(9;W!Q%Ialk77DI3V{Xk&rP`XVa?3@r>9d97+fvae~6!%avw zHG37oWl2BrXcNU_%f#XG*A*{3u}wZ0Pm71CBVM>wCU5(^YzDv{(tn$MtW`SC)71W! z(x`;NmqYHkHttwxpG#x85;npR5#w!1r z5Z;>6ae#(pLh(oICO&N6^*FYUoQ4&IRqXA8OHBZ_X)C{u>Zpzbp)i5C%09Bj=c;?Z zj9LNRz=B``@B zEW*L|`rg;8CRFY<_@09c ziHznW1gRI)!^y=R&N9LmHimU{&-QH-pMekzO~T7%bSIEIg4=UMnOXzIE_EgqOOf^ z-x9tajbN{rEmL6y5Zj*NaUA|(>oAGl*4_)goD3&ns8Hpt%9S5_xM#rCIc`Las>Rn;Zs?}_Sh#RuxD$cE zri?Fh9G~KWhp8jp9zfa7Zn0kh-mW0nKElIBeD0!yCuAIM7>e3O^>e$Z=>m|&6B~R7 zfuI#O$=G?vM{GZ0b!gHUVai6w^CzilsdO*p9AD$rSh@fNV7dwcOtw*aDBFe`ZrB~j z5al2 z2ICx+SG>)lYZURSN7J}>nzmg&SlDc{&F(Tmcu5u^;|ix6xZ{pHrrmU`Du3uA7A#m0 z8kZ`hDvn{{5km4dfxO$kaj|ZgXITrJxDc=iWT$Ipybw@(JXQAy zLU+KZNZDCZS7$r|z*+#BU^+ zJ=6vE;Fk*N33Q%e;$Z*-sp+;d=ZZhH6aF!FU>Tc+pn4!&Mq%<}*BNh%i099-HS}## z87b4eIA8{eCk+K(vSf*}nbkIx%3IiIMyr&-3wWeoiaCnIPMI?Cqyx^@XtpsSobwhT z%0j9Hf=k(XX?=R&SRG_MFx$F<6yJOpkACo=DYK?=8f0LO_0j9bm55(I5frPULE=fn zn1Jq}6#{X#*JgTYH2XmxRLOa&K=B}_5j2Hcz4e|_jCu43a`WV^<;uDHIK>> zBX9%YffPpOs>mwwb}cT<4lJ`e=pP7&cK=@c+ShjW-+%v(-O=dSjjgbl!*(&<)lYx= z)6TcQ{q4?GS6vm#uhIKJ8P=ExL1n`YK6;a?i>mReM{rHqAyxC|w{o9B6*sG9>={f- z2w0z>^1t}SFLvl}%NklC9~=L{4}Q@1VU)5s>V~s}Bmt!apicaKf`CBOl@WM2JAnEf zw?V_P(^usiQ7Ib1^Y*vDy>s4q=Y@f83T9kk)XmFY_Og+@@=jgN@!Eg@{Q9Yo^2c^w zy!v3ljLSv~eD$ke?Obui6{SBEmPH$y?9@|F4Idz_tAS+YRTNJCc4H}YXE7}Gl4nx! zaa~T?ffNhNN0gUIDvtgPqQ}iVgpYiA_jYxR2lsA<}+1aS7!}P53fP7G+XY&V5KS(;d1g40SGC%prPsT3z zDk}oWYHeL>G~KQts0Txi!L6V7hsZ=c#IPNR~7;cn) zZdPd-eb9V{?ivuDN$e^ju=J6WHcXc%J&UMA2zvx!5T@$j5>c$sfCt>#6Z@)=oo6M7ouY8PbQU)R945;dYBb}<&z3W5Y}67y;Ri1!VWp)kcoB=oPZu?tk5%k^iq=L7N-#aZt6_RppBYj_)z+= zBlls-Lw&FZfuZi=`jcOA-cOpK5fm6BQ6e9%ut^OPp#{U6NKG?L<0ff%HVADgqq_2b zxv^F6*aLM9B%H+Nk_theIH^IZXh_+1+A9@2wlLm~8nk=pb`4M~2@&Pq@7=_Ydvi%N zVRN3)o_+B_jc{`;Zjy%X!Jm5eb>`jB=>536U4tU9_0vjY9LIL=B#xkYCZBcIS>D?S zH%rdq)uagGn^3AhXh^vU^L2|mw`<5M6fJTRvjxxGOE10DdmG_qjF82%aS_Pup^Wi# z;_eXyADM*=82X|~8>X&h3q3AcnK_i<;V9{0aj9sWkfO0WMj#Ru;f+t=-MnoyX~P=- zKmF4`O`43J{I$B*6F6oMbqH@TzRu*9?a3mnJ4R4K0`>D@a?>qv4xkB!6UI$4<2Wi; zR9*yu@tZ0Fe!_Zo9|^z+P`1MG^J|hI&>z}E;(_i-|1ouI z0&fsV8m#Iou0Qcf^^4u35tJZhD{)iC2ck!`Zoc{EK4>Ct4(~QW5Ljj|y2R^+0A}?F zf+DlHNPJV&UrZw#VD?ecIC!jnmc5%G2o$=kAc#Rdf}lVu+zW+wH&G*qZkD|{B*NA9 zVT^t5CVZTuDh_UbH$f1f!7upv`lC$vfx%W>-xxs=N+7@NNp7{4sTj6mciCl^j(u{V zV=s!9NfKZVw^~R z*=l9Wlh53LDz?gTIJyxX6>9=lR9~`Vn&R+2L5LH?{@Ef3j2Y~m>bUrs{%?Nsn|<9& zCh!;{;)*WHvS;@(PMq>QQy+-6Dvvpb-Q_ zga8#5`)7+FR1pGr#7k^VG0?-g1l67B!tafbuhccrN@j~7R9UkA(T{%Ah(V$%nR+U^ zf)@)#k0AKSEO$K3Qsy(w-h1!8OBd-ApZG+j8A)lx0|HVQg4 zpP0VKhbzrYvT04c&|1d8i>95ZW(un@g6b-^DVq;VjuAWq1gwPYHTW@;%ev}tD0*X^e4oq=WQPgJ?`rwR!SYwBDs$%9L!ZF(4kzOp-rFL}vJ z8hIm|=lt0-O7k->Bte&vOKH&^qZ6gjikpOe7>yCkTQTEWCwbNHV%G@fZMD3}vn@3k2ZYbI&cr zhq~n@_9m~WGFw0p1~uJT0|<}|ZwF7}PjIN!QGPKck#%iBJl|VJ2*{9+YBgC15LCYh zr22`OrSRAWu6uYjj+CF)F1JVQ!ysfj9buzlFTeb9Uz|)g4|@*N(lQa(7(o}U$IX1b zC<`Cv-Neh^GgwqYZwt_ec{d-9U@AEs3}s=|UsebfEm|~@&kt1LC5YWC}qXhQ{E#&k)pPLpS!p4}P$7=9y=fB9lkIZ@J}`Qm~T*;tl9JUa;wQ4SvAq z1;U4`z;Qf;aObcNf|N&{HtPfzTyR0>)vtbaAzI4DS7Yn?L{4FbLjchDXoLv4>O@_6 zTyLp(g+W4BBPdX|=))iX6o*Y5nX>=TG_3%G=;PTJDI)|NKxI*8ItT&0hgMA)@nckf zS#{>)m#0|%-xUNOIEWkOl|9un2>vQ*C@hCF_!{hYzx&-%Nx%H%FL&%iXN{g6_=3>r zC}-UAJxmpM&)r8!OCIv9%t@nt@G1n<4a+p@^Pm5G=b(cQDuo(`GAQJxQqzu{8TJI9z_pD>txHCRqcoEGjc^gPdpP#yN1LRkIIJ z_N?KZ_93#Jciy?nOizE)-ISFsxbC%$9zmcI>u4Da9O)*&Hx5I7WnNa}jU(Pk;6vY} znU02Men;_EQ{P}w>cUr|5A$v@(ud(@x`x!^9*1EHm1p=+CNHP2zyA82B}rqB6 zn!I5oy7O$x z$L{ASA2OS=R@>FzNK;np$|E!{4t)GZ`RN_j4EQ`Smr=Q-tCo{T*K~=aPM9h__~3)x zx+$usLE@)u@bMR`sBkR?1hFA16)w0k@eItk2;whhDt&8ba{#{6y-EmHR8wYs3=zL< zj;Wm|$uO(3v%*DwnRo_|40J@O(zbR!2bdv92!PD1r(xoefjL$=w~L&jN)_B7HeCb# zb}J0U+@l_tb$KBuPBj$7?P!FXKtbldl49wLg=CO;))qMMI^73vL$SOdF?>Z6Fwpj6 z9q~WryUSaZ7mxYx@>#OgM%O6)}l(0LN5Zs{gq+|V@{Q|lQkB_*SY#0=B zdJ4@rZX-Uc?j;Bx8#f_weylaHwMsuZlMNNXsc!^-661lGwfdqjYOAlG( z>P=xX1=bTi9C8uiO`)#}9nj98nDJ1PjPdwkqiGFj3S9#ZTlw1^yD0|daUho0KR7Cn zP)wpP9flv2fq^h>ltd2dxJ6hZ2(~)T5b;~cb)NNaIp}@ z`2vK2{dqJ5gG|p{(Kb#S9x;~To&g6-nF?x6pr~Bqq*Hl8lksssT?2A^|zw;S-H!v6<=H1Iop_AsB3S z@uO=IPSOC65K++c>nWKS2Y5X&FiqmGaB8`LjG7p12>v8lU^Mfl?UhxJ<{_>&1i^2m38X;WI1${xWtcwUI((Yw2g&oO>^24op0jh|?9t$MBQz7tvT}d=aiHACg`-}<2Grg8jJYf*sWK%?A z-SI{E@_1!w|7a_nAGSS~WAot3#*L(AY$NEkCKP{XLa~eeUJw%l17xHgW&3d49#(PK z5~@1lm3M3_zc^g}VdKGrNtHoyiZ_@CYykK@tNi0^ui(m%u*ScU2to#ZT&7uQ8#i;U zKnM!!_b0NZPoYgb8LpF7~$j-eTd-vUUGbemv(j}afQkZA&-|cO~{|}lH*oL_z^QqRf9GJ}U8QpT@h(qy@&OksI3^>Vlu$?dV=20)`)#YB&hve}wTv zq4NXID|h@VGk9_PJjjQwW&a}#IDW$C^YHWvw-3v6dwRS(FO84$X}nu7sW8RK_AuV9 z_#)e<@$RB@iuY-}Tk&OV>e${sf5)$X{p*v7m8b=-r|-6{ff{=>?-kNW-LJZ5yil%p|V@(%@-;GUThY3LA$ld5}$>qTRNo z!xtfWKNYviBHAgJ==QV@%fl+^$u|X`3d^D~1)B<+M0)7pXA6*@w_S?&dm2*iBBk)O zjW*ioJexMW!S^UBL~U4g4$z2bJX{^drlHsha(KJmhJC>gR#j^C9GaJcGD~?d;y_vO zuCCs`MagkxSjvvFx27Hrppb1E@uORAx#cZ}@y}UU^Ei$|_=#26t6PPT#lCXkY6LWX ze)##u5kDHgddu0~0HiPwUX%r|qoXiTn2eH8nwZ(nr*cx4hFYN*erk&0bq0}C44Fz{ zlT9}Hv7J5G0gbInkZ`B`J}!2r;2}ANBMjI$d{XH>JymER9n5FAOgcVYWZOjHA#ln@ zTx-g6KuVLx*li2E`}IH+h3~LZvO_Kk&#FUUVwv;lygLiWbV*NHkUtxdUb1A#lGo#p zO;Rb?8p5~i!)*I{hQ|q8|4I%Z5DbM8T86&%N^Tehpio-{u#!)8x{ysq5PU$84*&$Pa;evP8S$*5q81{?H)~6H}E?juHY2(jJ^Ti2T|H_>KhPVhPO2GDngS%A% zlaUbW0p8pBnV=+avlvTwt0dBO0$*$d`@TEwxTEJ`#~!6%8h0c6(D8Mqb;B2 zaTqVtv0rfkaK)cwFSb1lZpCMXD_(XMTvoW!$do@w{Ae=F~SlsSwPcp+)Q zf(19(F!=?3Va6lC9TK?d1PqN~^1_;y9(qs&2!d(JFz;kI)tcGI0j)vU1Hz$$;N#>n zQY4b~>D(45liH}<*mefwfjjTKb8}vFnoEE!F79QT;y@Lau$gRV__lTub_`GkoFnkc za3+_%EnAucG!$fjT_o0ySV!Va1P7+14ALp5U#OIvr`+1av+Z|-wS^nQ^uZ3!PicptB4y^+nwA5e1IPr^3!7($k)+)W?k-NI8kA2v9o(tTpE9EdjQ($+ z6y{n%7YWd7MekN&eOOgDII5=c@Pnr3P!V{RE?wH4Gq%b=HQL%)96(0c%DnZ~Tf>wB z8RQ8$LMgEB!1RK32el2!yyPnm7k-7u{&A&` z>4Of@gdRX2OxcmfPQ2^Wr`8gxm+#n&Evp&>#f%_a%dif)hM#I z^Ms9pwwPys+t>vK{;r4OfT_ruR4C%O!Z_iG37Z7K&GJux|sebT+ zsT4e73l`&N9MvW2>Bt=@04uKIO-7zFZDTxsR1HVdl!$vov2%}q+ zc9ekp4v+p1{*U(Loa;K8MnF zc=Mkqj!Vv+T_X-%cjC3xgmEWeEff}^sEk09x>sI$c0(NtRf$|YcSI@xe!zli5U3SPqCuS8tKloZBQ&F_}eO zUyfhz%m@D&wQ+!FlxR)C_AXf-aF*Ukd?`j}D-N(;j$XCTehI!YgCI)UEq{^dpIb&%7P zu8e!Im#oA;pq+7VB4O2$SbXkI5$Rc^t!d6({i92`9%42M&G#IV3}twrVmXap%;@XJ z5i*%MVsV7+ln#zB4?M0n|o^;oq8p+f~&dS~~PmwJtdBL?6Rw+`}{ziXM%r70kY$&(SNVNkmNf~-(W9*(E zFk4q_la3-2Ynq(`luX4%ct6{ydb2S5gZ}i z^v(rxv{FDx=a4%c&cN%x zBTI0`(KAFHK3_8&9RSwmlNVD2MX-~GN}6+Z5pAa4kObr}c7L4iz$a__z=1ytQB!*I zB05Z2(qp_)iM8a9$p&oY+=+`CA{Cu2X_H}!XCY>}9RE7DqsZx?4Ki@66)&?LCa|v{ zl}(CjxR&H|t_dNi4;%2#)>ht`BkJPHy z?Do?H5&ULy;(Q3Kb%sj(;{J-QOoHy+{(r|h`4VM2^O6BmIg8Pa4=AX>KxG*9qkZr7 z$|FziKn=1)s95^J7E+%;{4Uh(@GqtI|$VBq#96T>sCNx6i!x&!BGnQ(y6wu6O zcPp|{{!urX+f7)kEo>r6rzsiyCitKeLcSvP_@U+U7`gks&(C|@KfR>+epdT6W;=>| zZNxSVB#IO`iXvhbWG{#1P*oWqHWR-H)bZvJeGzLrO!C;tI~zvkW{KCuUF>&udW3Kx zEYlWa1N^{zVU$IlZduSL1SuTZS_qzud}2_l{KhzDWvVK<3*tT{7OVVf0m-%M_CfFt zR_5%FY1px8$gAHro_eKqbzC?yCDe|wWrF*V`UgzA(sxD%UYJ{A|DWOe=9qB$!#Ub6w~ELY>_%n7$j6xyWl%_ygRp5 znr&WPM}v!psIZ!D2R7VaL&h(~4(__|Bc0EU3C^o01KkEk`&@`Fl?AGpMuTF@1va}F zE!`&h^m{)!QV|!uTnsE8b(T>r`Li1jz5E32?uQJ1=l{Kk~7FEiL>!OJJhOpD{L4cJFPGlr=+A1j*{ zSJ15!-}$1)vi@^er{=83Q3)a$%uWz5$p=)Bg7bj%^FB6@+)usWmS>5yxY!q&OE2xC zlP2||J))wW>f2%9StGU)j3Mj^rlcxNKc9YiHj!1)qJY0Kfs}xKVLlU_(2UF zR=ZzSn|r75j9=4t_oubyXy%@{lf!*BZBF7&Oxy0le|1kkte#mv`h47*lrD``LDRM^ zkK9pd$hWA?CGxp{fPOGM$6c9a_f6DmYV*miC_@Ixz83+V21xuCq0MKme&~?0FIWtW zN0JB1zYaH=MNWRx;zNC#^~BzhU%J}!t0ifLCpMw@<5Z9K74CfQH7`=n?Y-tA=dccrpG_@pCQwZnpcOtOylw1P7Lqg zqQ<795CVA0sz9Kh$MQyIJvVnZ{CTb^-diGm^$@HyRGTtS@mF*{>7w`W8xD|FQ zw4k1BE$3dx#hwA8ylMQ)*E=SxINHlMbB-WOP+x37qyADY56ieQ!Tmyg;m$_IXNg3e z9fezxh=pFTa-l>p{O`{qESbZuT^H(Y$c`O*2OE?ME6w~OJ#;^4i4E>PUb=UlGPv|_ zcL_NxSA<@u?m`4`EAV3tUg0<6eP}UhD}_kZ_|9wW)s<^SGw=Lx6JRsQ;lHk9%Xlhe z0)asd_uq{Th1?qaylF}baX6c9?5KYQu!+c6hl;bdp>=$}GEZS<9&x`*DvsW6%&%9K zR{av((djN)t5EO>+H2nOJzJ$!aO48zOcjw+CuB;!yc|(;S(lR5KuEcz5h4O1tJOTt zOZX;QXMnqW4>O=8F+(?4tJA;(!ReB^xV`GF7Ga_+0 z^8$Bm_=+HOs_cAl;_Q4Q3#JQk18e3Lec1v+5mIf<;sXPG=-248l}22#M-;HJ3p7^V zD={_$k$HvOBjKUHx28ic#s<4Fna<+h@e=~P6oMG%zbyd~i_Ls4u8En043yh+u8+?!6 zeOGp%I$&#d?X3CXYR5rQ%l)&GH2dm`S5TOs`gnFEhXsEj#rgWJO73yiMS5l_$auwPqO>*5X5Q1MxDgKP#avVg%WTIL`Kf%Ek@1L)S^b5t zH7A}2dSvp!sfBs~kL%P2ez`(TcJ9nnQY$+=1N!Pq?v4(8?E_9JX#3m_{%} zP%*zOcJVA) z@Nt{&FV~rD$sQs6MHw^ZAS~+e-N8UA*x_%#(myYG_W>KhOQ#5$67$!J-HkHyi}~pe z<04vw=RM?6m#X|q2j0VDm~Q8YVM7d8(=-B3X7CHY*+ylYsY3NZA{f|LDg7jWVdUu! zyM#Kz3IQdeyks6u8ESt{@pg^kH;Vu{zjDP{0=8|bHJz7113X^smHa$2fOrWvx=9c@ z&`NdvxANM8t#E)mKj-==vvXcBn)X@AXjPsv+fiTRgMCIFK^?Ce#l(3eqI`8P2C@ivVN;sJZ(GNg$Js-%!f1fPBK3iM$sAoBZxE(rR;`ibOKH zCuKr7-_fEONf|V~6x{OI%si{hdTh0x-y&U{PDB#%M-x%O3SMC-_`Xg1H~;L}>y_y^ zOu~64qw%BN+Lnc*KU=BuYE=BXhSkBSDGg_#Iu@3Co_g8ykYJWZeWq4mnn+3d>Sz^x5_Cfe zE7H-(a!P0gligKC;!9D!7F+i?&L1^DulY==Q_3ndTJvSVM}(l@YTzG<_RpBeVPB(Or-|0hMT*5)``-zhKO512c5n9wxsgG>{CV@Rt7G|_$*8pzN}%RKl=xp6HTq87yB6In-|6Q@cdOjq zbcnySzzmeSmX$TmA@jLh=lQ4y?i1#&F>>b* zJ2egib&snH*tVl3dEE5XQ4hcbC6;~Z6sB4R@MTLeZ?o#+3x)mute6$7VkUuj5#XVV zHZ4a&9R~D`MNe*kXG7M&&hYaRSX6GMppBV~+r6>D&P3+!yg~|0pAzuf?Q;=6D8+ju zsv(hS@(dZ7da?qj9oU^)BUKceb@3|CJ|iU6t;qv{7?Cd|^lZhGAkNT?9a(83sq2qr zTbvM#l4E`eOF6Eewh$T!ZJSbN>}cnI95a}_QiDlf#Fko@?j&Chm0D7=aw`_FmQmAr zcMm0FYcIW;^vC}bDs9>W6bgu38oEA6R=M5t*1PAqe(k@Xqr%Q&!^kb$+YO>FW^`ej zAM7IEtE|*{Kq$wCVLaaYe2<(SDIWcCCp_cs^aSbog7>bPYH^ZYA=(jLyv$TGhj+Az zJ07%y3p69df_IK@I7c_ElKQZz!y%!{oy+0Q%g1LO_e;Sv4b$KH2^ks8)vTp{NKKiQ zg!8J27pQNSJGL5pB))rpj~Wbo>6;GPkFiuB9{2eV2XOX7P3bEsg0o#TNseVq*Rx$G z0PsrxwNVEIGDlVLGS=60oF z_R{`Jg^=8Nu0=-KjL8{gRyNvFj9ruA-@$w$_Gbkx06a1fBsCPw7n4I`8c2f>@OBEf zDnVfP2;-M8|BO?g;w{w;WMVH4x%$6wc!uPP*e*dY3N_i@|EMT@^-EnWaI$7wLg(Qy z96zB(=k%-Wzr=ThMp62qN2&FW-8f34TZz;Toxj(PYJnfnCQ-0}O zZ|f!@-3aL(4J1~4c!8U&nit83bQDoS2ZSz7#gb4?_fH`jHZ>v7cJ#XMA_t4O_(>}2 z0#yzvj93DS<4t*woK_B2yh{%RL>QqB=DbACv<~%k@-KwcUbZ!US7B?H$ z4Dj2q7F{>tY@0^TryrAUNxgjegUq%f>4!eMw^?G~ef* zTnCan(f6vPf^~_yB9`7B)f_ae0Ixys0X-HY%W0|@|F#7_;e4TK6Eq{pnqp#gumef{N4C=V7k4ecDhIe?X0iafV%B|GUK@`>Sm_ z%aLlXQ@YJ@D zo-8Y$jF%1x0fj*OK|Zm^Wu3G%So?~)nwZ)zc3etcy@!>lWdrFdb67L_(3VdjTmZYM{a)4vdC5rw&uJ!@?a(bqg6dPVESn{rbxljO zEmaj=4}U6FbAaMEsbomf(9rocZl6hI!F=U~wftR~Y|@>8B(-cR#y~&u#}{1LX%Gu& zu9vb+RZR5VWyI*t27z}sfA|`nIZp%I<2`xboQjz0fGM+k{hE-?uycNz9zyphRE5B(jfk0?-T(_8uS+uNZ|JYzFZ~HbJfs$r1y$z#R}a@aKN;#Xb=$t)MoG>*PPPBVL3=D{`z$4wofQynqt;~@%zGNDPu)%a*A?$_lKW5v0nG=+Gk()J8pYA=)hQX0>YYCTYkMtq5^gp|+ zUa5>@KvIez4QTh&zX!=g|H=F2865EYGE%lDIy4I;zI}YYR>ge=3#Hv2oEk1q`tZ+M zqP^sBlW`TguuTMElT&n4`?O@a-*lVgfb`)fRl=gC8O7&Q7e{53vf|s!L0xH@fT_xLS*vH7_8kd%`}H1FV{2U?(u?i67m2f%Oj?dQP7aqqc1y1moDeF)wP2yrON6tdCYRO0BXM=`s55!^f`~J1(^= z2ux-Iv6h9Thf^5J^-MsEPvd=Fg`3t_7d?bjd=Vj0aM^Nvqb<*yW(xh&P? zS*!$&*s8L@naO%gSxFNz`6-bD%u~N?SR+RvEgqaty;GBhc(S*T1vrv8*s$L~4v)?q zb5y}j3tU2dYvZ%zD@5w&85x3e?}HMI*Zn91#*@_zNqZji-#jcYDwNj2Agg) zQQ%qh@Qs=|6gTm|R&k?(Y;IkvyW+`?gnvt0t3|nw+~+wt?1srUTV(XDj0fc5%&WWTlFS11 z&@{jT2rNwHNJ`IV6-C6{CY6`Q#FXc!Q8s7@*N{->(Zk>7`!CzgVb`12e2%tC4!t7# z`}{2wp5@K0IeQ2Gtdnc`?#tXzdzAJM{=DGNeC9|&AAd6eOikVGv9$w4 zFVieM$&abTs13L z(Tdj%z=Ik{k`?#3+aK^45nsFg%v2%}w}-zLj1d+1BKyJnth1r&IMGDKXZEX{1=TkU zVOoU985|)mx6f`rTJYx0JARVP?QH45v*_~B&N+|-841_!rgdPhc;ac0pFa0ioDFci zef}Q82W8eT)!$lBq(Jc@4@38Twf^5Va3{*GtHp&(PjzL=wW~$NZG1poj~9^KU*pGu z)DM_)xWOKl2^_Tw93w-1GY5u3B>GFNzSArB8lZ8J{=7QrgEHV)ka# zI;k>8Scl|(9Xj#y9tMUkorc(SOJ5K$JSl#euQ39Q!8^iemt%u^O6-LGc}S@DFfWAe zA~RO>`V_c<@!5_ktYNiET$=l=NS8Xf(K}>FgM>P!i{?7XNB~dYi)K!6BR&lKa^O+# z()Y~Rk=o$5i!3w&7S0XjIY_IId8I>h8HOen&3Smpho)b};1t8veV^=e+KuF)?@x!T zlz)8F{Ozw3E13?3g1vWW0}6K8vJjT_hW1SWj=AJ69daqHhu8PfOG_i#)~xq4UqgT6 z#I$PZAAxn7FzYAM=Xdkd^ZdJm8Zp6g`=llsRc9L~(klT{kGjjo zG_sVMj79S+{e;4(e=op8bZWm^U`q}BSax1-!hcXPJh#zacI=fI)swD5(`2cPgIk}p zqK$i4`*uucp01NPdLTgS=Z+q>|C&t*Zwtfcze8Iu%16Eo)%t`arB-DjmiyiKOMgvf z$~Y6B` XlyK#72P5D=69D)}y@wU5){*}M?+_Tu literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_eon.png b/selfdrive/assets/offroad/icon_eon.png new file mode 100644 index 0000000000000000000000000000000000000000..72856c4e685d8a5fd9d7b9f029ccf6ab3772c6a7 GIT binary patch literal 8624 zcmZX4by(D0@GmS2EZrTF(%rqJNK1#nA}ZY}y|gq)Be*N9poB;_OGryeNrQBU(s38x z-@W&_&wZZ#L$R8}pGLI;vM#C}xjyv`uT zX9HW^hMc$Coz8iUEH(!o9<&DfwcBmX%N?G|e7Id$k~`l!`1RQU%X_Zg&DuV9Cih}D!Q_znjlXmSi*Bk0hh)Ug2K3gEmF%u@8DzZ5%Q96u z&DbsUZ-3$HGR*sF`3t{N`Eb|A)RRaawQYcr!zK6UG=`*?W;cbW+FBxQ2tZ-yz5D3R zi0<-lv2^rak!Fet)8UpMhgyosRfs2i-t~7m66iMPRe)(ZE$HR0s5t+(t_2;{d^P3H z)Iu(}*Krdg8FZH$CP0N5GNfDPL*LZ=j>3JSX}&ykBN3rtimWAicci6(Gds9k=w6P9 zPVp)ai%s^fn?mtZk4$gJ%^IFH%zA@WB90HRuV-{zM#H@u+k$ib2 zPRZ6~Qn5o(1B;z1-Rs7()k-fnzZsK(3HH(yX`pwB)0bH)o%89%J30VY^s<0l!UcNY*|7$+mlD z@YSAS5dOp;u~cVK)Qn4G7b(ij*iE|j^@OLMEhI2jb85!c${MAZLe{g$fxDGvXY4bY`#XN5s)Ef{n*V9h)nXZTUUi=0-^)d?@pfR8e;hrXA z{I*VJVM9i75RWEyPGcdWztx|dWUXMKv$6kij^GBa2>M@=FgV__NY-ICc5!VKz|NlZ*BZgv2t`TpM@-Nt zudF$&C61CwkU`v+b)o@GLGeRznLpiZy+WmEiro3tED@cX?Tj_$*7vX>Qx5Y68?@uw zXWJ`Q6m!``;vBZ~x^HZYpDr-mN%{|$okbL1JDt3QOqhf&5zvH(zF@NcbAgVPDQ577 z_*KC&)6SL}fiIKS@0!9S$P;d|8X+>?)2%AtUS^h&UH0~8%o7{m`O>ehv!IgZvo8ue zH>nYrMZ9#gi9ec~UQIFUiq{d^!JTQYYTuRk1+@DNGAbJfe$Eg8U0dPqHJ1&zsGpm8 zzx8U%Yv?0~38K3t8Z3o9N}79)Bfi$@BIkR}%udD>AVR2MLwz8et}p^+Z^2>n1}Aj9 zmVZJoHaVYsNj)ppifmempm^hId$}#-V#RnEw!^*b-;BePtr&*Cve=otwLwU)`-78i z-ELh>j^R0_S_&?q=$D_RFTUP{2PYYMB(%C!el|mYqMhP?$iM>-BNxZaRB`ZU-sBfc z_i0gK(c%yaKa5fMsi}El*;q&40e3SPJ?-sRa>dh=7*<4n(t*NZ_LlJ@_==E9 ze>YD{b*XsEyXS%WkY~Hx!?;^O35hO<;-fu@2t>MRc33Fp$|Lya`Q8(Je|~V^UrpGw zNt;PX`)!i4Tte&Nn=&`t9-9_h=0c>gcP`Kv!o#BXta{uOS{@5l{h?utS;qpP5SxR4 z%O>A_dQ1u_MxIzxPFa5}?k2fuC!KY3A>*oqLC(?6>Qx>1ibAjsB5utT5=(SApc6Zp zW-*q-?sguCHTD$1pavk9%JST^jcd!wys;4nZX z)!+79(P$^Xn?kb%RP@@VeSU)d((wt6$0p0Xb-f+^kVI)iM=-nXM2Y z_b26VBXb8%7pGrYSl?U-avIm|qQ!jw(CpK6x5Z4_kzH>)>ELb5=XnZT{5tZ2h~7CR ztl*!jVq+%=6>E*biRO#bd2Zj(KMMP8d^6JZHR_;j#GpSD=T1ct#5ZHEftwtMtkv6L z5832GL{-gxD3|!CG-4tZ=yP*M;f900rJ<39#UTD?hrH%E_$Q%XPFwbI5o=-4q2k85 z)=GtD}7aC`&pz=8L!kh5v zYXczvk2~s`bCVq(Px3zwGsGh`EqOQ%fZUHqT>|txrX8(-SFB*fk1N(G>-aD1017hL z_<@PXBNSbO9gJwLo}iq}1{rFFX~+x}KjUFc%5}p)H=7lIzaE|VEVIsrqlTa>72(ol z<~l>&Y;OKMDBJC;O7}_zfh}w$fd+k1knFi!Sa=0^@v#-|X|KvU0pfa{oC?Yf@~*C# zx4O+U%U5y>T#U&xGTCMkBu3|4ayHkIZf9mIPZX|mQ^4;1el(Bq!L@)#h9*(orz;_1 zJdJhuO5HVk<uNZBJ2?Ad zY&*8RtA%u-^b(qO*p?@{f9lU4+9(RdlUgj+D+$L&{byKt)GIdGE(#2;msKztZIUx8km+oZen;!gAn9%Co^EY<-f% zYr@VZQc8oL@BqN5L_Ji3;6+j8jXrW=uG-HqMBv8pqM*XgmU~nkAV*Pn56F6nUfNw` z=VM&#T`5a@(ozP~x?Y|Oi71T_zX-BCaatb_WEksVXdU2G$OH3aP!5PwsWbNVjLXHe z8+_|LyMBDkXa7R&+$ud!6;_$i=V(7Pekokr#z20?ZFpc}^UJNBM>Ke_EY4O3O~a2m zXe|!^`{Z#_``{eb&Mmw&uRdwOht$3lv41`+USVf(K5~(>nWkmcTkkgb7VH72^yNtG zT!rf%d}M4~)h~@^9W~aJ`Jw=G<-d-VL6@fF7&S)t3>dsOl@gn$DDX6QGUF+fe^c1m zn!HQhK3V9`bc#9Mp7b53#>nAa@muKL+3E~d1^ikJ3p_Km-Qk5H$Wyp;B~0t!MCVdl z(|@@!S4gvgu_x8AZbx$#kG{kssLuG+r$3@^nQU=z z8#x$FdV&w4e`l?Hcw*J(FcL|eafYxI*-C-i?ye{hDc}`|gki6W(`?8}dYmQCOnU76 zEjg_yQaMK&JPu67;h7->9CQwSsfxj4kOfBnc~LWHeZ>V@ima&@q37Zw<$n=b5!P9C zQE(HRPZt)yJHrU*e|0PzgKyb_*7Sy9wuRu%rNTu*?!xqa<?7Mm-nEF z9OUMUm5=de?-_5*-oxhBcYWNbGNZ zizg)1l+eSRq=IUbZvPL8t1uY0Q25g$5|58_%d2Qba_`9v!N4yZ5FalSCx?YZTpggf znG{J02J~G5v5Xl)n~SS#JAxM!f9-VfdnL51p^TTSk01wJBTsiOwZL7T&#iK)r?+U+ zbxrFAU83(TlnstW6644^UFBBB(Y9F7$4RFL|4r1xjSJIVo_uVRS6ed$%oE0qL-ygw zzGhSB+ShrktVmKq1}#n$w0P-2K!E9_xtyU^Rc`FC5Kz`{q6c(TghZsWAZpGY<#Lhn z1@a-&s2<6_BZEF8uADPPY}7Dl;HkD!73|ixw94Po*D_<#qlMSj?#FVo0lL^B8NL7^%kj^)Bp~9- zOy6^GTbc^Y7g$tNE5lA&LWN#hQyNHN+y;%LG4C~1|I6_Oz?RvcC3X;IX5{N8kx zc)CuVRmNy%hNREXoP4xSJt-}zmIWn5f^Td*$HFd3UP6a5@0IB8q%}jtxX;1Kk2;q9 z%UzbZU1}&uMTFj3_OkN2+FKOa|0LW%b(R!Rk<|+_!&y^emw3@4k&mtcr2ZZ0*_9g2 z-(T8Wu;D4MJR_U=0TTS-8vk;Mi8P}_RB?`l#vC^(0U7^kbHYjOgD4Gd95^2&>lm41 zQ;e-|uB_H!PU7E~`WR7Tp&cF0qQ?QKP89sS4Nad)c~)5m{Pb%Z-S0A!3@S}pDS(^f znBnWlfXL8dK?9T$L`~4q?Vn_E6~aIX?~$UciaUI3GCBB|sxTcOpL7;OH~pjtW{_ zKx;;f#`U1&iew(V5;T#4mT|`M%{^wqNWFj372r>8^GGvH<2pDGhGM25v2AnejwKmR zqxeSGI0<@NNkXOh^|r#A@bHZEY)JZamqk3r2H$v_bToul3fv^GSYv#cHmeQ}T-4y6 zmIN3ReW9ke=G8eD3ULnr`*p6_42)G~$9!LrjVV4M*U#x8E72l?C7<{Hsk5admg^uk zGgmoyvT>N&pXYL@?2kE4xdwJ=x6$-WH%Wa>((sruX);1z4aBfUF-!32TOFyy3d(py??D^-}YlfYdclA4!HLZOgg><+Y#*uCsHK*8ZIDUV> z6yLlig((qAR*9A9-ZtXgNpFo;W7HMzXtSa*G^fUizx0bAA-P==eo0gJu|4_P69rcm zCIEso3@+u`*Ym^o+{9H-UG~Roe5o=E=lQpz9`-=odjh)Lmpdii06}}~!e@TL{k5U! zfchr&r@bcdd^alR-C)l9=5U_?3hP)v)|;q?_S>(mqN=K3pbCs0AXsw>sP3&#{~6Fk z@yE*__Em4(FSWs`$yZ9Krde{7S;7*9OgO3ffef|d*Bxg=puPpNS7|2LTJs%Vb2gJwVaI^5g!`VA1+=RZQ(<)pxT3LA*K!r;!s0b#FFn=3*J~UWQOOSmPBX2afks zBkfuh%g$Hh;*ffvzEMImP!D`kiAgga=GX{L3%Z)ZR4#;)tiyWKhMMK-DIAKZn=IR`m*m7t0>6+Sf1X# z^s~j+eG=;30dQ`bnmStDZzb>hev-H&`l}69{R8%q>()k*X}9IiJcBmxG=Aljrob`D zU6=jkZvvN^Q9Acbk5fyGPV4PmxpY!QZ#=&^J<40Q4qw8**FAz?GofM`*d;~Li4S8$<`y0OE?AhRhMW)_m}RT9Sp73IH4d}4!bw>ewTNF z7x!T+`&WN#Kf$A*w^+22B8ByIsUcD~1Y2Qh)dDf{I?CUjuD_INpejI{)tz>)zkWxY zbB61V>;~`R)lsic>Y-Cgr~_wv*XYMFDb5Dm#rwQV%_2Vf?#e3wOyKU--=)-gpu?W^ zLv|X0I>^zx?{tg(l>!PU| z@T8E1DpAviCc17yej*zbi<}`g1xRT#P5~z5F^ht4=?mh%&woJY%ds?h=)73r8gBYCqIsCLl>mBJh zbXv6_2`PPRLK4J1T9Qc!&_h)Y0V~o%@#}HVpBk!1#ao|=eZ^!2O2#}$2aj9xQ~Nqj zbYhl(ZVOTT?O#}>E$n3yx}Mi(kfD><3ql`<@2|fA_rf89i~FI`u#Dy-iCXsj1P@-<#J6Z!k-vLb zgigY#hHSU|E6B^Sx5^*Quu_}RggrEfr#3bN?OR^N(uIiMxL2l-{%a|4AOu6VbF__- zdXbr|ugJq2YdYgiA7&H7v-9|)ROLqOl~DBi6wR(b$D;9Y44 zfz5w_l}3=W?0&O1YA=qHu-+1Bbg`51L;wd_gLuQ79#o zt;3&RY3)eT28VaA`srgptQW_%$ZE|c=h8&^#VYd-$}c8B4&BQipWwB+;Znvyrp!M( zQan4dM9iCUC@)lC+rYB{>Sdrncq@6|dm8m!^>C6~PSWkh z#_;Cd<)=lPP1#dpFwzH6NDz*D=p3vNPGHHEN5Q+mE+k$dTxm(orHN8A1{8mp;7XT8 zD2^$7+v|a$ih{#KY9OE?K^wYx4dv@_?YCV)lM(Mhv0nHq{VWcPvyhQ)MVCk0Xi8E`{p$gOC3Uy?pMb2cczlJroYrlTaK#f=3Af<%v- zlZ7lH&iMqxD+#{s$nAC38U{kKH!FK-lD0Gl`TLiYSm~Fz10SfS8_8YVyJ)2T<%1UL zVutY%PEbBpF~vJ zS0?SJ57}k{1QWyH!Mu99q1PA>9RWqTMNtSA(wLOzh_ok39=t(Ar#1f<9AYRgj(uXC zQiG%UgF1Dvi1{}30UxN>rf6fTF7D{E4ODr~YX6(fmSfPiqM-8~SmUiH1Q8Q>&@NgN z08tG1XPSa^G~xg1`nRMA?_pPZ%qWAF_@%^^x&IJFJNuC?G(Pt~AflsGM2X+=kJiP- zp@10%3PZVSjp7&l$CpR(Js-3%0VqhR?Gq`#e$ByY#}AQeIn3^9$)Ond`srT>IRjpq z7e*b+;)d|4owM8^js%b&@IqN`UR<0mTQ0_PUW?wy7WKbVoKRaqhzkc4I#-y z7w`J8E_}m!BHt~{i`OnJfAyXGA9f!T_nA}XYbeX`33ir4YdCR4#s6KDAHb1YY#gnd*W2qwCMHxopw2L zO8IJ%DI+P3+H(yQnVX=fgX)+HDLJolFjP6-K}@HaRRsRkt_vHo|8?Jw<#F_Bo#1mG z1x1gCdLxEb02v4R67l)$YTJHe^8OFbZh&X~oYMIsvnlW&E!3G~DQW+bwhvUY7*6XK zr8N&&Iu6hLKfMV)9scc1rLS+p&6xc`5DcV;E<8udsGW~RXW}TGPX+i;P@s&VlL!K< zTn}dlXk50K0sG8OTU?wEX^;X94RD^4672VYH-@32>2vC$V)I`F4uFDQ>#Pk5M;Z%*4I(x5Z*ts_uFspk4@P_} zdDzDvrlZFK3RUI9qj#f&@1YmX|8ubh1BF2l&nxklmwBPqBde+K@99}G{tKPJ-|{w{ z|3DN5^5$5c8_K9GPqnP28wkR6xtXZxT95F0c4VzRD;Qp1xMcIEQ2xOy7&)NQthf-a za6)@+LFK23Z2-}`$9`+=PIG)LEb9Ix%lNfneQL&21DCf*f3lfC`tLD`vN)dBzx(ef zW+q-fof@`xa8^jt2!waid_vvsd$=|zj;LT-Td9@?EqX_v!Q1TWznwhSP_}Y4!~DcA zd$zYdX!x~O4g0RxFYo}u_jG$}QsVhhGW4`7qBAj&!G+kq^&<)V7ye^Ji93@=|BAX2 zc(yhxZ5#GO8uMff$@rdmQ$JzFDa2}Yw2GK^t*Z0;(crSkAoGayaL}XZb_IF)B-T*G z#m63kqmeGR@XfMpH;)F;-QWL|fdSY^y-OlJf((4;rGu>_YSe?$67K!$3s*Xqv4dmt zsmqjn-C5s;7A(;(Aar|jDWi?1{lSmjo(ha$FO$w>a_>fEeJ2!rXn_9cAy#Tu`R^RG z+A;6BsHdKsg3S9yUyFe-ZgAI*rK~HO>2X7eZ|EPyg07*naRCodHod>)vHMPd2Ne2;-4woW!QHliw1hH38QBf2@d?Fx1z*0@9_Id$05+O%N&G_y6|UnUl#*GRe&Ba?aiP{nkmc@~v;JWM)sv zWad2WX$fi0oH@@&?nl0r0Iv<1CuWKBIidD>NTIgY^$JAEM~qsdq%_;tURO82&rn{Z zSMN>P#+gy^wMl2Uo3d>mD$naS7zZM;%c?60Z}b#9Bjj>)FM+fjb9)Hv;9eHONpG-j*|q8UMaWQ_!{n}kshf7?MrY?{liE6i z^|cAtv(Na9ZJo-H?rQ5qu4L=vSjpC@Y;ZI^=C<|JI}BYCm3sgvx|mbd=3=^SCz-Zx zy~N|w3GYqDfiddlJJ@v@cIyY&B{#L~6PMo9-5?9S8-TBF+uHU<@A~y|baqZ-Yz)YYo!Dz+DP`j( z(=5Fy+j-|iX&T*Vja~+Jnd%E{l33a1bT|sLl3o=h(>hU``0MEQv2mu&mm3bZ&FBpe zdFNM2ezS}1)Qy3!(UADsY+V(Hk7r(#_xTLX@Y)VC%l@8vNPPYaShsPDLSYruW>tel zV0VYG(klgx?S=`cADl`O;z0kKP@DJHWCAmeTi9eBO2em$;k0#~O9(Y6nIOoQcMZC| z*++WHmnlz3PlEkV*S51+96z0)I?l`f%f}KC*v<@L&HT@X%h=m>Q|{yduJD1RD*>sX z>TGlADW55fllJPi_1OCK##U|7)CGRQ1xfGf>^jY>`Y_Td+1Oxt0$K+9jJvqKLqs7S zo6CnO@!4S0fbIrYUqzIP2lteVHGYfSbw>RVk4~zk3ZrfzfGcepVO%?J-6gX@rmdUr zq1Da&3ZmLq^`Y>=cl)ZZ+<9jV!E+ogm1ne>E;qRlUPL>7Y}U zjjK02(wlNh?wu?O8M-Gqa2tfM(tGeRcv>4BJQYd4a!X^)K;irVB$zU&nnA4yR`D^J zc3)eoIvnYOsMzt0V=I5U9GbfA+}2S(A1TdH*x0192n|qWC97`kBrcL}qIFL3Bk0yU z_-^?QW1F2r@ZTb_9C>FU983|c?a*Khm)(|B7J*U~!31i~N2+k9-Qs*CDG-mLx5qwQ zH#j@n#C1yJF(xRt&D5h4j0WV(bwGo>GXdZ^xSeGpvuu~3{4T3rT{O{q$U4ThzFXeR zu-a|Xx%Cjv=zDUTz?8`^LJl@{8Bx}Kde5fpVs0_S-Fkte{yXG9roA#3fdNr`LUofY zy;N(Py2;V`u9f-;2Il4^o#rOrd@f&w$tQb zw?=tjp)r9n;^cEyoJl@!uTu8gzwG8h=20*@w${yntjLw&1vYqUl^j%?% z&SzIN0{V*qbPet@hHh?fv0OH$o#I<84)2NBV2gl^!Wg=B^siBy(Z_Nh4&9~FD;e8~ z+GO46J2{Q-vcYyE`cpz}HcsUb4*hYVwqjHOe5XrtMhJ{v2fw0MZUA;YhO^sLHfes( zdF2vFUu_dx<$qb_R*D|~WnL3$S=$-Mu5tn~XC)U? zWmn(wF}h7{OhI53eC^UH8Q4T^vTpR9+y>eWKBEv;b|Jja#;3D=i>!1a z^EvQ2G$ghI%I3kAJtCdydxMYWHkl1H0ho4E4`7Zq?c^)k7?n+%s}I&g21cKd|J)`A zpFSeCp~`Y*bavV3x|o${yIt+1)9f~1c>*@c>%&BK5F8?KUcHJiRm8DZM!I*NYqpW-F%4-j6!ckbI)Ib{J==r(oePUXs zvBOa&2n@o>zL>!-8^9mp!%s<_+d;Pzw13^fTP_5l(wu> zq(iunQ;$~dj?;;I1x8maQB=pAbPn}(qNLqMaAv*#xn@w%J#6!(@FZh=#Fp+u$wZSK zFy==ZTcgO$jlC~-xR&!_8tHJbfaPQtky-WPCzayFXXn!yF53R#wo~8K)>-A>Yb%`mOl8Cv@o5baboL@&X>nl&ueyQ}AHC&wL`ByBXdPCP@#;iw%+TBqI-~E=Q^zxX#R$!Mh2P9jGNXZyX)XIOm!E^?#+%o5U zW7j0NIlI2rw{=e0te!5^S-uM^tKbq?O+CeKfIWH?GmO&Zt6MjG%0nD9xleCwv#;28 zc7rL~?UiL?Wb%+fxBW|Mr@U7cKExB!8$RVBjI9UOvq#zO(K5ytBAQB;{J{mID;B3v z?kxIuF}^xjtv~A|Uwa)LWRG?!lLp54FgD7K&g7_cm@xgnt)oZrBg9Rmg$*wq^j2Fkr4j}qt)jGd>smdfxcPbC0qUqdC^ zb@(wpNzP1iof^H9FX`g!I@om$-qtrM8$RV#JT}%Um(~)YU)5^URrBPsc&ni(x=xFR ziNbH4x~aYF`bIgV zou8IVVw|~pQ>VQ&v1IUp{JF+Xc>v>6`_CdanN^0M*vOW;ouV6E4lB0%yY?CNM^k;l z+4JZn)wU51$7i_&b_da)^Mzy`?{wFn1IxXAO`;B{eX7j96?qTDCs}o{@F(5iFqz;Iv z%&N`nW4u$cjj?#Q2E>y(OG4aEf%~}!TRPCXHdCrj=MHx}nA!pCdTs|&ZATVIr#5v4 zr1ZiMZ3`jp%-mbu4mli^dyIw8`Kh{Y`%|}qD|H0@c6M8!T)LM5ll;iS=CgZd^tP_e za`9n^5UB#N+KQEuj^2Xw6gv~nW;Fr%GPW({h0s0LV^vlZk2S!TrYg#?0oBw2lZ;DK zxAOf=o5^Wg#A@#pO`CGN&DNVT?SC~Gqf>5l%5D9?%Dw>5ec7iE1qD_Yb44;Z6xSQ2 z(Yd*=-RP9tc%!#RAeaS6Hoi{(IZ(!*@ zlH=5}E4Hvtm&0kWZSfesV2-0_7-t4#>dK8SHTT*2bg6tc&f>YtqfdMGV;ROS^WSFS z+9=-OA^D@xSshbR?=FAcw58^p#fp`gBI(-2`sk&O8B9LC_nKxaXL&42*DzMQUZ=5_ zp{kE}TJ5ExPWMViX$^=`wUa}vtJF?1jHa&K=u&f^t*y%}2lrxl_OrQC<4eX_Z|WRfn>*eN%*mhL`Fx22`8DsE!z?A#dHI+fAu;|V>l6uP)*-Hr0m zvFv_ea7Jh9c5d3bdFPQT=kPJG7J&S@_mkO^zI)hc%#b}~a?>nQhpH`Bts!NC?^lC<<+Gk7-# zbEAcuSOIB)tTt1;-D)n1rm>srAl@uNG}9v8QEb#Z-$t|arl>vZ6UakGVdWQ^NGx6D zR;$9&{&5>ax${n>@zssD1F?0D%eGUS%+^QQm0O+3O5pWMP5mz;cUYo-*2Q=5UdD-cKCs1s)oJTEG5si} z4x~_`HF_ZHhIkcu)Ik^5&jFDO`*Q!=U7tnP?T@LKCYzi#Jy9rj5Mxl8GqT0=8Uxm7 z+sWva+xl+#!*+Xa8IGkqoL-g9Z3Aq5D`l6Q`c<~BTkh;-9(~VGvrbU(7H2;LM!v+O=-V=R49EUsv6V5GcYq%GF8P^__LTh^dhK4w{E6-!sTQuw~0 zE`2D?A8M%3_q<$Hflp~JJvWXSunQbvwd)q8NE{C8^{LpeCJHANj1>jTZdL^}x!K}8 zE7i!dN!q(|e?E#sk1al*8c-LvS|&aPetrr_1CoO4!CoH^L^y#zHjsud2~X&Dhjym zJLH(Fhixt!XzR1ekeCD1O|GHkpyzq5uvYspirzDv6-duCYq#wlx1U8Fz|9sxr&u(0 z3wFEP=GMWMRutK`EtSu4eY$nqkEgBr@u^K<$}W-WrcJr8-PO5x>Mup~J*i^O*Tz_7 zElNHL+0t-YZO<^eP!6{Ap&1uPyZb?O(HG0zJ9rdkp=3)e9`pkfV83|HA!c%x7S22!k(qa1xw7vswGX-`M?EcS`{iMA2M+9nVei2kdl zO}X3d)^o6~t*Kia4;Y;<2UnVNb}_W;iNI;DzOrrw&?)*1987d;*jOJ|l@5FT`=?Hd zVF6SfM|SSgnC$QvU(sgJR{qtZ(J5FM6|Zobiz;mwSlH~fEtYL`ue5QLy$|0UjH*5J zDMjF>07##OS31+^V)+EL`0ITrFZ%*PA;#yn0pHxRJ;-fWo%WS2jEX1wa7IVFZh%cX z+UT=$!{9SCZ6>e6_}W7{!>QbdL2ZBQTd-?Aq6hG!-RJTCE_5D7(pw1%f6obIBbK9&q4WrbjpG`VF#-%m`RBmH!y;Yva#@J;G zqhj?j#5Q)z5Nu}?y6wI?_?Ou>R{2xHTXhwSt5uiF!7WTZcthygx^--y>+mh$VzTO8 zvWILVbmr=}v;`fEZ-KEBTc=vAbCErolYAhb&i0p5HXK#h;4T+3gjoOBWNFi0wb%u` z?zY!3_%`wcpJrpt0XuK5&nyEvxD5`H2SmXT)SBH+Wcl)RWNYy#dD=oMUCiAdYHUT1 z1AG0)+BPX|on-5(${4&4xp2a=_gwvP%}DST2v|R*ItTaCPcXop5Y-fdu%{Fc`KM6W{R@== z*$^pC-})(KCQV0tuzwMbnav3F?O1CZ*f|?jhZHS=UBlM*p{%*26*>Ie-3RWuma^|V z3pdYpb}%?E@SEw$&Ho+iT8#{SF8J_Um%KaISA728b`W$V*q?ZSYT94hF5X z0KghVQw*N+095T@hQrOZEM=wGpwb?D^3wCxON`5IgSS{yWCvwqd}Xkuscs);TI(19 z_xm^Y_<85n0oV^!ZG4mRe}@J-LR#xuCcxLTqDW;;_KL9qV=! z+!6t-PyJ(*Z$@5>yb}2saxRjRyzc^HC_Z26S$ONlZr35$!$*Q{EgNUb0qoqhvoHwy zZwtP(l^H0L1NyfQ*wuOeWtOoG<=Czi;Z)OmTw8Q{!PJ+|bg`j2#v6GEyw@z?ig|3u zCVE!~R_l*-3SBA`$CT023Gbm5eb1=?T`29^R)=x$WWdSQt`BgfmrpFaXS>*@b&K0B z9v0#SbcGGb-W*-D z6slP0;&Rib^%yP#Q5pPj|u2U30daOk`jaF-V0kdsGI?C zZJX5b>s_7da)LX~7h?^bW}<(HRKD2e#$ea6*Xs&1ksWNkDWks;38j(USzhgn*mTO| zJ`B3WOnbj_e9ZRv?)lyZnCm>awpD+Fu<1?|x`Q*Z1}8lGHO5)ICQ2vY-X?L{OtrNB z-Nv_7HjbQJtEfxKX*X3Z_}v82wa*bo*>dhZa+HFzD)=tewK#EXY{5piNYDp3fp@BQ z#3f&v5O2NK(Q^}B8dB4{Yx!o_sWRy*|r9vfG+zin4l#yGeGcZp|IarC{NK!O{~b?%Oar+zxR z%0#Wh=!-tJQC0WDUPt$ z^BwPF0`yvN^iyQ{M6S?N>DejvIT&Kn(oSD`Fo(y+Lgsx0&~@@v8yhP70`lnkc6Sr}K#4;9W{v@q~Og<%id|hQ_#ieN+CCus6N& zff#<3P2@2Ma7%rn2i{*5PS=P8l>I6NTz`u2sp-XS^eEzE>o)jvIEdw9UpzS+F)Z9? z`}ooIJpZcT(X@x}Ihvu5-~NO8jzL!B-dj{VIPC4O=*8%2e~k*#(0bUIzhSlg)E=KE zWje5DpcB#WQpzWGmj!HH^{0|z#On91rBja{Wx(n?w!Rcw7Vyoa;JP3m`4rV@CEeaR zeHRv+T?73+E5?OQ?ABbAzlhl~Qd->?>l@g4kr~LVk?jy2h4sckY%w~`wUclT*{Kb?9g%ga zaD8nL1iz#06wLfcY^u9wq6qw|0q&C8_A|_KDX7WH9Ta^JGA9x7(&28Ofa^=+J;}wj zR>zapOg!H8ct80;NcM-^u$k56C}j#1MeKIEgtsbJcWo_IwD|ef2BjepQ6BD#G(-z_ zMdUo6O+>ePWPF|s`3mXrqshg?kcYZHA2rx{x{fv_Khr29`FVVe;8me^$e&J|zIae4 z=~+rAo;t?HW|Y42!+7ZR*h@`pCeMixjwP|vz^KJJ&dlW_N~GWNGv_Ku@j2`M?dp88@Vq%d19369IGphi}1ZR z;K!)vYwQGqdD|fAa%>ym`nS%}r0Bd%z&56So~NW|3z*$6mM1X2#)qK~3;Fad=zJ^c!vAip1&1{$d@)U4EY>9TnMHP(<$ZXgW4j+2 z+xFeIM|5OKUAA|sArIufuL87vG_hU#o*?)AH4{64#PYo!T|fj3s&R>AP@igqA^OeifZ@e!?bi1_S7oL=NwVz7y1=qWgv|DU|ntZEDQO6h` zTSefs|0Sg(J`6mII9#2o4?9eqFGh6Uw;fXA#MU=i8F154zaz#AqU!xCkz8MJP)V6$ zm(gQ|QJ^4DgLGto)~gQq(etU1NW`~-FUHj1u+`^ckN0t;>Z*LfW4=mNMY%@71@bo@ zw2n6WBWZ^x*ub9b;pv=D(XZlbtI*A)eUl#L74xXK)&Edl|!>RDA}7a%2s1dL4T{UK@?ez1+Kwm#v#etn!1s9+w)Y1Qopd*6THpEiaJPAbK3y`I~W>C>{ zxV7lomwINCE2vs)CK&HgwJitm`z}H?1|P}s0seX!Mbh?3d=O~$dn>c9@N69j$oG&f zDLxw%;0~VWZQFj71M&Q(4POCnsbAR=zfSpEw82%Ig8+1E7D|mS4k3L`fcR^*1FmUE z9H;qWsYzFu!TAjzuXF`ylnTV9mEWOBoapSX=?C_YAingt!PLni^v+S#;i_vx3@i9L zhVJbRI2Q_VO6^-KQ*srsJ+lOAvl4LVs!vSyiQ!tVu~ok+mB+sP(xbg~j$ zSzi^$B!##1j0F48&g&BT)*@BW_qM|tdwcMRUW;@M+}_#VZclDWXPQ7_7y5rj(Jw>g z`tjkrG52IXY)l71Y`n#PXw2T%hK*K3ns>s)(UW|31Je=BOH-YJy}c*;vcmV6-%F3# zo6Dv}?O3lt3(CTSQ^=vl^n;GMTfI1kFNTG9ZA4$u(wmIi#;|>B!|}t2o4gBhd_iD% zm22$OZ}r)^I&Ab`&wQ!XbtLlZbJEpS&Y*&OX2jk!9q#teR|oujW6;gd@!^K9Be>XO z?&O`tbOgR_oR0gdn$Zp3MbY*~pOJLNPm>%P{W`rV#*4vLUZY;69wj8FUh_gzxl$n6 zNfRL9tXG8OFJw>cyYWDKji0(ldoP;OIuYvg_n;;fJGj15>re!L94-ggw@FZS(S%sI}q@vBRT2cfOSgpegn5l^uM-`P#NrE zU3@6}Bn|%?YK-Xj4Ee01$IrqMU#-5cR42Y98#)lW8n1On1>f>WXwD`wUX@KcLj4Iz z{W?-5p##t-#O6;LGzaAHRL*OG*K5Zny~v>(y(*Dva6&116w2)lPQD&;G$j3l_ z32j*rs}`tBDRF05l)gr}BC-Oab*y(FGm#UJ6FJ=9Mm|n+(+IGGRK3&& zB%1U|ipA%qF`KLU%EsL?y7}uj?mbrxO6gx0%7_c6DLc(-8I)saKS!WqFVSOvO}zCr;iKyG)W-Wv`s}E^ zT;lk?c51qjGkCsdE2ul^?5h5P+8p`w1l;>q?*ZvcQcEUqebdX(RaV(owL@d?D8|){ zD!XwzBfx0=(TtcU-#;`+V3$Ph@YtlNz8~V19)e9GB#mC{4Dg;-5s!B%Ma*W}wJ~rT z1O`v)eS958ufw>#j#k*ZDfm_&gfEGZ)|&B!FSK5EJ6~U=!^S=m^(?3g*-blrWMllF zue0Fa7qO|^q*I`G-Uxl{MSJgZOkdna2j3Y;PcrRp4$${D=JhUa+SeI~U-XRHgyLVm z&eL>q0N<9{`#Da??X@SiuUmX^#&j5a*VTq>Y-d*ai4cC;>aEU~ioOm5xTFLMSM;9o zCyzv=aoKvz+M?xR+`GDIY zu%XoWt^nfL#d6QveBeVf%-?Y14%OjsKN9G@SOxcY#FyS0;XcVRNcuEdh;JnHbjW+# z>jnqz7^m|^)y3AWL-@Law71ana1zLUy)gf4Aa!Gs9X`C*STW8)#1-@3mo{Ig(4Fo& z3*e+~^(ioX2M2sz>WRsFRCIAo>%^l^ak!~xjEoC~5y0|v$0iSodKEU}NG(PF# z22~Hlt<{24I|Vv+zTGP@p}2o>o*YZvM$c5@9eV~ zy3PvFF22SNjD{QS#%}rVHl|-?k6)>JK7|p$)lvTyqjxp!4;=b|{nf{VUQ0S+Df{WU z&reL(Ghr12SG2jWY50yJZThPSr>EH$PYRC~FL&6Y^1aXF0?Z zpnDn$t&;1xcJOdDQF*^F=OO%>M|UB*9T5HZ(a#`{AZ?`$A=1-oJzUJazVMxbo?=H? ztgYbs#zSXcjQCRN7vKY+)9b8#O97uZx()+4?~ezp?_xbbk*vPRjVV@#)m|2nwAdV* zI}yDR5q!!W^VwP(0r=7}wgVqPIvdkw8S3{0e3k|ajJw33V-|}A!21K-MyR|B8k}5rK3NHSGmqj>&AB;71o%^~L7<-e z-_Ed){i{3C2S3jmi?!7@f(T7PmkxR0R#e21^uaoT!FOGR^Kq9GtX?PSNiHs>4#^@t zM3airU7?Q;=&u=EO_t*gV@UAJo!UhCqARwt?(?8vP0tL>oBf6;0S6*a#RO&Dqi z)x*4K@{t4#zURZH=->-&qiVsBf&|0{k7@z$zb6WjoMz0-N6ou2ggbp)q)_ zFB#66^BDDCA)iD(jA%zY7fDS$r#1}ru&*b%G3M5L2qzUer;&e6nt4mxRK?}7+O5iF zDD4EQSxH~o&kYFBem-D}x}K#2a4!+y|Ee2bZXI6lsSW*KbGX2tfyB}-ReTsYpVE#GU37a> zioJ`0=y_hUNoD0}#&BYC`J`E}w6VbtEGLxE^nP%%$_@_uXCU84^Z?A4&PQ2!v1d5J zKHwukw}`>CmBaaHz*o-;`YAr)($^z`DUoA#kYKW*G|iF1+Zu)#o|ufIRGQVAlLR6> zZ&&g@S?QVnPoS%WK)>#!i&E*ZO5*?kmRFaU%9YBAwldsXyFTE0Fls^yeK|nUwsxHm z>kWRgF1TY{Ic@5oFXeE!Sol8Y(!o}quEsiu@5clF zpBJ-h+J?_d1Add|TzoOWsnc&LE$p)~I*jZk6aO^&k;+3oL*Li8{^0*>1A5ZFeHDp`@-gH&G`(e9e?YH`U>CZQ$I}aR|@#Rf; zU0e9C_xV6~s*CMs9e<$>`usNh!he6DpI0{Fhts~^N;?u_L#q!TOSJ!BC`McF za`n9QB(Mwe)p=*7$JWKAa$)xt=uU9$Q|cK$Qt0}MNg1=$03!Wf96!-pMV7BwpbbW(~VC)J?kX_$*TSgNp?HkwDw!0ewe}&!mOvfIl1K zDcT@h6^Sm$DZqgO_P!K-s1=~{sv-ZO&%qScT|nHWb<5sPJIYXB9av8_WY^Ve2}9}* zRp!P}Uj%S3f=(}^$~Ev>;pR)aIEy{+NImDi)JHx|bT`wFb;={^uYub;(C1(IEheBOMLtdx$T1D@#niv3?ph z+FrqgnU*pZ4TOR^$}TDT?M+)C-`ZnyR{(3PpXJ&OqfS8U z*g;ukP1;>;)pLrv{V&Z%Q(r1TQ0ry2fsR!m@Uu)1w7({R@u`bn2aU)20ItsX8HL=9 zty?dS5Y%-I_hrPrChS6knZArrEZ_>E`ZfkQG)Dvlu2tgiuH!5a_^RTfO}C7>>6sW* z9fb}kNyau zyecJJVLuAT!c{zh_FK`f9B4~bKTM2S&qq>;>)-<8dOI<$l*$K(-Vpe9D&E2U2Vc>} zW`P(Tny1ZyXI|e7t_v*c5Wlym_zQJ*l;a6RX%#4guZ=kFZgJ|SdVwj7NbY+W*O@*@ zjgN8p9}N!p&!yT}xajs}d+ujpD~pEgJC(=@K$|Zl-3R4-jKf=vZ_3M>awONc)H>Hd z9?YoiESGy?tfivQ-$Jz0WPM(&!r6lr?WVbWoyA_Jg~8Etm$CHa*lvuZrZ@OFj4nn} zfq9#0ABCKLc$auKjSb%C#Ky>J+dSsa!MauL58K7;J8gjU-@*QjXoYy_uwU?i`7TnG zo+=C?1xP}lvnbBL0Y|MYFp7kh)kKVXSlE-YNFrc}AMYXWRaBm8FwuKj;yM%ADB`l6 zCY)S_#L`_ko*-J-BGV4rxfnMbR-0Wc<{k`gm^p#H#}3Yv+l&cL@4xUfzR2}>W3-YL zoUhpCwN9twJ}09!BAvU;mk%ONe8i40!RJc3<7F;zbM3P5T$g1}4rMtQUGVHdgvR(j zJ>sWyM2_Gpn+CD7tX>(#^ab2Az^;9!-@ZC~9fz@R;%HmM-3#^Tes}iVW2yqt;nstB z65GCfFvjN(UvB)KkOr$7WSl-<>TSxnVEYH4>v={;lcgKM@q}h?AC;4ebfkx*qzc$; z2kcAo`Rj|LhNOdx6JJ->@#nMg=oaWq^?Mq6R8?cvV}PQ{rb+vt{nd@t7bm*;>+;3y z;N8{dufpa#J{ynjzCm2G#A2OW+xoJzFqpGz3~164PI#A0-C2?*)7(JWI~R6!<9g>B zB5AF0jj^gTDVchyaDYxj%Xtntwkqj9-8Qhwd)4T0l8NP`C?**W7*qsj75WtdF7CG6 z6vZlk0IN<#H;SXRy9Y()3o7MG+-Fy%^ZDzSuc}yL?SqWd=S#7*H7=>Aq1bpt+vvc1 zqJVK@D$I3oGUESIK=<>B~Zp7HT zH?=O1bGyUfw02s}^&P+`uZRoSSE}i=wqa~lKx<#TYIA2fH`X)l<+1jb+E!_ar!AVM z%S5AbFr<1WRP{qVHA<4vSh=$hkk++SF4o4U_rI;$vB0BLdhf+wW0mdhAh#-fDAs^nPqGx!{EQ`a!aah5+}$6=nl% zCdQL}an=n2F7NsnpAVyp`2zD?gR96pD-_LXDD_eL_A%!*+AbnU?b)FP*fGkPp2pfc zpNFdr)k{1icX)JB72~rSqEpUaqQKt9s<$OR*=yp}OfKvukfh|Lv6PUcd=@O^OE0o* zV9`a3V0|xPCCxTRiCb(8bhPps!i0dmt`~im1Oe(E_0ERNmxE3{qjYXg%#kH!;^s`B zLr1r_Q#aLTm_j61EEjgW`y2AA+u*-?xTs zPG)X@?9&?^?e|l@!PF!9tWp~Rx_hvG>H2VA^tFu=2^H|Z^h)7qNWL($NWMq8Sk-U* zq1(d36h+fM3V9J!x$r7CHk$Q8<0-**KrTva*`z!u^n_r5M-{ER{#=uBtFr%hjz&^23~bgbRK0KuPa%t)3A z{L{YR-C)5y8*z_jKGR&?3a+nV)CoHEP9vv(r@4K>c)b8Y=V%CXVm z`6y&d*RF-S&byZ)7j@-2@>#@l8+mf-#<&^=5-l{+-J5RLUx2io9)a-9#CTSWn3y_u zDh}pU?1KL{(!sV{C7weRl$Dl_c>wn+3u_lO$dw6$mmxRXhI2_-r{&!%2dE1G>zh8% zP%RYWpk3c&F-bnZAH!F+L7;P?K1bzERRmt6Idk-D$x86(e+8Zz;F}I=t#123)}VC3 zq0U!vh3wEjf~-+xU$g^WFhW)|6$XIEs?XzlvAqq7}4&7ES}Wi z00{d-5MSCcVA4@zpn06C&y(Ut*hKo0MD`wBIQFpZ3__W%RTyR6@!0w zz~~xn7$w>@d#sD*y%AkNUxWB|V${h=el-*O6GTtCHPN=fgvXB0JE^;=sn3Fs@$=1I ztNo(|C|-CV-rQ-e-Ve0bMUp1mvObs-;z|fM3DR%=q#ztnAf}%?uv%5Pmk;n~?Tm2j zfJEoHDg%VT_j%1fRT>5W@a={8(g^{REH%XE`pC0LS_BhI=$ha~ZMgCEwX55qEDg)~SfEf05;^buA+XQ%}{=JPGxiSH|PfJtQMCdUQ!94U8ns#kFD;28ec2geoAG?Q$AZ-_4Vxz zCtRIXV4hA$wR*{MMkT=4XhUVVH+}Pk@!MP;gNN*3A7NMb1%nIa5nDCsXw&XjE+G7a zn5$AKV4ohY`y+hOhm<}(>EH|P(6x_PAzwZ{{zDr!`cTiuB^`WwBcXIt$j;Vd>^;&s zq?g+^jmi$OuUhL{BR(Qaw|t$TEql9|vc9;EyONFV&@Puii52X>Vsp6VL>ldInk`RB zNk35EbiW(Rldhs$*S-BBOmWxxhSAvf-mjr zQ^s^~9ZLIN5lqT9>zK1`^c+roKPbYdrp+tb)0^plom#s zNjW^ZSWny?RSh03n2x2`53JH1#3%U3D-HVzAfU=SBjX=z)mqi#3^pbA4Tf|nwskO2 zZz_IIIzERFdo5jvr6qItVpyCUgXk0YN!LCxuG(!lx4*Yfbx!E1aLEU_H3g0&-|3~q zVJdKZB*61KgK0Al_)6Y6v9J2E$VJkvE;vmgL|-v(v+uRJ2r|^^87ZXLuYy#iq;qS8 zq}6K|{CNNC2l}M>9dJiQVl_=k8y~PH-AwW>UP{>xea8^tyG@jy{Ku&QV4HIFUb)x_ zo^3pFNOgN^EGf8vkIJJ8cCqI?hBkC#(Gwa5Z!ktqo^+SfL)b3`!G)&UP2AZ5W2m*D zRq5NYK1Gb*6thchgFp28O7t2FyXzvcnWn6l=P^3P7<%$or1q(=I06ej3o$Y4m5^Eq zg2N3-MgAe518icawa#0CKD!hh+&>M)6tV~Ze<2%3|LG7%NRRzy4u@OaIb=I9y&I8J zuRL8;1qxs2R@iaXseakzL+gD9SZEiUTE{eY%H7oF0jmqnKO?DW5!*hej04@>#L^pb z_*%zCB0IlLXZX1~;>&H)Kd>&|AaEP4`oD8y#CB`T-Yx#k@X_!_B={PQYe@Z%#3Jvm*Vxz;(u}m2K+imZaNu*bt{aLe$8;i9)QY)E;4Ud zAtUL!C+Th{b*$jKIpjZ;qi;9@voA)2i@Cx1?of)aE2IVp&*wvf(LjG>$UmH$G~kVy z)_TJM!pi^O1jhHKV)SdGq5cnCPw>wVjauDc;H$a|3%RV)YXSI)$U{}Yn(awTIoxr< z*A0%p*z+SjMBK%~|HI`Q$vOcqY6aa>Y#KC#p^32`Uqe*r`sD?6`-*Mob6(rk(smU%$|u=)=#oy1*bU=Nk~P$NTU;?67sjsi*5bDHIpL@zEtT zI7aUoq$f<9oA-=-SK;DJoo0PH)K0}(7lX;oA#+#ZdB4#H&b}SCW7yv36Tosd$drB9 zxmL%Z*q_#loqm=!1L)-5oePW>A@!u#Km&ffYY?03=;1`s^O-JmcE49p@g4)Pb01bZ8)M2otZ8%ddji<(QwzMdO{4X~zL@3;owIR@ zYN+!Cz$y6fKtgM7dN!6rS5yPMKPdp^!dX82Sl7}Bl*hWLT@#`&5aoh*?JbaZmSIJ$ z=h+l3?qiG&I5UnZcY4tSwJDu=c=o)^4xEvR_rY^HeAhoW_=rbYH`R8Q&p3nmE2mym z`KgDVMY$Y>O-8}X5%S3nt*6;@EPj3J{5e*ATpZ>Iu;EVYoEw}!p_qUrpN7QY(3zoG}3yF6YsImj|z|E(ibsE%`}AK~!x2x;@QVDj%26XBO!gJfsoe=l(78 zlP9mdptP_>F&4Tw3n0E?*m2u58v!=_gVx4ZarQLp;6ysqInNPU9G+?+8qrTOodETeF#dj4U&K zHM+1wAeCRp{F&vjk7o*(hUl%t8* zG`6cET9;*HeabIE`Z4ZWuf8X-Wqs2Tn{gVCz<2~S0{mz{f!GTJs5VNvZ4#%R3Jomb zPoGoX0?|8*RsTE&NOC$IC z$oa@jLBPvC@xIuleZF z?~;flhQ-m=JTNS&nlidv6ivD59A{sGKykVlcWlRlzx0`gvD;q(#d zMPk1dqBSmc(uaB(2cscaeOfv-1>Z9rOtfP!(`E$Nm1w{at8r>{fmu#5cee^ zhq|v-eTLzu$ZEOq3yx^7Pb8>r{DNk8_79q0v~9)7H_Z0>65UsL2{og=`(2kdQ{)j1$^y` zq$V8#-#dX^yzlG@ZmgJoBfy4!7NRpuPSOu>v6RsOr++?wU=I0+U{5BF+#lDM zYQ(-n$~ZQ~5SOkRQq#;Fe~{)}>3Y9Wnd5Ja9q|!hhtQ|~%q45;PWRE2Zb7yTazQHT z2;*iETk^M|!0JGKS7v{_->*s;=M)UFtdSYd9x1%Sbh&f(Ax-R$({vqy?hf%}#t!#S zuv*O;O<)#8PS4;CK{eSb9{rP~8BwR6Mraho>&5ADry-M55OVon0 zI|gJ)DeH;?#+*rP9e}+5F{FiVjwyyc0&LtB5%2e7(fiWXC@Uu$!Dt0--K2@dpCfv# z+?NFRlE^oZCI^}WQiH>f4vIPH-KpF;I0E=%Mi8f@a>J=f=$y1~D)$&S1xJ8AK?jP| zbQQqpnj6{|LT*SUba01LZ}j-L&L+U8mh|hXRGst?Mk}TG1-E6UgQ_(qDQn>80HfVHCh4vRBDI4DQS$8#WOQR5`A;?eKfhLyU z6=s}lf$Q6ee1i3LGIuhn`XypaeafW$BkAhSjs}~JkkozaV%v6H9`FdTq5g!VrVq!$ zgJd-%XYyAI;RgB!b1eQ)8!_rd#GG42;B#IZ;HN8FN z5|X`AiNM`}MCWN@zJ}RG+$Uu8Q!gl1Ciu=utQoJs`lz`}5f7U)CH z+MI7!brZftGRAMqD!%E`&X}Y=t<=G1>zsar*FR>hI%ug~p9-1sDY`bK&E7F!+Ch&= zwYf4|z(_bwNd=!~KG$xk*I{N!utL`nrc_|J0{%%#e0Dxpp z7ijYTP}d{e2N8XP#^m=?z7@HPIE0xpi80ad;c+B3&g%c0=v&fve&Adi{FO+~r#xN- z|9RL<*%TYVwmY?A2H_nQ*wriAP4oS1pecP&QAg;5ZiV#Y-pF(;lBbT%ZE&OsFGOLt*OUS2rP7Ar~U&BNx$69XyAY@UMXN!m3VO??BuW?=|RN3a;`W$-%K8*jtd~ zS1`bu6dX7M81;OR2bLu>2194SSW4Yk_ryr1SX*je^r(6XcK)g{d~%5W*F?I`W07;G=`7t_&m>)2D%40pVvW{MAnM<1ZN3IT-7J@-h7Xxwi8WG1Mm&2bHeRaP;B| z?41?urg?c&m;)Zo#7&ZC=Zs?QK`>JD2uHjM2y@GUyk2B9L}g=zl~az6btNvoIj z1W}XU{Z6@$iytST=kdE(7Wr4dgPYd;Y~UTt7Ej236&eg|^|t8)2^*>I% zrW1+zs#Sf0=jKGN=v5LNdTjkJN63Kp>+j)33as1sxejiLf zx?dt%Dc$cRUq3^Z%I#+r9?s1XT`fI?JdWIrXc1iMLx-RXIJ7u4^nR53w0F>WIycbq z*CVM(t80UkjI^DXN(4^d%}AX99r`99Rz3E-5lKzjd83#7wCi7+q$bT{)J`~A7tsN| zPWqJX7=o3NJ&~O8$n|?72CLbAN2yF~&quTmr=*#q6#KwpVPt-lGCEz1mOgvu7tm|D zd+K0|PU}Ico;VF`972wWaalwMik!4gh);TmR!5#pB-|y&mD7eleP>2*mFFg%m9-Yc zn`qO-{I1AMr0t~t7BLc&{=~5jlDggOaahYcaMM{y@8?JK$S^gX8X6A>mPh`TO4P-j zMIJr7hy3+hPh3CC?2F*hg>$qojp*|MDJeL&)uit@{&b3S2czw}W~yJXuR~6AIGR@f z0Kqd-V`vM9PrXm1TbnxRk+$NPay*RIN{Fr?QqvKkPC}q7m)tYF{O*f*uZBXt`lTn1 z4lT8893dm75VT1BH*tR}j2j@NwV$wsA z)+eHyjQLP)8H{Z+2lMz?z;J1DxXBS;2bnjJ!MH4<&K{WZDl5{p+ zCQ8_HBmUl$5}1S8qm3}&)Roiskf$8}+^XjHHftj$almy(ZUErVY0Lk#<6&@g8<3MO z0~}r4NBfU+2qV~k(5A`ecO%JXbg+8#s;4mji{#8F0S_kq3ysRTAut;T8G0N3jcTP~ z>{R&Gla8F*VMYJhHe-cvY2^Pz+#qQTi+7&t#s`N^1}O(SojCueuAjNej)D3pl9Tk& zs3l^9M7t)54?(7SI)e^G`)bAkT+SjyU8$^KY=@EKUz6`zj-QkIGS@)>FG6n03Bsd3y$JJ0vIRO!3^5j)VIMlDh-v#L_laJL%Vv=#`n> zcd$Rq2to(u`Hr0qBiAMt1nk*+kGB)x_)GKr3S1<^LQ4_JCwpgF$W z*AYghU&(>c$<2`5^x;$o5HE^o@-X)aOm0kd@kd~oH8BWYuQ*(q;ZRRzDsQP$$FvO` z@ytL{ZUam=bqlpz8@^*4_|RNX-4l{de4EDj`_+bDouuzYQqxuaie+SY8Hwj0x%b|O zIo5qV@olxpr+3Lwp^2EFw zC${fJ>LeXVZbACCR?Cfbr0WdCTWXA=)}X91(jChPj=ubN<`|p@zV^EUk{)r6{HGyO$D6)fmeKi3QhED{Bi=7%#B89N5PoJq z;~H}(i~t+qU1p19=G!OG4;@0E^eFt4%)b2v{CqOBQ)?1yqNfU#?j|dHW`w*L+I_dFW zPO5w{aoGK;>z_e5AY&kOD=;#j4Iq{yGh#Q;*VP@Xw(JOGapdcWmR;!gemD~SL`Sx7 z2!D;FBux?>g!KJ!tLX&3UXc=50P{h^Gb%Z8{x%S6NUb@ip}a&ms4=5|OCnE(2Ee2L zuR+C@;)nQh--A<^2G$3B%|LVj)VpI!!Vk?Q3<7pGF{m zMcPVQCD_W<3_P!EE2u8d7i$kvLqq%@({f*?6P?bGw<4EjcB=6rw1%6t$DH_=K_1NP zM=PI4z^ATCa<2NS!aTO8gO(!Yie(1)n~=8FLp;QhuF=yOdaVBwbQ02b(i!$;#CLt$ z#6CXyp*M6-Lzk3g<$tz|=up4nVeI%`` z%C;5}J^|O_#3W8{sywh5D+WaORl6fipE^82K(#wa9M2(!YmnsF!RDspFxawRJ0X40 z zh~q27QU4aGDp&&D4*46ROV!jQ?8mCOL+#jV5>HFiQ&cNWrR$^*gkq_yCx{Q$ z31nu&3q9lVPmIiEEEK4-lcXRHm|+_g2jZMqP7bBs6C*6LZGAU4L4 zj%FJn_T{}UKYxjA&(UrUd3J(ZvFa$lW}@-?@bz1R#a?mMnMcv(^vmJ;yWy&n<6p1M z{}oxSj{N{^GzqI)L0#VJQa2`i+8Q=U+|4Wx|AReL4LzN(dY_? zeL@rI+OKqbl#;YfR>Q9*zOz&JH*`FPZ$#{Eqiy~t|T@33XjAzXe|Xu(A?f*d`mHOXi!*F4#YbPRqB3Hb9#97V z%}8p}kvEzk(zi_?NF{V|yGO~bM(j31w8Xw?(v{#ibw_}~+_LF__Ss%iF_95q!1V&&KNAOD8`OJdLq9*VBXTp+G-*}rCZVutTMW6psgth#KSF-y zRz2gQRiUX#a|Ok1IpyV%ZIFYJI;*xZ%T9{nP-KnJHlyt~nXI~+n|g^(&WEgztb+{g zmI>bnBB^ONd!#X18PS=eU+M12-|2 zFXsici)4?@GRW_cK_-3W?#;;KeQ^2?cU;Ex&UW4>W32aSGG_RBHu4SR_6(n?P<@52 z^YoGYL#akx+&i1}%e945pJmnif5#!Zve$xE{mxU;X*OT!N(5^y#a_q;)GXhR-E){^ zx~Han$BcMRq@Wq>l%z@7SET@_7-osw3Bf7Wzgpq4Z@dA+)J2jPFov(FM64G^KlC6&lgDlR?(ZU=a_l&0dx^Y`bjx{rlc2;_ zw_$@!iuYJVw|>t+u15NiE`n6|+$rhmgrS-%Aq<|*uBk~^lBJVq+k*zb)}`odeqmC0tzl$&h)Ftkn12?a5P_{?S+ZBxemtmxruIsL+H*r`xIrY#~fqSBtJxv4eqDbmly&{aB z=3k-7dJz)*-aRaNivKb_$1LYcY$szk&U;6IvHU~EW@vRjqBokbh8Q*3`B_AB7X3&| zhrNee2t=#W+qhy8$B)CFoEE@(toMH85abF(Z)R2nqV`5-TI_d5+DykomUS?3hC-9V z3m~}%-Jg4Sw#w+(hOYg%J~;x6qn6yKrY}!g4zEP83n2%k2AznjeP;l_4tjb@Rh9IV zOyB;|*A5Oq-hnJQypgQonSeDb-84M}fo?lmO>pX9tH+VCbQq1r+6g-V^t;6jowl4e zU~M;ZMVYbss54%%>c~B|Cs@sE=DhnB>fcdw#RhNENk(oSq{$_t7Ck+$NerpB_<1dI zG@=PvEx6JgN;HA_4w8}{j}na=brt#gl!5GGQlB6Vd}N95<;XuX`r<@aXF+D9&uHLxP^K#+I=VFxH#fs_-Z(F>uNc8mWB>ggVd(&&x6E_XK(5kL zgBryHi{5I@N&B-wwm|0O7!47dI_8fIF~%w3nr;3lfj*TOtUlu~@`*m(Ly$VS+?E;a z=v}dJU8P5$b>H^YWtpA?>4`}j&%|>MEXT7UKAE`zh7C_Wu;@oKPSqojy7ubn)l{Q_ zV4v3f+RKrglVzjTzxwTVf5TNzeSrm&jv?!76z8RIH2Foyl2X)6I-tBB(Icrkw=%Zd zoHNT*JE*9isRx$v6^p%Bgv(lZn3D8%dmAUd6km-o99(q8@{9{WuAJ)GFAImYfu^( zrH-du^m}=IgKl_DbM}EI2bQM4SvUB5^?r=rX=v*?xZaicqU$BIo_Ypao=dI`Gr30r zp87*rWE6s(0x_hn{(PK$^T{dDA3Mai+m(v)0~PJT=I(FyyFox+!+koYbXJE_SVp$| zP`4tJq`t8A7}#?Wee3f^@;1^f86;XV-*iqV!(A)T)TbEZ154U)ryf{RPgrSQ`;6kZ z_!?Z~OjF$5BqV;npT_>v_+5*9dqgkbrd}~=&DAk*978^uiH_}sKho( z%(NR8{LVzjBegCeG3J57*yfsW)RTym^p6zKurc&W-&eT~>D)~u#&ZK#3vGSgBhh6X zHi`$9I#(c_c_KE-KJo63L~H7SWz~_0cC>@gD(2LE_|{SG3j6MYh@Ju+S0he+S7@YC z>P8t@&>VU7{Ql;e4){(SL|}u^b8{QQS-4WYQ^atY*5Y_k6#A8EMhPHbr3x_Q=tg@Mp_M)eJhBamwmz3Oc*0oKY}eXB&b zCQZ^|O^hvDZ7_X;LEpT1zoj2$G3UUt<}d@D0={z&yd$xglKpUdM2jEwqTv=TjIkDq zUekn!c%F}3hS6MknzVso3mHt+zakV6LR5O=^LbuC*TN+Kp5Ozw}w)}-mHO*)0+Tbek>R-ceP z1quJ2XgmRFGd1~S-rj8n65!IoQ@2Y^uduSVE&ftJ>T^;S@mvOG9CemWNqTe}-tk)= zH+-#%{2H;Z0I2pQtx`99qWN*l5fzKADwFuUjUfsP(t@YTbahPtyHPpNj(vz&nsO2mfbuy7sp?vHchE>=)>OPpwDI zvwRI1x&^>)hiLxDB>fNOU6D4|$y}Kj)3W#-KX&#H);g%|{nwA0&|Vm8%xPnLEQRcX z6#EGFT6wxXqW!0C(u(Y_BDZA_?2&=(f$|&s0?M;`8tNT@uUZqM<>i?Kwzl()V)4$r%9# z@6^-*1Q(o#pzT@6w#aXg`;dMoJ*C_WDJ_GbzIujZO_)Bz8IrzM@wYMZP2?;@QwKWX z>#5Nth^A4dULx>wk<|3cP!Azk8POUSP38?cX+xZYd=1$gc>qaCQ|jfp(Ac-BXV9LG zJe4wdU~WV7-xR)%Xg^B50tVVzItiu?Vq-vi>O{1H+B?QIZc7{i267FJW@6GUP||1m z!0G=qYfX;M0Hd5XP8_Pa0>*}V^9XM&9q^7rHc8zWV1JU)pIKo0Jt>?TdJs4A0h-7e z%pEEJ)YL2TKQl44Q3a-_86Ud5)FbjwAS?9%Mnj>+Rr*AQCJc?-K>6>;o%H)j@+p}Z z|Ah&BMPxPP*^aD9eH6c2dlPYKzT+UqKKtwX^jY&ihao9RlcTHSXLbsBn3%pCSQxA~ z(5d$zFF@`=e$8O~hP+XN_YerSOC*uc>`6P98=ucYw=JSc)aSYFQ@pN&kbVq$?5JGt zt2}``-py4uBAu3>>&b^L`mx(}T`lSWElIj^1UFUExdf_x@JRNp#=(xO9&ngnbA{g9)q^>LZ3jV&F<)i_a_;fk1`|H2+V@=XUI9og>3)F$cLWT{@V7JA)Pf>2?1$8e>U;!mb6yF=i(UZ zRyXPQp5R0)e%~I$RXQT5;~{u+j3l$|8w9myrcDo=xSoyjS|oJ?9fjYmdx(atpdU9A z!s>}(oC)qoWDP_%MwX&HoszC7ZbxQ2vIF&(At~t%Z0|p&00)I(TW^l9(=z<2|BVhR z#uvVip}eK3w~&8_@!ccDGf$|&=n3dz%IlhX&0LpK7a`i%_t)g;F(bBBQC^QM*wg4& zs4p)k2JN^bk?6y&1oDH7V3s5PyEE_w6kqdE(b-Frsy@+Vp2ku*9k7+#Vh-Y($hAdh zQ&ZQK!9$klO!*Ko*FNK7udCGOlU=29Lb?Wj!jDWM{{JGF12O`d1$OPG<7WFK2Az;} zuwBd6*DU{z*xpsswzEMOC7_%IWtx!E(%|nS+KKy`@UaY{6@aNptBF_ZYfu^F#IgXQ z)tIU2M;Y|f2FlA8auc!}QhD{0V&or4)6W z7kt0S9`!Wy?DFgEHj6q4AgK@mHS0z^c^ZD~LVm8pN+KXZ?WMUN8 zLrz09*P%--y{Dr&nZ1x!E@9z$C6fF8&nehwqH<^n|1*))^tYh}Iv~dkgx);P*^X}* zP-tE^#JY9r#L{e}uJR zJhYzHFQkvi)I-u+?Ki3EuwnI(09Qb6O%2q-{h4y@TXAgXL2j`4+@gMS7a?m8YiwHc zODD8+SRb#+Inw|yrJdUf2-clS%xRT-feqzxC4PUH7Gi-~v#qfjB_4YB*`kNl1)cR% z7fZI*O?=La9911&4?@f4w`dXw_WJ0(cyf~P$0Ji?-4lT>i0J)-Hj+BOLX$yvZQ)xK zxw1xZH(|4)%h%63{?8f^zitk$88l576Esf+JIo%GLx^7+i_WU01Hz9Rm)#c>Cj`H|=A(E30 z8J#_%StN9NNksE+scE3=dI)Nd)W95^mTEM5-^U$U_)c_uG^zf<B!WiD}cW4NAPRDFlWWD8~g824D?B3H|8VAbLTjp7<8=3 zJ1T)~i`;~0qbtyVAlfh^J1b3WYan+Zb<;O6tUa?|HMnq}kr~)at2jrooj#tG(N8_? z=-WrP;C=h)|7qmS%aOyJr>W+uBKN_QT+K!{2e8ih`rJ_-Ib=&d4sRs~xzpY8qc3P(G z*v5P*17t$bFCZl8v~8OY28zcI+MG(NMfxZu)GuXi_c(nf9h?-vi9QNMJB zo0D4o^aYMTf;^HFfCqavx;D4B9*A6mnA;hhEFMO7?ANxK_Ph+<#>l^soV0t}1A}ut zoj5fo2oF{}#Ltk%a{+M7kKBmlqz|?|E^YDAiPe$ZA9O2oNci0bxeIBU_Jg4Dqhota z;Y&HtUI#AqQz16}+*f9xK85IqSSRh-&k-Y_FVzXkV{zOkBf!A?9I1Oi(V$=A za`vl^FRd@RR!&<;n%MpflD%RS8%>DkB;7_mt6$@i%1aCjAvyn;OMTSAAp2m9&8rYC znQtqd0#U0AH{EfA|JOBxeGTC-}1X^cdnI=P%Cg{QGKyn3CXbsd0t-igS`ZtkV zkbb3`A>Ojdw(o~6F)fE^F=m}K@=pc(F=ic3Mr(Z}w)5$LvPYc&u+s#g7U_kO&Pg18LN?iZpa-6yY_c`(tk>e4a?P@*7!)`MqcCezklr|j17Qo~3$PW;mkw-b{O6GJ# z>pNBsjSX$jM>P4Iv%>=)TAGFD4j5j_7}vK;Jrqc$P(UiT`jUwsBLv5zr6s1Z1<;H(UiF zK2J{wS@C_Tf-2gKz1CUni=2j>jO-LO7&qpP00XMa#F_*|cKTdTRPzCI4F+Lrj=D|1WeYG$q!?xgnx= zSZ+n;_M|J)!x7EpjLefkvmX)DyOBCcYjvj8cW(!Bzi9@(&72MK0DMc<;MBh~U5o$X zHm8Q|$e7Uo=Mv0oy7FrB#;*;)F$ziBuE9pTC(}-kbajb+7@|jbPe&d_^uKVoAJv_J zn3pC#E$-4+%alvjL=^upk`5TN5&gey$={HRkgG;@42i9FV*G!D@%w5L{Dd*txu)&d ztjP$l;ci4ylIAOFKhwwd&I%`IHtENx+R|su`8)$z1z8JO6ImV6+uy4q`p(A^$do)e z#l~HILJmOgL$qW;w_tjWV$qnLuMHcm9!|%G8C&gK zkNAi^x>{>(1~5cp7nvi#wmrqOeQnh(nUuQX)f1ctY?6fXrn!E`_z@ogHu?gH)&r!b z&yRSQ#^EK502_Pf#0{}>Ae8D(P zgArhh?on*j>Vi%@wOZx<*XsOyv}IgV_QV` z?0T*L5abPYc*Zu9BfuDH4UooCW2&*OHAjKnHArgG)kpTc%VgB!(zG7|b`aeMYr#@# z`g6{pK&r{k*t<*edl!;@iJcS2bi!(^kgCs@YRt11&VkSQn3hgNdIC32;}Pf`0d@|3 zSv@uVsh1(Ff%FB4?wwQ8ykm{_dvb!^_%6oK`j?2gn5RpOZs zIRw$uJpCXgDj$U8#+o`-8vCp-4YG~(MDbLOZ$i@V==cQO7&14G06X?+NG$D@J1&sr zu4C9U#|Qi=U+=#yhtr3}&nk$Ptk-^X7Tc=Z79ex(^!fMcztPfQ25=4(=t z7Eq4Ucm%>Dz+SW!awejK!imUwVRX0!y91G&bWWJ9w*}(!GRV*DWr%Cw{(A-g1#yPS zR(Pro+P16nCN1M7jLxzR6UxCa(}g_2xmN|RUOyP8@d)&P1lSQbMN;QgwBO#J8x=OX zjYv&L=I}#Wwcf(`y)T6q@R7zKAcT|D;+1~Z9w|7%ha{u7g)m}0l>_VwQ zjB)iwV0>VyH*P6by4?Ox1yFDNewZJ|K^3@CGiT?OP)JhKfvLbg<8u1BQn#N;Au)zO z2lxdi}F@>fJ}$m&)=U#+_qsr~Olu{{DwP1zq-hPd@x zAv5xDYe89RI>OlH)lGO009>W1^@s7@YFCu00001b5ch_0Itp) z=>Pyg07*naRCodGod>uyMbWl@vLaa|BOqBp$(WD~3W_KyCgEPgVEKPUz{G^Z))| z2Q+8SoG*6((;R}p-;oz(k4*iEF&YN{EX>LxwrSl4aUr1=37l){s?KkLgU-qdKdE{c zv94CzI@`METxEm)kMQd~|D+s;UrQlyQPL``*`Ib;GbhYt%A><7GB@r*^ ze>-K;|2No68tS1$bh+x3_XSz45{E~^eSkFoCK>c3{fU9BjQZ)G9^Fc@ZlI0PuLTG_ zGFD1xWpP_NE3@_B7i6Ifa<|0r9BWMd-|$c1zM-`?0ZcMzFSRM}fd6H6sd|w0l|m6& zAw$-)|U2zww1zRW> zhtfLPy7aVn4|cXhzH^~>6G~v+R$`$1u?$2(XzM9(^bZBwR2lmR8_A(>N9{6hkoT4H zumYOvMeRO)qf5VsY_FX!C~YZ&`Jf=9`EQzwg|^CIL#a)& z7Ob7{SJ+(=bhKr6GqT56St0L>A(@Q7EJIOGFeNMNg-u`EljZz@Up(kz|6cGApYn-t zc|9Vf=NRO%O_0ZdQtemp7V}v3=b3{1>zewr#ne7;IHP8MV7; zt{{+sL=n6&Mwd}Rz0*NTAIm};zpFxBrEo%7VD{|>g|6I9)Rxl`y~ZKD|S+Z`8Y+c5* ze~@xQ{)kwP?2SPd;{^FYiQ#i%`iQdMs00WbLLT^{({J zDvbMoYEB>+$O>t`uqWg~JJ!jr(De%IXLYf>vJKi-Q^Bkw z`rUd_`~M8w4_TbTbY+Xvs2*Z9ax%t+|Gh@kz8d!|AR#{`)I*uE?c3bJzI92U-r-&V z3Mw-7-X%bg1-Z()H1LbbIdW2eZ05{fx{}aVYSghUow}+J{K&4bYU89f0kXxd+=59S zlhqGZFMw|ri0T2%)(hQL$dWgCv2DOmS-H>1SyVV(M!Br&c7L$-!tMfOz1gdxT^6!6 zc%?jB!J(Y7YT|5dRfqOhpsDJd-eqpleor<5t1O(uh*(uw4>oZr17rgSIoSngTMx2< z&4kgGQYMDJ=OYkN0q{B51uA5{NlEH`S9FE$%%ZGUOob|gl}?5HM?pY);64Z0OJpaT zPzL*0meO0>vK||%Eh-JD#O{~d@S1Cb3d zB`NV4N*wQ)X_seL1(LB1Sje`EWraLt+b4_hX!phM!$tX9 zD~O$opnF@JPdL)O~7}2${Ozo6y zA^)y)fvhjG=i0VF4hjP5uMBmS0U%M{i%bteG?)B`gg%JMQAF_gfKB~#pgcvrJ=g|$?GncggRwwDy-hi+e;HFiA_=BybL*v%sbKR2W81sX z5B|n%_^JgBb;@#nhWdYu{Nhj_K5_*@2t-*XBbOkraGwmdk}c@3HlrY3#QL$c zN#Gep5~-6xPh}Gc2}d%m;3_Y{tWI@wdIBmsFxFMI@%gqKMOC()>WQ~@FY45veJwbm z@)U06P3i$V(o6EqwpJ$TVJ=1b2yHy>lztF2uAr>iPbjhfoiZHP$UGwHie0-H^A1$ z)W09Y1zjw!-3DNp020cSGrHb^k+NJ+lCuvOh0T7Uoht)gQC9wZJS_a*Bn(gAnY>7J zAW)s)b!mWc)s2}9j0Wh3(RDfyJgoNrlOA#>*_(d)^B z=(?$5>aWG9tXs!WkDZYBy>}x$veSZnRK7L#5A9$V+I33Lr;w*6=AJH{#iqGqER$Zc zn5{=UN;3`;?;3daJbm4a7oWi`1&IZ3~0soGQ8vrME#-^#bEp zDV--Pe6rYu&9hP%=-%UDATOt2J)0C}pUgT^e{5(wyiIdx>#=8s2{4bvG%H0*-I~q{erKjEA)H! zoTvU|Z)f`Ov0uMWP&5Kqtdl&J**5Cr6{xkbb?o0z12Y*@eo*Sl_yOcv!`zH|aM7O> z0w!TXt2`S7x0HR56*hI&1%T~e;-zFEw)F{ilmmOewQpSqIIQTqD+JDgg@kf8 zL08x&&xCQTfJ?b_@DF97OTLp9Y;0NUnU6sGoLJ6h+o6t`<~(i>?Y>oiK}Z?!JiRgP z*?M*XC)j&-(l@aUc-ay_UHJ4UYZxhUun*z-23Dp5j9dnqnDowMR)MVdX0!Z7R%h!| z+CjZ1x4y0GfZr1WsH_WQeOlH}ZxHKt8>6mYYdeCKgJMCDKPn_*<>ROmcQ-FKa=mDI z%pg-a1a!Bqu$YAHpw7U8RS$oNffADAA=xVCrP(juvZz3t!&2E=~UVI(3xCE(WPF?3a;~Z zN#}bPhx2wXGrddg89}Bp+xAi|9CA`4 zP>|(HYH%D(1r2g5>!M!ZzT9FVyRVS1W#yrcZjC~J zVUVdr*1OrYvd-#&-%teY6>WfVe7?n~s>d-3`|{g=v0iO#^cm2;jaSGe{+;TblaMXd z34ndy0v_Z4ztpwpc~y8_cpvz$a7h*);RaGznO83WmbLmqR?FY|CF_7aI#z@LlxxSj z&_=hQu~YRF=_oH(BiMPRY(!R1^UJZ!>TO+i&_@!oK1{0*^}d(BgV2^jR-58JCY#F( ztK7tMVP6JM*sf_~G_3!#q5U5l+SfDJz*wsC!nQmHdA0%1(+7F5qb%>Mq$}jTFU;eT@D1)4`T;n4h?QkJCkVEhZ7>&yUpl>VXKx{x;Px+uOq{YPXI%TsO4mX&QF z$3~BB!Uf-LDI3YKIYl_0K9+lrS_c3UXO`X;6QI>8xNXM)QEN}sH+GV-6ZT~;b$wzC zwUw93x)^=GPdSR@EShTd{;p%{y=p2DvfspZiFPt(!p@3%2Ym1wEl~>q`1QWq5cMgj zyDJIw8Mxe%0a-FpXs604i@c5XE9}o|>X*RC=4I{s>IB{o&aKKU?TaMOF9k)VkT*Ie z#TaqB!0dIZsJ|<=$+htbFIp_%*qr7v{7-8Q9{tgvwp&at13 zXX~+@*UtF_T_`Pv`+JwMHH_-djM`@eTS7kN5d`WHJtW}}J&K@WGTq^q4 zXREDgPt^mr^#T+1drh?vALHq)eI1+F-ukF6vNm3Q%Ch|X5^IO_#!{2{LV)#g>jltJ zDT5FsrL!{G*>+VO^WMFewJTzM+{)rQHoXf;%HE8ld}5nU+TgAu@Phsjg9b$`kK3|~ zWw|!yN5?*Diz@u4jLhGh{eTX?^3wwaM)K*M!H=u|MG%hsRmt|g>^6`@MgaEy3K*M6 z2Avnn)keNzPdoR|&PDaLu|4wL=bH6u%k^v`VQ4-r0U+I-K~CLUGXHmU<-AR>SBZRc zc%YNkCaz-a63M*62-P7P>AAy^CE=o7%jJ zAeUO1>d4<9T`c$71A9iw5WLSJe{=3$LqT(T;bNj?>TAi4`Xj09O*efeK?|0bg71N^ zF8Fscqb@%eTRPbknAcEURdvZ?%HhPey*3Vu2TmEFyH%hmU657jWrxi_>(~X%Q09El z{Ze`;9B_9JesL+ISQgr-dSejUy{#b!OQo`?1YIn*ZQ0m%s*Xu-DQrrYlT~3$AE*ik zyQ!B!3q#sZ3cjZNvU^LA3owMvy^$LNQ?9*ZoA(onu$Pb8i$-lV7w!EP8L4uyAmGWn zW?AO~YqWEE`D3Cx?LhlBk{eJM zL6u&n*xXph&cODnRX*q!uCgiOXZv8|*8M4c#X5O)l1pCL8T;1Xe=!)T>Xs?tFtT!B z=+wR%bx{n+uJ!3y=Cn6;|duwlUcGz55g)6o$R?ektv3f^8^~_3p?+yH1JE=Y^fJMSPHS8G3^J(0^Mt zDGX1R+&jRyo{<|ko&<0Wa14m$vY0IipVM|l3rc_?? z^72OhPkiDFzWzWM^|p*a0`*(;0-P^hELR(G@*s&^??!$Sz8xNhbf>O&od!O!Qh*-e zU*{DNxIM}_kfQs%tQ|Kh5jwBP69fxHzfnr5vE31euez_97bVN zPLbwp4d&lGJMgX%W=dbgO6pSfjbwmtA3Gphvk2OEwOA*SIyN?5VZWc1*}8|9k*`+h z7O^jAhZ2Nn?_zh62FNOO}|X7#E|FN)<}yUMl)HfPRp)*spD3i-NLu6iLai&&p+ zmtJ!#Tc;d?+Ug{;?YN%uiEV7V4qjv*mhUI04#3+YCJqk8niP5(T)6(CwZ7sI}Y&`{t{>8FM>0%jXugKX- zCz2mUc&IjjjV}3YDvsBxtpo}hxautu3;Hjpk_%F$55Cy-KCBhmaVZ=~7pA?vkh1R? zQ?Qp&pdjm{44_5%Tn{v|>zj18K80Q18O`cLJ>Z45Ez$MfDF`-{->`aHH#VV~yneGj zmGyuW$|?u!ULR~Jw@TR;`s9_hwJ+?F>upSo?A{shu>W^cpWvG;4cM(o14n55RDG8< z3py)H)eE~P1s(0)eNXVG{Bh9P68XBpCX)ZQkZby6cmizTnRO~~DpIgBWw}SC?5(Wu zNj>*D-P*-<6HC>B1yHelXYDBPN_Bwod2{5~raAEKDKB;e{yWdEGkFv+JC&IW3eFEB ztW@)$97fRL*!%2LXou1Q2HD6;FIbR|EN})m#HPG0HY;@998+TOxJ|IfTN&-;iv(2k z>8#zT>LzxrGt{W^7{K)sGjdH;c0yqGo@P=$U;$06fg4_HH`cmIYS$1L*&~en6eHhA z^3cwenEe9oyWWv+AnO}sDy@84>mezdM3BXarsT-}Qpm4!FuoS#*zIF54heFV$e(W8 z!_<@aJ;MM7UnL*v#S~(%Y2^1HUsOUP>swLLR374WQ4W94P@To9!Gw;k7V4DSntIdf zjfKO>O&urFo`Km)dx6L%I3=0-TSsnf=9xO(ADC-J_Mc*K2Br;=my4R_nL(I@jxex` z!r_w$2j_CaE^HvGJsQ|hIsaMR3?BhD`8$gZ-&dr%g+V!8+-E$ZUotU18pWyG{4<7A zuREkVGArvJ0S3!n-i1N_SijX&3#FC}rD)&S9;1=&FyQx=cczjlWPhSO6n+)_TzG%@ zWAKG=6={XjETu+(k?Xx*m>9w2IXz+56UEpFJKtfz)J_o7X>shPZ2%X7wK6M3u?zV*gp=8&~f`pcUA)DF&$RIMWR2=)G}g)t>Zzkm7MB z@3X7&#dalQ-?Un5X9VAo>~<_{ zFQHsF;Mx+o{behDD*`jM(KpS2J;Uh2sn&>ERj)8!E1G&-eJ~bGYnu({QkRJlMBi9X z(fjJgvCegUJUg&{Z1Ggj*xCzY*Us}#$)nir>@Ifp(L(QS=@i~rWl{12&9=z^l>D3) z^1n32#OFgMv7sllzoO@ias`#6K~zu(kb{X(rj^&OhzhI?4V;%k{_kzs*b8u{9 z+nAN#YM?&!kHlhkS|_>p%h&FX^V^Izkqs%|0UU&(=W@vNQ2wen%=V4i1ji@JM@ z8)9MC_vTCCcNgUzaPRa&sTV`u1*hodfaR4q9cUdryOGIla8uWn`trjDHF%-Ac)&!k zZ4jyq@+Kv2I}VGHiU+1PaEd;hvX5mr_LexO01`4yXlib#lCbN2iOOIsRO!^UfeD_g zZq+0%K(|C-i^cwtK6fV)yOwP*{$Oy9DHR=53~pRqvjg~65K$uAv;yhMiDaG=CDhlf z69>ty`z=N@N7dYM^g5CRCT@j-y-mZZ?ypB)G2Aubs*jJ`(hLM52qQNhZD9G$}Qz;)Nmgh^X-sjVbJpSR?rR4bR z4aaw*=dMzmKWda z7xwY%G!~+)d;SA*JPs?poXUVxLV)Yjt$V^GDZ;1k!a8YGQ)uH;AIY7IjS;7X?)02K zwr|n~_iq+E)T=OpU8XEw!mYw`^?)A)Uk4xI8W{z4dO%o`QB_uPy0df~@=D*}jN})t z&e#~#2c{N~9cOJS2cU)lcvl(B3#gxH+Np=5eW=)e3BChCPaWAZ3Tm*SpFE9D9L#f#M;1l*On1g;XA$$_S!21z!leE63^t#9w=S70Kr5 zF&?tTtz)cj+U^p|i%kr@a2Cj2zJS5d)AeAamavA{eWjOg9XUXHneIJFTNHooi=hn)=tZC&tbuPWDMOc72aJXeU2FpNfsG zox@T{edq5{)|U3=QWRAAz!AIKgK?((myMyrS>I$+#A}^$@b4plS}XUhPcB(chyOPXhJKB@cz!di3+}E-zgX?yn)A`xUma=n z1o~`Pueqvy1AGrWYU(|iPmN0yxO_01vXu;bJNtaJXII!hHNroW_Wp3K2c0?WN*zJ$ z?Qrr_^Hm^V*v|GHZfp21jlX_1?}dL3+jXxr$3|LwzG#hn*NHOvQtV^(vCeDbvsxQJ z4{v00l04lc`r0;ujQ_x)y(u18*BHDPHuY~}Z{jq{8@~mtFZHVwmvVJ0Z<0&lU%EH- zt+WTZYUZ!jlE^Z{smdyqffEK6BcX020?S^|?cB(@q4BVJTmPt@eL2oc(_(lwR*wB& ztWTo;AKA~3;x5Xn^VLS!ecA@7s`s1_P=0Rb*Ss+MEgqb@Rxe{gubL&8^5%s5~4IMyTAxB!MfYv4a~p>yDmx- zr*+?z$0%^XtXvg|P1Q|BZ}zx%JIY=>^!rKipp(G*;9eBV$K2LoG+caE9Yx2S+W5k; z9sXGr4Vzk*5MA#m_TAx;USw7cK%wuQcZ+)1aca7b-;5tw<$TQev+9r7^$znv1Anlo zH>s8{TXisi*P6h&w*!sYv{s*NqPIS^F>a4HIGt9@9flyuN9D*%s*22E?QCO{x`;Ds zw|b`0JjK-8RPD9bs%-%3_%J}Vr}r!Ho^SN0nR?Ue3C7{=ran+DH?Ci~-a7Sm7}+9R z-zrjd%a`;_9jB*to=WB z0%oIf7faOE`=HaWTy<+orxINKc7LrYCImE`3xtegPfFN4gP z^C{{&0_b0-z7|$adWbm;X)Lt>Yn@!KQGlg#wjx3NP(XY zw}EsHT>^dq{5AM$cwV5J=)||-J>W;c?}G!~8VyNh6UToCXUfm#9MIojY(rJcVk>Vl z2JU2V`Z2-m)w&mZelDo`FNPvZuyj%VkP$x$pV~WH;ddTBRnyicM1NJIVI<3gr46N5 zavuXP1MB>(M+l1)tUDgnH6^dpnD|~(*T%d_3|4Ppk&S_DU`(;CB#VLZPQaX4=~Nit zt9;ZS(HZzYb*h^F8^uZ+{lEWr7C4)G%2F<{3c9#7u2BJNkqEEWjH30a5ymyKIMfex z4Tn(J7;RzNV&G?wEPt&VAHUp1ZZDm>Sh`c$57v|3|AmKs^B)YI(=ENEDjAG-F%G*_ z*?W30E;Kl&dv?Rf4Zb~^)rQ3X9R{PxMmKKh|0i2F34nBWdK9cxf$yyAH&Qziu{7|{ zE92nSIM&r|gJIu%Y_&mivB1{_cA#(NY&~6YF3QSDKz4X@J)Gwvp z>UyhAOa)!W1aqskzy>?vUI?2&;d_h1&Zpeag(_Ku2&@jJw#>Qq+tsoSf>TxqU?L%Wpu4( zYw`b%!FaGmib)qRmp8a)CXF&e)=b(nnm(1+BFIulfm%C? z#VhK)d7>tHjn$SU?@lBwQKNq}h5bt$oSwK%ry{&g&es;RX-?Lc`jeuzn*VNs>0nsc zaw$s_+>zMYtWx!1f`WH>0#mcmjR=gZ4bE|moE>9>R~{i8(>^hNXIkH=KGdlmEIoJf z=(@f{rla9yhP?G-ey<;3UYUre0jfOhVbk|3_F~kPgZD<0%Ll9cu>G8|kE>f(`CC2C zyTaL1Gy1FGm~ON<(^ikNI=?Cr>~&WqdJukWm3>N&-~Iw{=tksQ#D0(^{B?9zjqO1A~5J-?wyy)BhoOPAhwP~cX^}SvHXYNtvF1+b$p4TX^kY+ z@gK%!ne;g9#`5bS?xMug!lT7uO%m!&zq^R9B@H8| z#8@px?7LHevDGPUU``49k#EyfKAp+55i}4Hxt+r9w#Zh^?K?|oLV@Vx7KwgKEwQYHG-gkthm9or-t%0E6}Plsw4L?~ojQ7KjHMTVi`p%HG<9 zddd!2lbzt6fEAYxw)>-q{b$=PM}UDpFERM;ta8FuqOZo`kuC1nCKp8sBV`}shBmf+ z|C1p22K{U~;t^oL-w%HrP96ai9-SWD4^S#Kj2i7Q1^xgwf_J9ygADyM;4i=%2ia^n zK_kG1iLW)>4TWur+=XEnZyY&XK0#fdO=TP-zz*?FE7IUBwJ zUT+3>Wj6ITBfv&~7cA0**|Hu6x(#F$(T<+|!%^-|&Cd&i!G`}O{fJ+FOTOBR?LV-M zKN|QDk7Q~siyUUWh^=+JdQ!hOtXFjOA#1H!xdv7rjw6pdC}(L@BM==WLi1axctIJL zDcfOX#Ml&0O$o%|Q|*zw;yY}gCeokL)0YkYV@7dFFHvJ-tM{kut%0qlY}?AfJ=9_k zS=Z|}BR}fdzRtMQkOtUxKy~l&J*Ib}9(VwmvQOdWu%)X@VDEwLk23apA@6wj3|OB- z)iQ;ZU_FX>Hk^C+N*{WjeN4b04Ujf!f?hvhhyXiHgbk2mJ76b4%C?CNh+C4tQ~%Sb z_Ky{e1>s{HEQu?>Mc5?odBWBktW@W))t8=9v{r1NGLkH|tJ}tPIR|sAx)`1vxcfTT z1CKR4jE9AsLAuEqsN|vAvHf5?SlDT9C8kz)Ab_kH1JV9e9CO$7&ham3VCJ*>Yk)VBJLu?jF*tuV+jQv9!jK?N$+>7ww*R~|qdWm=^w#Azf zestKbqProNbYgINqLdGcT_XE?Q+7dytrmkH5ZX;j{N{^dwLXnCjH~OJm_FVFW5(Fh z%V)*t;7BTm56ISHYWjm|e)h*Nbu`b%EIgqYON^vPu*G8DUG`J~Ov} zb8BAmSPcAv<>lFrLr(a^l!GC68O5mbA-3kA`e;@41oxk#&7%j2#_(AnIhVS=9lITD^r>h1*0= z4!<|K_kE+r!@+(#<5Q=qC8JAwcvg4X|_&ah5Z_7kBe;rQA@eRx|cIpj-88B@x3Qe;uC+0z8JXGQi8 z(yqJ^#zuE@@o9Sh+!$aV-vn%yv!4hZNqe+&DnX2|jU0ZRvYQl{%{7-3c57Q(>XrXL zF~-B^$_PUb99@cR&vgxJDk{&fHE~=s5`GA!_v=}QC#ILh&iGu6Y+d*d=!brm664!8 zvGi1W16VJvJr34O^pAvfD}GDCw-)93#Ck@l^m?T@yyv{+xM1c&URvSB)v84(kK!om?o%_OBCEhhEupZJ+Qwq(E8lSPz08J z^YZ;UFcVi*H^&^t*mWfO`Y3VR+@`C90R5x|u2KIBHXnm`gP#ho13wzpk!W-H`S6?J zV`00IXwIcv{&TH*wd{py4kze9+0SAId8)K_)SsWSnMfJQemzP)G__EDF%3I>E3zDe6FZ!C1%N z+JN)&2+KCL^XQ0BUPxM{#c5gx$9{0R2b;s_Dz1%D7t`8NKh$E3y-ot(jS_P22tsn$ zYZckSaP}(-!9FhWdmHT02V;A+G46ZiG-Xp)2G$;N@SLx;&Dk~4)y1@S)Ej;Lx=B8@ zY@=jCQwx+kC&0Z2jyf%@mkWsgBOy7;8*{c*I{X(hSfQ%h?<56-qAZVeN#hzqa2{nb zb1v47`c669k?IJ(a+Hj1eyGdf0AFOmi~60EwXOlMyTtf^Vc6UZR;V84VFrVue5Ges zR}Rh*1~YpaH+FsVJauDrYG;#4)PFu~Ffg}G;7Zi!qBz3Xx`VtT$T@d=m>6n)rzFp= zuDk@As_f?Zq3&C*;Mt8$PC{>ul8>8TY?}-~zl*`tZi8oW+W5yl;Mobe9(-(L+crM+ z?X0dz9p8N|R?ZhY`w(*I`JG&>+B%Zz^uK_Br)vWDR=9Rz#t^)cjJS0buwRsbb1Tbu zfS8;+*R1sp-*>G7Uh-Akkb{j!{WC#6?Ip=<8YNdYnG_)}hs z*ToBVVCXhI&>cZOObOV)##4YCChARO6H(=iF7}^|eAHaJB9>;HOUl_!n~v;s3JEiu zXVpyvpLdo$o2v9SD%JI@ye^)#!(WSw0{ztLhN%a@sLZ}2gzZ+5eP|v{MNhspC$tE> z3;ZWIMNh5DJ96s$1-EQ`g6pmQKtISDH&g=pr2t%%mjnpf_S)dDLEfYU!(RU!(8M=q z8|56Dr{#R4!*Ii3+@h?UDgbjMi(8dXr+NaPVuPFd;ll<3>kS4^)srk{q-(XdCBkqg z&urW}^$53Y*721M4kwjP)s^fQF>OqsZZU8}O+Z@QT6GiHtG=%mP-FzyP7&a7k%?<4>r=` z=SYadeAbD2d5vOCk^jxuwOWgd|H1~N)4>BbzSgp#v@~<)>Mdf7UPOQ`fEn<3k4L+MI1u9k}tl(mp0ur$@0mx!Ks%KT^kMY&Ik`KdkGD zRq6!AZd=&W3Z5TE`WG)Hd3IHD0PNd;->I^1sxK3yB4694eq>X;w)Vv8TLI7(XJY)K zf&6MNF>H@A_J7RT=5%1(Yj9qlvu&d@*kNZmGM2T$ZR$hJJ51bPH1(e-dpdHO>CF9A z$r)Q!8{LXp>k)qMrLRaf^3wtFG~-)Roa4yaMAV(inXnc(x86uLL2$HM z-cscQG;3_Jn$|52^~TSYs^UfX8_6EoZ>_uvV^}@0E;sQmZ-a;bjPKJ9seI*Wt zDf%PA>@$xXFur!W{ivL6(Agw{tWDV!ju+eFQ-5)=i{zc3{!E;B8sZT_S5=bZBjLUs zJLFyEt6#*+f^nv7v~UNUzQxUzNnn7_Q*8V?KAufiI2rt#OpFf&J7jj@(a7$Mh@-PW zpx(pRkb_rZyk&66ly8dt=Z^%H52>)%o~SQB*QFmB!(B~1SAD5bUSR5zSUuk)wZ5ru zVe0w;>}%T{*0(fRr<;1RN*>B_V75GAyjVikFUss`R&{H?SGtA64%R7cH7LdBcH{T9 zL5q44F!VlCN%g#%Spja>n)FS?q0`%rB{f5?wgz}$g0#vDpNq?c@|Ehh5b$3bz9)|} z=kHZXNgrYCSjQ*f_vpHQu^sXImIB23F51M{$Mo}o7}MxfeQm67+XhQ>Tq*i!4iksI z9XJ7?@4zgT!$|6I`dk7`qRJK8XBxO}9p7#Mn5OFS@=9$VT89 zV{k9Cacw>0rXTPM*4EU&k@Ksq18^l+UjooA+B$U{v9lL`rTC8MaXBa)mxC{WHTN~}e++WIBhisWNlgOa z)a9Mf*UKd4%&`~RO;W0~H8GNRJ?MW>Wm6f%7=U%H!Ry@s(7w^gt~2JHRpYy%PJl`J zbq44bQ?FCCuUOW4IGF)m$>@f~GEmK`e4S}e>%sVZ#kQN&@qHxrs~Df~Zn=Hyq4sxk z4bJpb%^q&6nwUGVDkE&{;_7c#+2{0NonsPcbSli@#yS%td1R42Hiy=+i?QQ2820pT zA>(?J>5Vu{zD*=ukiHvUJ8xO7jk9*zA4NVe?H}2?pWdp@qPKzc$Rd!PyQ$+|+a?51 znRBvs)PI|^P3iDiGQ!9;uS{Xokpa3IthX(mF<_6-&H~ab>3(WQ!cC@-_ba`prupsp z)u{TaXVZGB66=$)USuHI27(A{+Xk+UOl_Q;BX)aPTk4H21F*k4^0&=z&^X8na=8Q@ z_L__O8thG%TpnzDr45j&*P186Utcx|^pOw2k#wTTtQ$xdcP zw%62+hhMyAS+C~o68lH^*_{#FCr0*ObCF&gw5k79lXQv`OSL1%g&Z3l;vR}@bIl*3 z>>YVhc%Cc*te(F1fGXrsoYivX*!E2n(stjEwm4CYa8YYbdiBWetpf%|fUSMN8@cv1 z=iXlTi8Boo$E{j-*T^Wae-^BJ{-&gPpVz~4J7REEwSbYT)259>eQOI&Th|#nHJ=Kn z=ss(os^erI#tzI9TOVwHZGv28b#dL;WvhLDSUxsuJ*DhFcl9AmH88WCsvLv_MBfIk zk&|blrIhcp%2cebWW=!-(l%_}x<0<_QUtQ1Yls5doveL@ZQty&^)vO}8l5B#M!G9H z48FrS{3B@`39L7-kk;QEnuC7MnSs1x*FEh`9-jfaDRdIjeYTz@NMwO z$r~I3f7}GW$+NR^W1qb{lMlA`vB7_6e--X~Vs5cJs}sbY12<~}3`R+wKL*c+wPQY5 z8c%*jJKuZYb=5D*z9;gu2iA`icBo29UIWJCR9aJsbraL>BFSMe@O=WjFZ^Y=Z}AcB zaglCepHOF`V5g~xl42herxt@ur4HTkN7s)my*}NC`$rQ7n0#Zdmr@QDV3QDe(Ikv z1D%BL_G+M0KK}^{AGa_{t2e| ztd6kl#eALBhP|-lp+#QWu;ECw9qmUTzZaQZVD|2YdHx#vu(NE?(APCDcNUUNt$e?q z#O*-1KpiPoHaORt`lMIw7}efc)G5Yy1I9iaO(nXS=AM)~vh)a>kB55A@^8j&LsQRI ziL1%Cg<~V)-zAw=TkQ!e**g<_uXIr5v^zFBoDWM=Glf$qBU!98Y=Vxz-C4?w?AWHn zhZ~_L4}WRe>zjJrs-5PjoVnKa)kX$fN3?PnBvFt9sIqa%yb=a-wj6GC+(x{F(MQP)s`>Rjv8*}lhQpB;o~HA{OMv*+8I?me@4 zVP~;N$0mJ$R&30UV%Ouu>RfvyN98Ve7CT6f$n_+no2fgC{q?pwsw~nf5M%3WK&gORY(#ToTiy>nd-1Oa7}d_NC7DeanLE(Vru!&v5~x zt7iKPQLgu(x92~}JhD4Wd6(rGJMyju-GLvO*yi2p$WmlxuXpTtHch41^OKH7bt;pqXvP5E$RA}e%8%SP}yrBYcq-UavXXpkmQdszD;ZsQ|8&8JQCh+e|=ed=zs4D4-S>KspuG>Iuff4|fRyrKj%l>dVb4mR?u`MI11`Z*a=R zOUU%$o;Sdk8hxE=>wjYdxNdmf1vh>R)C^0#YSfc=(!M^D<(jt`*@m1 zcBfajaR!tL0romtJP$q+)}rmEq!-@~h@mY=tee<2Nv~cvaqM*Z`!;M}P@~z1v?HAa z9}MpX_pWs)E!l@_osOLiB4FBD)A}6v!|(}kn;inTlJv!deR4^oe|2fiKex!)w$;V! zSCTj+p(nsc!K=Z$a*KRv($EN%xM^;UPu~&7=mx5h?|{A|!Oh@Y4{QDD{qTK7sk&Hq z0FQ$8+{f|?w3miQNgoINP{yqGlz%j4&%yT>UV_-F4=2J}Z1pN^%WEXhr&126{UEUN z3G~=1XAJEHTchO*A&5%Fq1YJK1()u$9)jlu(zL?6;SGyEmVK%k+gOj|vZXVXSZ~{? z7qhme{&j1Yst+7laMrIz&v#K49};^w;E$RwXr>g;u$GjA$yQ= z4e}khWggfNHt7uDt$;0?(f3qfT|y;XE8K$5W2$_lw;jS~Ajdiw1f$1nvN%&}9A&@pk zD+1t!0YqghkP0VY_cAelSz(@3*bV$=FEs!oM>(CF3(cY%swEEYk4lV5M&U|JIf4Mx*`2EP#vsJeA z${4I-jC4BA65HfT3^vIcO)1Nxm22zlYJWr?&WWyXN`c>^5$5J8yI5v?vgi8P&$hwP zRCY;L*HsKviCm+wmw#hcmIE~5JF)kkwRN3bAHfYYSt*#6FHW=22`a9a@KaqZP$bOtqeO)P+DEfnCR8Y91%DE(U z0iY;#*U>3i{5HV&Ki6Q?nvcT1Z$`LH+-dP4aqR@U(5fWt`W}Pl9E1r6`a;e&rwaf@ z`NEuS8=b{(>Hiyp@%1VUY~Nw*Rn;^=masX-_`E4=+_jRxx+T{6&C*qM;#ddj*XDeT zt>!sek-<>)^Q}NKP8L67=Blhe^(VQ8D9|qz+1J^*{x9+g&AoE5I?)kH7eF3W9$|3Y zGIDk|ptWn8JQ!Lt6X>kAIG$esrmQpVFaTrxD=)yUE%mzwz!HMUC)M08;WnIzC|Vv+ zMeEmz0?5xJpr@z&u+fv`Ky#P&rHmaJ&R-7zDjl;{V&GOa*e5jw!FNUDpUn+B%@&tb zHx>?Omri~~b1&TxF^=}*lp0Nk*CxE~FFmI!11t0p?_z8Ysts-o@qeYk$ZinhR;voG zoxS~NEhl4y|F=wTzcH%5DmH&JcB-z|XHe0=-p=wyP-XKm6)^SGC7fS*Up=ILs|1{$ z)%20Exw}tMvw{EP4Mx{H%NGpxb8Dtlni*eJw<#5-f;?Uy{c@wOT?J=p_-@#v)oO#~ z3_(A|iO~8kMe)GY1Yk^ktK+RQmt#)X1x5-V+;a`~;whV)%=jjEV)SQN8|t6R;nmTB zu^Ma_#nYT~TOHrpHUMh1Rv`QArZz^(5Wx6xfMPr$*iyH@Ec^YEU{YBM(2)J&L8Wib zz+fgfc7^Z8Ie&Dv-!lDW4zH;WyvM*Fg?DP|JFWI4yb>JKvy~LWU5(=KHi;U4RiD`g zBjsapQ~I0?-xH00-@`-X_C0f%)p~G?-DNT^C_Cwy%WZ5r5?vAwtJ(fpH!wbWs1?)C zR{JiqZ(pcoFE&f1kaw@ zde)ThRcWRMT_W2byhZJ@LMOBQ6)zg!026{7B;0`n< z;aSNEvYKbaLhp- zHa_tyCdYWT^OD@|C8oYqu8-IqU~ETz3e4rwiH^>kZaSo@yMPJZQju-1*-0W34wC9O zvVTu_+TEu|r!|SD7q92bp=)s90m}KzD>^!T;6TTx1dSe2&MV`Q?FZxH-8H$7|MAg; zm|md&P!@cemE@<>@hPxw=^y8%gDyo6diD=nIinP>IPVRdHy|i=M`CFrZyQN)1)F41 zPfpUI+cRM+QKM%_-k8l3at($vNXe(e*xFTUrRyXP2FYDeCTJ>NuExYxKjYbtQ$8s( zes4~7nonB&FeOKJq9ad=8TFIQ$Y)_e!291`jE9|Eg9B$@j!KR?!qi|PUeK{0Si*?i`3c+G9o&~BY$aOI zvHyl+-|B;fsTi}e#0WTp{<1PuJ9geqm^uv!!d=wl;Gdhyds1bSa)CSS z_@pihg_)cJ=fe4+VFG6SlktjJshHiqkUmVO=0#tAq45jj*L(eRe$C#|B5B?QwlDxs zJ<1q3!g=v#$YbtEYP_mS*WT^g{^6~5oA1woYFFbRf4(B>J zlXa<$iEOV_pB&rV&azj^CxtyLn*k%h##}Snpm%y{WA~59R?X~l8T9cBV{3Z&v+@}- z0&G-09#|xoF8U4Nn6jri;o+e9nay(8v$}b31lZ^+!)L>Ko-@`ZpYz~w&UR^%M}Qq% zuc>r$hXszFfXAmsFbg{nrc%wpg7?U@{S zq1(95&|y2H4=&`d*>!z8=MH$%=}HoG*F)9WUb8k2;}Kxz`E|`b{2uJwPvoVB5c@yW z#Fm-+7O};~ZpIy4$XQQqehW7xy|4H!_*L+_b{v}2@zp}g4dFMz$HHw6Y`U`fEbP8p z&?Ki>+lRpju(KqWO(9QFqyOp%z$;TAj!aK}Dlf;enGpvU^3?5)evEZVpS{+t=tAS% z?TEJ|{08`HxGvp|;XdQcb2iot907Kc=hfY#3cJtO?I!m6f!*H#{{>apVClBvp$3?1 zS7COkCofIJYSOfdF2&$^UB>PLi=6b%(%ay>;5wuU=SH{8UF127F+)axoukPaRy$nf zK_GM;+au*rlWM(q57tL&;(b5lG3t_ho&euak(UlAPabtHUE-6k-g!%YuPEy4pJ^}F zW$an3X&3=E;#1(iL>u>4v{!AL4!(bi@N&%uQD)!p4S8Uvg>$#%zzW@sl(o-**e(x$ zukekF|3fgAb?d~@|6+}|MV!ya5X|UzDT{s{7k4bt*294r-Pf@1KCDVMnl4$Z?v0OY zGbrFL3I7MKOTTFn2hbhi3lrdyZQTTGQf$fl;6#6d=)Y9>4C9*gp+Gt9{e6|C4-_bI{rN~IG>x>$ArG?3Di$A zV<6S3@WfulR6aeJ*Egc=9~(-a5UcyYANBo}P54BI`_8n*4s~K|Prd4@2T^tb1m{GGA_4|YCMSlIIy1uYodAu!%I=W8`ie@JA4VOr+defkNfI0 z`k{z?RtMl5*juKcu~?TJZlau}Nge?<=FxCn(o>68FACzPc^$2ZxE0oAuFlj)!L8?Y zCV5=zN3-xWr8>`qWelH|7~3FvMHd|fOmk|V44`8ub>ir3ZUij7#*m|ldKF`yye(q% z^*z$%;hVW!yuZzk3C8E~tNZOQT_&$VtVXv;ZStBIeHd$PtLx#^Rp1L5*B=ejZ}9c8 zonOLrUnJCa)Gd$R$4F`ol5*=6@Bw>jEa`5E> zsvv#r={X6A+9Le5SW@qZRZ-nJJvTN1QvdEC#J$LMoK-X%0Y+3`7`-WsY(=Si)0Z}h zfc-%gm{JS3^&8Gj@|o9c88^LTm?B+iv?c(n76R&)WyjV5GLGPG1K$jLq*c{hWgse5 z_~%Z1wH8ZO26?y}Fvy#DTQDQn((BsarNnjz*jr|=opkkw`*vv4f5uIZTlLOUOqv+= zo{m(8!dD9(JDSDzEe{x!Hg04J_gnq^^Nf1@XukbeEkSaCf-LThnoWZb9&4_ziGx?FHqraEgu}dnb#4BvbWvv-16EoBZ(e z&fwRz!5ftid1@tgiVkWM6QFfcV1=v|W}7@xKB@ONQg$PkF&MfhwU6&~YojI4t#4IW zO!N@^T$0y(%12=>GK%R`1e;>FNvs$}oBrq%2|5V$=0=F2ob-dzqO2-98-usQtCFv! zWohgIe+kxF3wICv7L7A0oP=P?yO zgy+Lmq&bGIXKL5UeS7$#s!kgHf2scx-mXob@!Q*A#nrYuahp{7d`M*dIGIFSeQ!Lu zj?cFeSQ4Gom&7zT$mcdE&o{M64Xj-pJc;*igE>$5(0NV5X=kcSx|(_2q<5Yi7lJis zQs)a}nDzeY@cSv3?V@ksc#mU$+XenG801!G73<5J#sK#vut%*wzTGsBoIT0qR@SbQ z^YwIK=9Xcs;`z<x~TNBCx(> zm!fGuFq2fBiFVzpHYTvINp%|8v_CB(2hFWr@8ox6`!&DVjD1ai*RgHR}QTo5X7U_?@nv+K!3KPD_@)rVDgTQ6y^c=e=hulftPOEql*ys> zjy!B$u|GL(naR_t?xC?*>|dvipXQ#bp3ohKO{eo-;H?K=0_W%?l#QQ=g?{7viVXNy zgWYUdF#-(Y;_z=WgLwzKO)Fp;tHFF3oICsJ7ViCU?+i%kO(veuICx73a?ra)DLS_$ zN z<-C3uF(wj&j_U{SEfPZ2BRwYlCcN4tb%J~j>1F5tISbXm0TS85u=hCq6XWV5IjjwP z^qg_!Q8x~WzRgS4k*{4BJ7)*>qu?*WZ4VSqdIMrj9=|%5OH&$;oTe zOui}AbqE*iI$tn1gTDuBerFic6~+7DrMk{hc;N1tNp37pB1h4$T9|ZPkH*>@T;eg) zPV|ggL5DCR#+I;m#i5)u>6ZQXr|2I8dwqV(5a~5`C6E7sQ}oBiU}JJ1+1&W2`tpBc zN=-lJh2V8y?I%0I&xN;#H;2c%UWj-b!XD|pw0WQC{c7-)-Y7JbUpk5rBL_{0{XLV* zdFX0gMPc_12S@klW4mh6I1x_=A~DHx2!lCXCW{_{-f zN2hr*Alt!bz{60h7x%o5kjT3;$>?*BwP*6N)#S2w)$$%Mhf&DMV@=qjokkI}3rrH$ zguh3*edje@#GiBw21XAUyvN!)iI4RJHj(314AP4!FNNz;XP3YP)a{EV*gR_dMk+ub za=>)&?#|JSVgnKHRZcFNOPZEfBkJ^%+_rG?mUvhA+>Cx=51MuQUdM*MpX~Hs^LZ0D zk5;EoBe!8-7J=Uc$7@4$CGcZ-jjoaa>;14tr=e*4XFNMk?HH62rOKQS?m5*;fn%H?7Gpi*={!pAm^IqCNF$$LFQ z2h_ebR+HYBc`iRTfc_JJe&{LEJ?x^xbQ=H5QozVQH4JVWUt(&)&!ausV2;y=#6RsM ze?!OveeO+aUHJ^GKMKAxt)wsSa>hgAk-XwE)5d7p@?`^f^AFlM?;SQVFmi9*c6K{g zH&60;nmXoC?Fs6-@w&Dn@0UBdOI*GWMg1umyW7z%(RFU)#-k7WXZrZUapyDgcyv}P zP>;`aS}*l|27bcGlc@+m4&Th=+3M@+aY*og>cluDwjD>CT=sMF`Oi4w4;zErb5|uh zSbS`^ar!FpKj7@TB#Sj^b#m7O50CaAb-n~%13m=yZn2fyNpLrxtN>_bSogI}NtdeM zg|~w{eg7vl$ch1bPZo4m>*QZ(fTMXF-S?*Gm8slDEhCXHq>@2)#;9X=flroz$*$LkRC&cEOfrk>J$1=eq)DQR16JoFdufCmSl(r;=6A;W_&ID`;_7UYq8an*J;`5?>HxAYhkn`;`Ewn6i7$s| z%mId6cTv&~b@sw3_%DOKgSZpk6@S5Qk5+Y{*LLCCDSA%;S|#H+k;WNLDrY(_t;NJS z)roafYtSJb$;bQF%5vYTe%Zg+s31( zwE~?6CpzFgA^Arx9sIP=&Z8?)wEiGdE^Ze(a(j`NcqG4%_KL&A#Q*9Dvu*PR97ppt z1Av!;wZ`Mma2x9E3{P-xlKIqOHiYL(Jbe%-Mb~;hqn4A5=CnL&^#!+4=bXZ)1G#yW z#Zx{(hHq{Rw9aYbCV9zeZ@3Bl3**-Pz*lc;x1o!1dM7+Ri}nbtr%8LjdI{}8I7M2` z`n<413|oTbeb?eDbn_33pYjLSo7d^=zBm;(CnG1Va!!%=U;T1$)25>XE2TP7$TqA> z47(?1{I$Y&>HXI#Eg|Uh9i^H`Q4lWx)*sT z|5Pka9$dYfZBibG%YgfT_6R#M~mB-op<)Q_sxo9}-xw<1C5VI{V zL8y0)QVR$liToP&jZQw7IS@P}Am-aqAMTjE2>JQg=-~4!_+HxkIkpn($=b-*j%DJ{ zdnyL>!*CnY)x{rSJ&|a&W8tU!_7uH;I!Bs>E=whaY{oo>4&z78Uvc{KlVDS~1ZN5O zW(QCE!{&9dhP5M>_aMMYua@}J!{#-1f4a3StclqaX;StNuvUb=65a%E{JDZQog&Vv z@F+<4;y-{jk(HbgN4^p4(No&=rz;*U0rwL%a*r&&A-jf7Wtw<|lKLI}v9{WTg zG1r4V8hbu9H>YbxM{2*lkqlk9UD|eH*ll&)#uo+O)y{u@mFxZSdp+-g5B1@XuiH)&kW~bU)q~!2bik z6W$r_>_-olw|ML!be$a7+m3G=KXP6H_UK7XF#*z5%Np?R@CRUT4hGen&eke{r3VWs z`hL?s$Q~fw-rbb~M0Ru=%mVkR4rW{NJvc65^C@>i6j~#42He%X+(yjapJ#(Lt&`K^ z@VUbA+XVbp_u~#;PfSeBz3c$*2y0HI)g&-}P3b`#u7NLy)n{?2UrAs4o`8_&OVNK9 zj_G=ASBZr)p-rFkq$Kq;@U6%%fz_`RXIJs!Q-_XW++JMAFl9sT3nBj-ocjG70rqQC zesyGEe*n8f61H=YEd%!L30+nMrq=!30(bGmSU685kIQV(^57DL1eHubti9lkVSQGw z$;9nL*l$gs(Tfn*}7HgcAgJ)^_MnDHs9RMzZH-fz<92cY8(EGul>m#LyTov?Lq*Aihty^Cx(U`9eU{QAa1-Jy;j0X*t&`C; zY!~e#Sz_#u#o#%Pkxr0ngLA8+?}@?CesKnz`W@|#|Ic&&O?1T4kN-r+XL(|2OeTs_ zgEA2bGMERF$YF_O&SW5;l8}!?L>|`z9Iu4^FF7nQl7KZq$xCP8^%CYfAm0uz2`^z- za{|*zx^&i$RX>889o9#PR)AxADdYXUSU7B(G5jnTZ*g#R#@4*yg(*G0nl?B(q0@m) zSGBs5?~I72D+=Ax>Vy>2zQj8+7S6Vv5nwRAwJjfWTsjw%gBBB|=-SSMH3TH7D^rOf zYdtC1Fon*|$^9ayPp|GgSOG}9*E=zT`1x^c6bA=oRO+eDim`oHZLsxpGeuwODn^$$ zIvP$YJ>E&|_l|rN;#C|_UCm54rOsf=>AvYsY>44fw}6oR_R)ksJ&xQI zgQWDnk4Fm)n+L$(_rM#~LoX_;n$gtnaCd z*_GYH>B?nfw?%eiuy6f~_VTbM%j=LPn%`c>up^smGB}#RZ%xJT_QkCM`W^NAJyr*o zu75yX;CTlZ@3OVOYu&ZF=u3Cm^do88rAX^JW-58x*XwKN{p4WrAguYmUuD4cBi67q`a#DH9Y1!`@dUoO+?X_U)Y7u(Ngyo(OA_~nI*8qpRCX`)&IV(< zOwV-5%dOm|8Q)1&c?ZU^U%3>XUZA7~n7vZND}J0~$+C3siL({<&twzIh| z=Qs0TM>lQai9EOzqj8BdDw=E?7wIUTq7_rZG0VJz%S^s<@p7MzE0<+5+jF|ET-I@N z@_s9h`FO;Wd~i9-8G}?i~CW14?`2c8^BtZav^*)Kgg~=h2Ra?D#U*h zaWpeM4${?2>NZF+z1=%q# zeG7kec4v}0g|ao_e;ZiG1MtiQ$g`1+>)`SaVtEIb^Aov^OXU6FydUVe@@f@_ZLJB^ z#T@79xN`9x99-$-IBN0UPJkcqTlue}%ZeFuy-)QAcp1+Sn^>iT%_Xo7K0k+lO8or6 z7LZ57SHoS=CIlXeNMvs(nd^oEZs1J(Bb^-H+5o0=(@b8U={(pN0O`+?&NxfF%NSDV z3qef%kFFHy2Q^kAiB(gH6tW%LB!jO$QvW~(w~0#s(`aC_**lp~{$0feg2{a?GTk{ zRf*TaVBpTB%E{3$jr_0tCi|{Ddj}VU+OS=&-8i34f6qyzwz#<5`?TZmMn~SY_+_nBkxqK-z5Be_-g=r`}!x_2IaSP zI=;uY^-uWeK=rtUy!Se{{C+tW7KQacfU4+T41NcH5Z(&zl1L_l92_WoO(zR_?h`~_J5D|%zNlOJ$4DU`%{ zJ3K7u`zODK4}!Oa^@OVyVe5TBOS9|KLge&9I7JsvOF}~ir6Vs%bq1N9){T{j`57md zd+H{FzrGFgO!#0}`(4xT#Nd*pm)FgusU1=6|BC)J?cc&){`z0hy2YBgLcM@|1B zfDWMAxn2aXt`Va=0Z!3trfWn=X6sZ!$h_O7=}NU$T=IUi)1UKd0d#0Y9w$4w^sWlg ztq$)Ae-=I+z6Tx!dAMhF*xivqbv2O&TR5)Iz;2GCYa`Y&hm+yoirHpYQ}&23+7C}HnsK4u!o<_i_iW?rAp`z? z;(aI)QyY9OHqMm^U7rXHty$R$-m+jl6&U9|z1D1mgV1HvuY#{G_&WOV5cNu;AIoCo zE#g}Roa-w=Cdh#Pe4TV&ok;0x^kx5qJShU_Q7Bf1wFqu?I2JAA zA7C9s^bgGbOPMA5pj-AEVf7`ZvHe59IB?VUj5@fea}50ND7IETBK=79k>oj%ym6Bl zdg7w_lyCsjnM`N4Ng(x4JFU)o8#)QS3;6}G4rF(l@=nHQ)K^r5OB3U|2%5!U{diQ` z`g>__3df`$nO?zI37)nI^e8DEAasR#4*Zv*JcqHpo%+zkIO%}&0@9*#> znUqI1PhI@l7Q0>1)IT`i@465YxOycGO8_)l;f`fe8)5qRfJ z@WZ-@5n~WfPnc5l%-A+= z;M`i8-e$u_kA+j@&40w3yLFqO`WGf1wO+IdpvIsLU4+v+;4as|%^e?rmxs0bt_#wJ zf5cq$_BC+!$|Ur`_Q<{`@lsbPog6UzsB<;M*P5R-VXfoQ)2x$VkFG?aN9g~CHSUu} zy2`x+z5%{EliZ?nM_{xya+nXk+sWlkql`|>cRO(<-fo!K_+OvFZlV&-y2IpB`U13e zlgKq}e_n!jP$AwvnV1K35TXx)SgBj1`;fQ3T2#1DDt7-s{-S&41OEcjzbRwQMKT#D|+|P2_*nXPPb_urJgJ$ zQ0j>Y;@uj(xE?~cR^+p_*Ky=~bsKGTXykgJ(~l!Y7j+Ps9FB1E&;;v9h_phc>~QPFoWGT1Yx7_Z??m#7^DzDy6rKA`fuA`5ndFdlWH+3HIjjSK!;>Hsq}X zYL+sQH5qw)CIii4Yenl5njv>_je_yiC#0#-2>efFyr< zssqT@ZwcAhjab__IXr}1kIXwG@aBg#;q1|~Itx}4h(uP04}q`tl0tqCTsbLTGvv%N zqvIRE-lgBI=!Ty476zQ6L#AW2NaW;HGRQ8Uj(pn0B-hjvGp)}V8o)UUm*i2Rqs34R^PXQOQ^C^eEZ3RPDDw=d| zO6TG5oTmMn2zwIO!l*Nv_BgWF+smC0xVftsg>7^O!G1wl6L2vd+eyL=KuEy51^j0N zn6aCZw|;=B_tErH;8=+G-sdlla&_8rFfs zqX$sz+61$WEiv?@^nI{*n~bU!d7tuVlh*J)q`VrO`k__zMrVnS!AlRHMKc6qezGFD zGtp-k4Wa*%gVEV7T~)7$zqpfw#9y!SpDsPQ{oKiWqfzHX+}Ap>HTha=E(E(J;XgY# zLHzbn_r=2}ffe8{z_|(KkY^}Q@$jZqPIjBXnh490?y|Ke3Zyt4S#MA?ZTN1G)I;1K-Ho8Liy^J&T z9dw=E)>q|Kr6-?t;UB=M31H1VwSIb96}vM%NowQiQeBt5ABFdUy>Fy;7IzpR^3yGj z7Bb~Xt9%DG0J6_GPCE^gQxjj}zu(D0;)$DgAt!IX<@-(g-Nu&KZ`YtCNGHYxJWOO!}s=|S(gN%0- zfT~BjQqhmOcV?p0ZHexyW4gL3URQboZypCX?KgH6rz;$C`;f`cR`=~HMhb^OOThQr zfTsQ$$LBTJq_(edo%2f?T^&?504sL~paa~rzRQ;yrx_<>5LbdPfIYew#dckH3{2fF z>GrLPF2-Oz*jweBZ*AxLLXv++3nw>YD!lf%n1d2BzbxJ_}% z@x@M_hd0G)Vo%H~oVdCLNlh-t=DLE`zbY9Sfv@?>8{)tX+CRazlTXQxtdrveW-v5y zb$EjTj7@cGw8WTmej_oPJmP!dsPoep!~?pPP2sU1PyV*@p) z>!8!wirTt)6Z69ja!i@FUSV7}$BDONR9=`GnFg{>zckl$z{pcS=pWY1_dM)Ix|j-l z@3H#jP5U+~dvd%ZFum1A<__-iuuect=xZ3)TJK_GbzLWim%(kW5cb(6S z!K3qf%2IWIt3gW9dnT=;B)J;=vsAK<>{rM;T`&gT-cBrur+wumIc)Fb*V(dj@U>c8 z3nc&T#PY=7MX~&(?N`c&ytaV7&v1JEnYbkgV;fsWWJ$Qm!9{1cXOAtxAp()-BVk?I zHaTPJ35w<;8o#9-QpH!Fvq-%Rh`8CZ_JG-CNe*9BA_>~FO&oAEN3j!p9Q+X6gmmzE z2i*CR2K5EpC%`|4W4aN+ZY}$}BEILwfQj~jZSdzQ9|mRj#K6R&zav}kPfEbhIfSB#a(eO*m}2VoqYT#j@P73ZmG#ionR_&L9o&C z06oyuNR z*fY+C0eK~SB^*d=HgsuQxzl-_#aA0ym%2H+3gvPh#wg^((~sok@I`PN(vEuwyeT~J zh#A@QVUN}rMW5n z=i=J*W7fwR0XEhL8*bo{F5Ys|EXCydY*;T!4okW^${kSOS_U0+g}grDbWT66uIRS_ zb-t*w$xso0^Ol{_x~`Ev>Tc4HVQoh;J3nkv!}zmto`?Vc!nJQBig-KDH{X1}876j@ zzVt(D6?9+za(HLB>r34^VEz;Sd&Jk%zPsT6P>R(KrS_Re!CLAr4t16K7aTfB>!sAd zy8Rr*mEnEhYUS}!@UPi+4^U1FvHdg-e}pSP-H}N8LS$Rfr`r>{S<$#hfQ`8UoO>Sw zwM(BIcfM`o(F67KDz$`vVR0$oFrr@?}=%s*IaIQ?!E6h_kCa8ciwaAbniU(od0v4|MT4IeLnrFL*VeL>D)f_1NyRR zT;LqTe+c!;V)Fd%b*h7XM}J(VKP;aia-Ne+{lwozr9Jidk)Qa|M{F57h5tK`e;sTo z!+hdUm!%h7H+|Lpa#ZD7I(_Zo>Jf4J1yz0Mnsm9QxKH#goYkuPLTobxj(SOaj*5${ zDE>W^qf!?d?Cba+&4L#EJxM+r3!X)CI~ky&22igY@y0|3+t8w)wwle*OByl@7@#iK zpz4Y>lFExX0q#M^8f0*D7SP$*MWBMNHmIcJ@s%ni#o4kaMYA0%tKf%Ey%?Y#wTRIw z=UWjynXO0rQ62E@orq{f2!T<=02QLG^5@X(c_#W*vA4*tQ98aCP^)N`Dx||1pt9$n zYByG?^p94D(-h%1!vHPoinVoN_qv(9!na-wP@mdD;rYM}*Q*2(O>G&VVGW~JQ6qE> zC}XdkuG-3KV`!ABWjgvULpW~Vgx_!#SZ%}VSom7 z+SrJ+;L9c89x`GlW@oJ#;4pxe?Go1R>H#ZWJMD-=ACj+Vk!VnUn(3O?$$zd^0?14C^HGzqp7R$%PTSU|C}PQl-{;3YQTo^{0P9UoZ;cF`bt zUbY&D|8K`IBpk#w7-$&-G~kiEmR*vz-I_TV+QjIQO^vVt(=@E-L^tidF$uVvJi%hS z*#taoguP~rJaWr}AGX0jtr(!C=N(2}^a8j}YzO3G5l~LLw*NO2{1)Z-mL+X%2%0hg z$U0l5JTInPO}F@*lA}?+nLxuR7^ouyG;(WWAMwTycG)`c?f$qdAP>c3 zl}i6zDd20-@tjOFn5(X8-i~JrMPU;R%x(sFIV>A0lXq*>$_5T?{kSL&@)%75Gh8e0 zKDL%Q?1F({Aj1GJre$&0d+c6$=LhIL~*9ONh*iR(~fg@n+Z33gMnb66%6ol p??<)fCQp8n7=xj$AbJ*K{068GS>67Gs9FF3002ovPDHLkV1mH;!3HEtW=#4Cq!^2X+?^QKos)UVz`$hc>Eakt z!T9#JuNSkUK-}xN zy3$3a*2|)|88P+VipiRrX)xc6<96RxzpWB&nN#kbx$`EMZSjKD$?n_zqh^;itetfr zWN!IeF3D`eo~+^-=G!ED-f~r5ICt-lfwd{CT&{wA6>E&5>G2IOY;*5l5pTb-S}TFM za^)|sjC-OL+Zykb^lyj{eK4(mZ|L9Zv-|D8y}JEyHJ^VKf8p}B14q&>?pt}=L2t{O zY@6svMq~5eH(f9OUg;v=cw1hazvNKZ&Ffps?%w+%RmR0S5*~Ld1{x zO!a@Sb57j$=d;SCY4y0Lw)n9(n<#KBhXDzot z=I5_I>)n><-o3DyX`-3GZ+n!>Eg6BmUO`u}u7n-=O=-S1(9a~(3 zr&><*h?ac*L(k>bqqSahJeRC(`P3lia*HkDsohkM=)8xGUpu$(vYalpnz$`y6Z7kT cQklP*^0qEYQEN`^2c{+lPgg&ebxsLQ050{ZK=1wOcnI=%}#*3H>8KM9*aqPX6E7L%J(3DqqxjDyIh)1I!r>2##ok=v}7l#CGTHA-AUZ2t<1v z8rO-v+}4c7JQbN~gol|VNIuw=b1D}-e@RQ>oMbS%(EV#bM`g&M^W|~xEWB>awgN$* ztrp7~An&HTW|%tue;G;XGlyPG7+a2Fq9p1ZZ`EN7Iuq9~k*}WcjsyKn*Hv1-N-}KP z{&!0~GNY%V{O+yHz;S1G2IRvTodg-8}DbRFmoQV>giHK9#iD+hgcta5KLZ#g+h%zO_g`pNx9 qf}XB{F7tQEnNsbyzzpm?xcma8+;JeBVG$bu0000yP$Ou!_AX?FxFZ7cI1)RWAis3cd9o zuol<$)`AuEsG!H5>|GQTv=@a|(1KnRe^F>xt1DHPwN)$I=Lvbo$z+mmCdqtB`sIb$ z%#U~8_n9Y?$z(G5c4){VGcz-15iVJZhGyxRP@2)x5}yT;_^?E>lv&O)$Xv#wnoKd# zOXx{?=%vhZ*j>v%Y@oBego+C^>$kPI9$hL4uQs64xK{<$Xhy_k&hbd146UA<)AGX! zWj%pPYqg5I^)hQ5%Bv8bAbe^nDBQGY7D`&$=gdyT3=EElg}fv5rf223H!FK}H1-)? zY<=cMfANL!y>2=$?nRydNzq;FZICmkms{hgG{TAwve#+=nF_Wj(3r#v9M=H-MX9HZ zmozH&qNC8`e0CDG9TIXOta8xxRv{C-aGs#%9J97G&CIu@VdG`wKQ+sEp?zj%GEL8} z0`-((+6c;d(B7iPpP1t{Y)%Pzq@OE=+%yQjr;+!HnQu$$25sfJd2sYK!YzbJgdY&t zJ8~rt^+VLu@7h*FS%?+aQVVFdBXC^lX_R%S3wb2<<(NPWg+EcSND6(AI(mf|MlX~x zN)UuDV3c8Gj7nyiBW#~${fG+PQyHUDmy`rC3CB37&dEU~_i@v9PI@W&+nucPOwa&ZYI>CA&@+Dpz+X4( zq^?4Ml?h_u`JCybMEV-LnOQ%yyeXj0^ENDuf)j;Y|K52Z#j09+A06162<}=katG%10LB8C|0ng{G#74 zM7Y8Wx1@|00g}29ix>fL-k`Q2Y(aP*;Y|cy%zUW$1K|Y1F)(-;$NB_7`PSNb-eQ~) z&fohdaK6_7P$tQlUAP+?jE|K;*P|}GQMCexk9s(*s(8B#^4tp%NS45e>x#FFKNp>g zxL|YND`tWQV6G~0b*T=y3*d{h99uyH@N!hRmQ|@w`I*2|paGaWr2g&`uwHJgUBz}A zZwg>GXcQ!-F3tqgP~h9ijlG)R?{f6-1WuIzVBU5)mu{lm25wFbBGExlBgbi1L0q@r zheZH>k4~dL4VL*rR6wt6IN%5#dPFok!Ax##Bh%-6nEnUc@ug(t0=r*$oR_zJn9hBR>fzL? zic!qEq0^%L)Q9O$EC#B~O6@?+Fh1qOG;MJA==}_1WwL$N4li4GL*;lU8$J$lOcgHr z)u($D_EK@hW9%MHpOTtwoYf7mkF8`V#fR3$LGPXS^~=g-ZLM4d^v~1 zz`|wb>II6g`~IM%ax&wp@hU=}YfWw~o_6TdEmH z12~uGJHrhK8xcN0sA`@3F>IYh;Fgb{5H8>XZ__j!kP8S%je09((wD5N>_y))g5aHZyE#j#J3zzPyg) z7X*=u+c7sUax-GNJsL(h4)YRe$FwJ-k$uSK=aHj%<9B9{2FYWn%vnT7a_=)mjyOvp zXI8NijS2^#ebic`%gkfoD7fQml$4~1hT>jmeVNkiGF%zh6?2%-PmIw}7)Pmk+m+Dl z621)V!I-^IDk-8ta;vrxN&^~xTnDnF_sS8`AeqaR{8@?D8xFi}@a_ZfVvzk@#%R6+ z??|rxG?LS3e*rhr@GHCr2vse(R}Z({7Wo2VA$v4Gb?itEcQVQCHWIxxoR7|O%)k~B z{a!~$a0W)bel!K+xvT694n2?qG;qwdksf-Jycs?LX4n1TuFV_4l%`ETX`Lh6#_bjKhJtmfAWmtp!;5c8c;GH{9<%c4@Zau=>sL@RjFq7oQC4?l;( z`5IWuhhlD%yZ$j=UjZd62bPv<8-5iezbhuy!ap-WG&!6v;G`AetFa;4i2wLEwg&PW%`kXG>xZ6E#yrvlNQ_ z?u@^+!`HfCW$nRz#lMNgFt74CTuf5 zkmVKvXOc;hSC2MXMGxofVs7Uw3&2MZ_@mCw|7HWa{Ssm#wvk$UW+>-q z7=QYk|2?ee&wrz;x6l`Ta!I)FQtD<{HCm9sm$_W=;tHaKWr%Z;i@WM2AR65dIF2%K n5r-e|T-CxAjIGa*ZiM^?DE2tKw$>7|00000NkvXXu0mjfk@?0^ literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_monitoring.png b/selfdrive/assets/offroad/icon_monitoring.png new file mode 100644 index 0000000000000000000000000000000000000000..05f78811e274a59ea8cd114eeafb16a7294878da GIT binary patch literal 58679 zcmV)9K*hg_P)UY)i%PV_YTq#M2d={pdekbqgYS`1yNDJu0JY>f@1mX z`uU+)K(L_LP(ct2T>(Ks5m1DCsZykK>2Uvd?K_#1omolN%4EtuXYxEbldQb!T_v+~ zW>4D-EYO28Z{EBIdf>(ak89Hj1U--JJr2d#HL`$wVZa|T_$IdtHbqWBqFlxCLw+JB z_sDLxFu{q}?WbfnTsg8ncF^v3AnO#C9OGdjhu*9LRdW6tYLbN`2!JqyCr> ziR}=KZ|xF8ws7H;FA?t}j!*&T9G92+#7o6DX35`VwMEV7o?#4=<1Qn{7KiwLTW;{S zjM|*OiwX6myas36D`fXTwoJ%Ibc~2h34wvx!Qiaz?IE3%F^juw`gj0XzXYM-!-?hK z*g8gNkDGSLfWgGJN{)41yu+WgB)FWTzD2yG4Y1^+rafl2U7WK23!BTd!SRU0bB#6j zH8W;p$y*Rrz8ONcolR(rnXNr$+N5K~1KX1^c2Zz`G-Np4t)q928Hapt)3&#euVwdx zZHN5L9N59IpGOx{^ta*oI2rJ_G92{px>6k6tO@`E2eUSZsmL6qQP&1Ru%nH!$4ndJ z``Z|_S1@DREp#8VxqSK|j6FteABR_N6WAc1T#K>su{Lb35wnZ&WqlY+UO7aF+4hcG zq~7cTbBcvq*-NGzusB1uZI~AqHBBrb5Qaxbmd2V7YsP8o!=%bB?zuh=3lp^O`d9w% zH3JsWdl+L68JT^AXJjpJm+;xMeKT7) z;es>c>Ph-iZXeE;7wuPg?E=7_Ub9KO%Ef>N8{=}vHQXH5lKs%-7O$*CVwCOO(8%nq z25aj{+8S;RmTZ@6M#vG6mS4DHi3ss@Fm{W^=4j8bGf2vA!1lO1#u?M%IS!vp%k9J4 zaU$uWc#GZ`1r7$J!;#d_Lwb? zwJp6ZV_509#X06B9vJwB}mYiuQB@jR{>lEu{g!P_;euutZS4#94C;yOA%qAI2-cy zT@tQu>5Or4Sg9<9lhd(f#x}((`Is0yZP&9qZMG4>e=U2>ee__6PUqRiEW6{U*vAGU z9hw1CBGBM4IBqmNv<-rtK}+ws&d{if@kcqiR|bU@45=5y3_#~hqgQPAW?(^)qo0}x zmEM>`a9}p-*zt$$)EGF@f!-0eF52u2aWsyeIv`u$@I&?-)RRo#yS0_6Z3FEwTOMme z?{-_4+A$p(2dr|Zk3`R4p#KuGRg|Y%aw8jUjeKl7hA28?0Ca4OJLc(5D*w$9Ev9{c_?eS3?15fh~7HBh0+X{gtz%YI187nkACP2qhDVq?lXX7|MjQ^@s zU>X?zqs77gV=&{kdh~GI22-0zjLdT^VutPQ#lViP>f8D@z}Gf5LV5;cIBcvtW-#0~ znhYYg32j3hAt$r-Xj`z}xal#=2l^s9n!G~)zvz1}cX|)HNSTW3yzQW6)NUSI zV1924?RGKlJxr%@Dz=W@F2=_G+ZE$>BIwAs+>49xmF7n^?^v5J*e(>x4F@g)E7ZF9J7TNmw}oc^e5>p<{tr(der@}xGHM#uQJGGrT+7Us=+ ztuyw3HO4i?k3De8j%@7TuRZ4YL__Rdf;KLx?K5hV*_c3kGh2t+z`h}XH$ykMdZupx zv^BEEwpwF0K0~{5qplk$Z0u>-^Z$geBL z7PsZCw0%xBZ5(!QGPawxCFbWGg6#L4TukZ!!L<#?XJoW>RNC*thc%5uwsj+;EhFb{ ztF&R|@reD-lXEh%W8^V?sZSEz*nb3xf&^m)u(JpMe;#>7 zjHHy;H4LxWR=_m{jqDjdpER@0VST*QMvkDbpukb~oHjwF20}?d-8fZ$;`9*grKqD~ zJI~2z+$Xnnd*4P7b0`qoQ4^R?o{F{g>a-jA4+4kQA*Y<6_pjrqtqWf9SASbC)NbUz zhn)cX-=2|6W#qWQ8eLl!3QRjzdygOosn~{%^R~>_CM*?a{50w_atD@gEpZ*F7>Wt( zB-oA{xh;!vg~ok+K6!|X8>_uXfb7AlbnX(Ke)H<4ik*PZo#V*M?tF$ShilKaQ;coFVD>JFLk(lpY<*ZW zUThEJa1LhF<#0ZkRNuvMe88A1WO6@Z#LoD69>ZfW4kML~5uwBBg)r_I^*Ih!2JEX0 zfekP+v$e-e+l-m5k=NN8F53EdYz*4vafU7T>53LhTbW2r-~Id!EY}vi zCrY>thPJM4dyE?||IOJzo5Ux#G1LaGyk*fHtJ?>6d9z!Li}Tl(nYQ7ntPupDLHF}- z-3;q z#s>dKSI`mGqod%Q_{i51+ylq6x`0^i^&$Eim<5q7`fo8-0v_!g7&Akcnnqu@W5J>` z@)O%z*nuJndrT4-@J}&161)Zj-lH_!!0y1|jm+Abapj5maOC%TNDk@-r7cKp|Qt&ZA&NkAI7KelUuyye*z!Y$fY_>FP2U7n|Nz) zX|Z&RWI?QLxF*5%HTB0n@|1vzU?jAx*jci~!Dfn1kgymuyb`Rz7#-SLvh8d+wds(R zUMIP*0bx4}OF?-v7lF)J!Wtp|EE^l4t?@~VMW`{;ik%dSePR|f zd!jI#)vwPsAfY{$2pFKnb4-@N*@jB+MW`_c5aU`dhA!%keU1u%=y<^;v-Y?Iqw^@Rjh<#{_~(DG_L3a4!R}<*~NWp=}H+8BgJZ&Xq>b zwqaz}_Q#{~La>Pqw%eA%UA8>bwsc0#5H>dEaQ!`oH{-URk=a{}??M=oi9P}bJW{}Z zWRr#3ww_kk@Ydn5b>06GhTm-2h0!K3z?7|PT+8d?UA~Y{&^^bD+j=f%i7^cT=&Aj& z+4d3Ga-;9ta)u@PuAW54_QBRSy0)yqmhbYi_XuwiYy+A$V|b+QlN)YsoRb;6y9L&M zZ4>hU7NRv^hD)Ver=WO;&r<iA#qg-r9#~_Bl85`?LFk=cuN2vD>gQKm(^AUS2)E@gdxIiK$nfZ)S+sLSm z@)Oiojar^Rwk|;&eUH|-O{pH)viWV>B)9us!}b7l9wkLnoU!eVoZA|#J!WL~)*g4- zV-M>a9fNWEM(%D6j<%sO8#mT=m8d@k5E9!wuD-SpuKNuir)$Qn?VDYkH8yIx<80q3 zv4e%sV9eIVLT(;ytR&LK#`?wvZ8@wx?!%BC#?~&d4{|&r8E2p%EjKPvIWTYD=iD(( z-{QH})w9M%O*4+pC}`8qvbBx5g!UM+0LOzP7DT z7`t!Ut}f)q8=1k-*2t2#1=;Uyf{+1wjBDFGp*E-M%3OVW+>Al?2+2)9+txPbGXQyc zLx+pE`X{(fVQeAPJ1h*_boET%1sl0!8$7af31Dbh$nG?9$&ng4XYh5mT6+?_@yY)7 zX=L6lh|4onwh?P4=AZJi7zjrNB9$#eF<*QBUn4VHW7qU)TiCKiqPA*}@G)Amz9<}_ z3r4LJ%WiT4jH5}jWRz*^I8!Epn=M;U+xGDNSdiKkakJbxY z#yRHUEY})apTlyTG1=HTg&3F{x1F-a%Lm{r8QTm6LSr8Ok}Eb|0wayuAB_lqIgFT& zC_4!aJ791L;Oe?0b>5=### zSAMkH$8Fo0q;_jZ6Lph<$$JG&pi{ip=3INE=gJcLl^p^cmG`<5FU&pW_?p9hg3Ef9 ziPsxeB|nHrg*fRX2u=xSu@J=XA`Nz4hRp zYh%!6pH_mLyLEf)WVYdV_)IsrsuiHwhGRx=k&K;9)~xM@zNA-(4|-sma;z2Lv0zQ;ZC&l5cRK70l{_UadHz~Ebq;mjr4PwS73=bW&|?KZIG~tVs1hI*)c7*(EBY&=a_G^|4s?(>5r^0biz$ld$ z!Esn41AdK>mh}f?ecB<&)yfO!jQ`Rt!W;b{5Qm?iQ9h>}zB3tuV86=Q4gs^GHJ78N zJ??9}I>LVWG8!Lm4mo_eRp^fmi+&Jnu+=W_+i-mcW<^)lS>JNFZ02yLB#Sp5&0#Mm z2V6GSUE)HqUU8M%oaPgh=;n(7fZ$`9r%qas5Y=dVyIeu_OZ)gnI(+us%*$>GC0LMi}p+nDLHK8eFvF@aj~`@wL`itHpb=R8|?1}zfY9#!{?U+_wxYu25_zEj=QmH z^5k;W>XRc*`En|u!{c@@l=4Eca+L3qIsH#cxm_H1mPL*IMCh0~mm}04Q>=E9&WV8L zL6<7zgK7-KH@oC+Uqa~WIQ_3kI0ys1vFG(1o>5oIRTl?i^eW9@(bxzP#dx6mnvgz? z#W>XC;M_Q5G(;HCn;X(|#{xY019pu^`ta?Q0so?RblLO)9&el}I=0O$Z8%|GnfQDk zAu#2SiMmevbbNAG-}HU>uH^9R7~`9})%XP6@>MEQ9^g(urGKmTySOxFo4pZ)0`Yir z3l5G}^^CD%A6I7wS*({+LijuOq}0^N0!zT>`>lSo*>>!e)7)_2dUC=oQO_L!={urP zmnIQKwL@?`BqJiMxgrLbfQ!iLna;I^~e7%YM>;-V(s`U9jB`?Y%b6 zw0(Fp9@@emI+a~n)#`AD?ByJz%)5Mb{01FeeXTsl#&L4C9beS{${hXCSHWE>LQ4QA zZX`$CVnLFcE}!Wqk+rO3e6_cAU9h?AwvQK>;QNGJJ$9vVLDD`s$Y8g|Ui>FUE*5!s zdwon{g5!MWKGg;<-EzF7n}fStl3}F$O=vQR@;0f1gd+tGUw4P#I0u=3@-YqNoQCoQ z+z~WqRylYKZw&;SV@g&BN=tK!7Nk}a+=n;GU(30GGJJkolYVpDB;#E2VIBEsMKAw- z_{eMnzNN{h>%-fe(l%!!C%@DW4UY4f^mF>n+2Hs&oEwYLE0-D)#EMH2>JwLJJjWOU zZRPH&9KKo{zqQ(pG`SrhHn&;l3l3~VPPip^v@XBt=eCoR&-iF>bMg}xxW8`mn|2*L zwLi_|1m{53J+Cmp*=oWL7mrrP`AQs3_{-U=OSMVpki@bLSLwrpjvvsDI; zS`@K)rg6IQb7NS!EN02K=Mf2~>%((csjN*~QlES{&etY#LiRPbIIJ7P#Q*!CfSO9S zn=DPAOMX*+=C)OS`_KgJU{yECIJ!ByH{~FiR1WMAwLjQy>^XLd z@CnJve#Kk;Lm5Wk^lh{hdCG5mCOr7nefU(l#}0c;lWHTE9_MQ=Zkva*1KBTa47EKt zBfi+h#}tgBH~A&NX;ci=6o7sa$Asx7-R)e{9k04^%H4VuY7DqGsL#=HI7ar3QWt~l z<7bu<`x>8;01XRUHtq3TZIIto8gLr9Y^3tQo$os?mEBa%kX}jdG<-UMRbI|!tNQek zuVgfQ~DiXjM^uvLqba}qN8F}g+yxG(qE zG~#zQVz?kRMts{2Z2zH2nwCCl3C=k1+#BR5X9sZjTrx5cDXhP#_9M0$|Frt- zyYT?`ArE#v7aQz*NGf6<34rXYcp%@zr&C8>aV#LHV~2D>y;*>MY^bg+pZ=H;tHa@~ z;ZW25)k%(qKVY;Od986N@N;b)tNpHVWLgh=msy-{^FCML^pnnOI2@X8whx2PXe^69 zJtL3lm*Y^VJndW#3L4P=hcW7G#m5-XJI~RLbw6WV1Mnp=aE9^n>GA}wos6%Nt&d-# z%VEH`3MX$|2E!Xlf&u10A5J0<1tQT;!T4-~D|7-dYRct>!vFb{Tx_R(t&=`{M)~ov zguvD%8SGWg6uNdjHm>lU+p8;;-=qjK@-{OBexc<-Tk2N{2 zknJ($20QSJ-Va)NEHLC7bm-rycpf5LwdP2b8aO`sT_Tzcx2T8!cJ=MPl*`t!+J{Q@ zo5ESX*v+>{?Lo==ggy}}cowxCu-j6O)^Tw1FxyeLEpf=zp}s_~DGbd2EY&CI`M#}< zD4X)R6<$Q}UNoI}4qEER2x&YI6aZUG)U1z%wXV<~7T~5!)pzs4$X}<6zgX?q~a4=~(5AoS! zCTLq`x6OEyTiElx&gfglE-*XVeg)d^Hae1RfF~*M5}RTStd+S;d&>7pP>nUy2N2Fc!g|ji46%xVbce# z{2S!#`jkn|;d9Ew-;Yy`hJpxv=MLEeC;2TtT^{0UVeAsbxp|5m#JL*u{^QYo6ugy} zmw2!$agG~zRR#%6I|CJ05lI;P_u`J5K2%4)_&p*i{$OlrGv49$T-&Fj?cE{h17iy3 zGxTpF4vca4$1cR_Oe-0ZGsh&z-sTDtoYI%3+veT&?;uEi6`>uAOI-99u`x5cjfAjY zX?;ln{%k9$z5B$#w+~wWJtGi@1uL7iu1@=GO_Us|P`yE}Ox<{6_r3%@?$%V#=id}! zs^!DZDEU-6MlJ6Fq=PHFT(ZhRtHI%n46yA?o7-Z%@)Z#>)>q4<-TVN@OEMdTw(51w zKF%2-N3z)KCBERDM31^0R*EBCDHgaVNU@wxgG`tKB>C}7qS*s81~(FMrZ_BzBN>N< z?D-rX^2+lm9Bz=clmTw?e5RGyi#2$k%|YH_1~7s28sayETu7N@=p2Ju-k%xbAI2s$ z1DIfXsOXFdb$@VMngL9*`6;OXW`( zJUI5&Lk>I00vSNE%^g?4*Dt!0QuHf7Rs;D$4EB1?1sBI*Nao_G&tW;74{P)>en_FW zl#$KoEt28BYhpQHLW;yyHXI(Hu}APYj8^6tW}jzqFs6I5&lUjgs)yhujH_k zAmet3N$|UIACZ{vQF7c8G7Rj41^(?JTvuc8%{-<5i;xd)%+wFzXVe&%9LRe07Tw$v z;)!|Y>=Z~q@W)Rueh`O^W;9okmL)3sC+f_5v3%_#}$&p&MefuP`Psy zt{dNgVBHX3${09Ta1BvE#O2~c*j|shftWt$G{&B9#?6+)X=LCr=RXW(&MkX?sMJ5# zk&vE?E&6p&+lNdxH|7auB<8GQ;89CQ{hTCp*SGZBY|iH53CZBx*DVLV?-#W&Zu6%h z{yJlgo~J+*+rqiCJPy)xlC^&m1UBeo&;1@7U5M#<(&ywbjM(UloN@?=kOrz&1 z;5fbA*7xJAt0Cx5RH79MpgX#=8t^{t5aj(f@XeIu4;={J11@%lfP4;WVo|l};)f@Nsc+RG@Yt?6B{;;B?7vPF~1@|CR!J<&ebT63jIs z4vOC31`fK=^EZy)lHHE{vUfXKm`W4eJ3;vS%0Rl{-|%BYtvdXmTt_E9wi8A29sDH) zsn4}nibxRA_fa9p&%)W@4na0h#5)8yx25D!0e8+Fg7Uh-eCE;LyGS4@@PG71KVaE= zMGZ&cv*~KK^r5N!A=em;ViC;!R&_8cE{D_2+e?D2vAx;lEKXmkV z<8ZCX;LHIMW59hpgv0o+oxsMrAzgQDOfju<71T~fJ*lXtrO}LOy}Mn68MVzC>|g{(lwrs^Eo9m0HzC z=)k>-b|g|CR5;ieUA}f~neI(KG6UeYJ{?XD{d+l%LbfNT)21xoo9Y-Wg(swgv7a=a z2hIVXQD9f%@P$l#LW=kUJnQ)Ew=EC&*yxS{yYFCZU)FZ~G)eR%l=l|_$sxv3Bl?}j zVWY%szpLSC1Ize05@~JwcpyL0$5rSwc2lp!jO7*EBgFY^?Gc5w)EBjmrQ6le3i&J6$VTBL^49!O7SQVugx_sIQJ_us4U=Mv2MpyKM}w;vV?u zgT+1Ayr4U|z!EO{LFDGeT`A1%T)BV8D*NR1eTN84`ZEJ#!6C%#TgfX2^}xpF@G@?P zAP3kdyNz+|ZEFK_jpOMfPQUDWJ{h#5tx$r7M%Niw2=h_diEO7TD}_A>BdM$Sh+cv8eR2JE7a{-|qX>a?5WuH#osm-CxsF+It69d778 z0rdu(qhiw@^t4Z}C|LrJPL|-w499Po?`@Ow8#3?BNSZ*v^Cphp#{q2cu5scry3%8c z9iWr#pwt+zvxPs;tE1ncZk7jkaIpGqE(YYK@>CvV?+2DW{lIZZcM8%~-3tKx2Asi+ zvi&o1wMo_V4KUn^LV7e)SFk6Yff_42`B*tcA2vnK@slitt4$rw@0|8Iel9PNUFySH z@@KQY0kEqD8f&r&5CYWrE0o6^u{u7V`XaYnEt@%g11bA}5@(}yV7ze;x=-iuwPfQq zrh2tV9c8e7cZzwc<-mH?g_k={c{ODYwsD{_EP%9B68C^&t&7hDDGM$1pt{uj~+Q`G_4w_2`7_S5rI1 zmt8|m^b!0Io8WDb^QZ>7ZR&mPj<(&%zmK}h7Z(J#OcJgMTbzBZjPth%UpYH<^FlX- zu1>_EqD@Fc_`f#9o1GT9Tt7Q$Cc@A>(-@hde;+r->;Zdh4Aa8+t6H#;%S3BWy=xpc zlOEC`jPx~y-esCI)WkALfwXBWl(^U!=O^hjkr$0EAJ&aWdZ76(S8?c1+YHRV$Q9dz zLVGx;8^YH~Wt+Bg`$>FFt5cmZ=bAVzmc5+4joa)DNYwV+OnLyr!w(7 zyBqTVFLii>I|U|U57d;4TU*p|iqpjbQrC&*-15nu;2UT|j$E-Vxu`oGlkeeGX^IwyNk@gP|t-e+mlAaY_{< z83ddi$Uc#QIxB_8Pwz9hsm5W4UM*cIE?)(}3(C99ga1Apa{8f`O2Jaq^*g5yt~k}9 z0QvU4&vTUq+@jYF5L=G-l-0(b{EV)E!oE#qSrvzc0fQd?$%UK zpsI#Uv5&QOaEUOw#2CWU8PoG%Y;kZ!v4M7b%t)q=&F{2-naM;ljpL8qy*HWEqX=^L zrS%>-9aC&#JH)iBPoo3$*8-@1MgV$mV2orxu%dur=MS8%LUx-kDNV}*J~fpG_LbP0 zIN|g0h2P)O=!vnOr0gOlPyju)O0j~fHWWrbpBw}B zfdZfB>nq6Ub-k713$6kz1U`HYIZXW4XV=Jc*fAX7q#tSvmDLTli7gC&)MLDIXTAq_ zjoL2|t?MBx#XeF1o>hXz8$0=Q>dME>czfBtm3S>!19f8x>04&TnywB8y{~RIims07 zbLSssn?dasXE)FD=;Zzt;gJ~%&STFN(@!mI?FzMhg*`2`2oL+u_5eTT$}tz!^9~M3 z6c0dOCt$2N++$tn(htLMCF^Pd1KyXybH+(F=BTm*b@seK6SjP=X>IxNj=XZL;jR?1 z$M6oo9$5L`We0)b_3ggZ&azq{pd~3N@ZMr^+f6s7a;(rR`_cyVP6pN&_stv+*+QAi zjit!I^&XGjtsc3#QTY45agt-cDi3Z~@S{-1|EN#VLY=*w4*8iCgF*px|7YASws#TH zVT69KBviyFltLslR@jTdXnbj5s4UE9fCYPm90vzw_kJkTt9l>h6r?h8fWv~9wdrD^ zz71sOxbjfn=JweS>1)S~J=mgGIbEsH{|9t8lj6Zo#|K>AE(Fgrr91`)zD1$;py|6? zcBzFztsSB;a+qt3`k~3f*nu=o1<>Rjg6tp$E{QahrP%yv{~M&5C+*F79}}zBCjjWh zW^635tKK2V5cIq|gx8T=1EYxfKVuhQc!*r;^A`;3%UM)N-?xC#POoAb2Y=L!Wqf$7 z=R0}!F6VK47eXyhqvbCgij;E!E0*1E81#GaOq!_SW8hw}kM_BX%e z>mcm1#2GX)7^d6zPceOKyDXNa%FQkmv4yGIq*n%24%lEf8b=O4Vs>ETMevWlsWe(R zKVbWI7+u~q%wb)O+h>m{ToCnPbiE?6+zvsIYv_+#Qk-%)Rw0g}EaQxcyQB|rC20}@ zV_bk`cL<|j`0zymPY6OEO0KZ6(VS7?6l%%l(?!yD zA*;Q!&pt50JLoNrvKipIu>|=WulMPz<$fFG$WvmZK<-we`Nokk4jPB*Bb>TKw`oir zzc^i27V{tYKe{?@KgJ;*cZse3yTv2`T6$dbLJ1cXm*$iux=mu>)4Fy2;`EJ7<2!V2 zHhS(>!xO}U_ze#Ew}T3SL5Iifj*hwm>Z2i7iTW{}rpGy-G=BN?3whGlPw0-Vs!ivh z7JnoG(RXHg^yBC7Yk3`3_V^?^o$k>!;;)1)PrxW5F?;7tA$Lv0zHLPJQ=DE%r^zw+ zvU!R>(0MYaXUW*Jy4Lu=nv5$8x8`?Am29Rlt(9ez#HOB9rO4S{FeruIX=BY zemUn4r^Dgu$i(L65wy_#pxQEUyc1x z8a35+mI}>)$w@|RL@zdt(3Vz=2#@(RoDb-;hzr|0J*MxV;gG#tW3W%ZF2I$~yTVv} z1-|l|OGzb@VY}Ua0RAcKe{jj?A&2& zIor|uG9Z)Q(>d2?2^{Z2rMuWFKNA7j{-|v6@wFo7JPH|R@W=Y_z)F+K(9Re6xa-Qn z&VB{;I^rMjF7=GcjjrFoti#}rcX8Uj*C{CxIc2b+|7SMN;AtDtA^)Pcs@r^SJH+o| zC4IzE+b7t01b+FBM@DXV@^u{a_ICZWu{q-PF5#|WU!R;X#fPz-_F*_Vc;^u}#y-rA zOJu3GIc{)KzH0BJ2r0NjaJCB>U2b@;J5D(=#U1NqA3=nEId>zC)8M)mwQji!1av@K z`B7Kb7hvdKO7ji}G;0;rsvNOYxzWh=y|;Y?_Ju%jqXV)O=fO$8#Xcz|c{L6Nn36ZC zj%x3fk{TQZW!ld6ax8c3cWnn3?1KKu0Q@Zo>S&Ob^BkrFIs5@k_+GkJ%XIQyT*K<4 zz8!)RV3lvgY=GzQsG|bxA7c0x#_2v)<4@3>73Zkw0~48NZ0wGB4< z+!rKZe+6!H3D(ANZE&d{B;t4kGCIewG-4WyQJ`ne(Av=8*-U93ZNiCfQ_yb76%=^s zof4i1!#(CiTVHI;~tcu!*N(xvg4UFg%|7GFkOoau9TjE%j-jl*bV#$K^K zgwuC0rt5pb%II5&0hukwJELSs#M4YNXd4RN##wDTfi+ezM(?<)lrfOi0dOr;@9lF0 zt&l-rQIt&%N3s&&G%&P_t>X;O>@E_sbtnTEXWvf4=>RMG9SqX7CxqG@ABQXSD({O5 zU}HPomOk5q+>-%!@`^rt#nOZQw@dB8o#5iA@4=p>zGHWHmCNNwO5n;UM$v6uWbHUq}p=-mNi|+!?SF?c)Y!^h!k= zOKlGCVv0VyQ;CJ9K#mXVIQ`DLLVr8+&u6#~C$D_I zCCM=n+{vE}lE|t`y*#a6b#sug8Nky0epL3`fl;uQcf0vDGtO-RTpslwsFm|09DWjI zl~c@<7(^YPX>YLgCw0lUV;I^)25MyhpNZA!gW)Naw;k3pHYg7n7&6d&2Jm5K&-51` z@-wv_K=1FK1;Q2YsO2U+NS1Mloc>NJyo1h=fguB)3^*S!Z`Y&FioGP&0q^NNmKZ`% zysb*ZN-pwo4DulZGa>`{SS*H0?_KyA>PJwc&na?=f!;Q#((*EngOf=KflFB^#PpnR z5*Z9^fl9w`_I=bHBsv3T$Utv0fSquiY39g}jqdV#)bp#Tqi*PDl5^O8F{ zQd!r-V~cZL(vYTd+T&*Y8SdOOjJ=g^nW(&ph_Ul9&Ze_>@-bNYfSeDx=x#mfS$g_p zakd!Q?ciLIk+UMuUW$QD*+EAr^_A4Xy8<@SMQawgbNu3&cdJ(x!CE6p6= z=*iY29a*R=KB1`O4cSZ`6D<-TXYZ~J7?my(^unxRkq9Jm80tX=@IloS@hxH+Qb`&V zd>2dj2m{VN6ugxeclqpqbL^?Eh>cJCcm{b|28JVww7kW%G_Mkv6C<<654YMmnv$qf@QVetO0>;xKE6pq8NbYGnd-VX-ohM^$?=^4Pz$Ub2R`8!isq4!}_ zago{p;pqZW>4&N`3(n&#-iOeBM>(i$KsWfx@WPJh3J|cW-xyZ9TEbz+cf_(+2^tzR zI|Idz8`?aOk|7Y@79w@VUZk-BU3y#Ar%^9LJr#8)jeZ+g__Pq}Cs2)#&(qq4uBM1j z4jVr}PVX6rm2(V!*v`-lU=MkFY%eLswI|+285MF%uRhGUSwj9U73S~&ZF0c-6e0I8 zKicF@N4#`rAzVuQPz(LUbf>?eni5ajI>=w_XV90^`UK9MQKjXxTK)k)O*0_fV+c1* zQ!rz~!W8bQnD3)zOk##WWf@THJi}rkOKI;=nB(^<<~jFOrrzaa#yEsYr;~d3cqV@x zZ6Z88ocJm&_kiy{1KdP&c?;lsX(zRzT}mqZiW0ss>by5t?2pCejuFT06p^O!ki z=1OEoeb|WS0$Rxd{G;b8=pB@;*vr1B^p}vH)?E?P_+T3@Vjk(9jXM%-&4Z7veZ@-f zFQ_u@c3Mm%-9f2|>m!)Jj|a1qFbF^B!LU0MRGUya1Egmc^&G@|e-0yvaY^uOXVu`Z zd*!exTD5wGX}^zx3kVrpn@}F~XsP7^kk)@_|EgFHq<2*U)^I*XAIIM}nRO zz@LJk@xin@kjZVUCgqUuq;o6K-#awKJpf5pPG;{C^VlGn7 zKd9Y640K|f-mNMw@U64YDmmHNSy;q`yEY5~seql4jB>NjJ%a5(aKMuaT=98nV^Y7@Viavj3bbhy)(8y<1c9 zg?M52iwXYvRBD~iFn)skWj+HEx#5}dTO?~uNy0psEQw1j-bHBZ%96c{nu=}O@3;Ty8`tV4q%^9JWkkmcuBnI|=n_$ybd0`zNV!AN) zLD%3k?0+PdhdSfPSM23Cl9ZmK^#P=}N{B7Y-?cVoG#-h&!AhRDnVKXJKHw#l4V;^5 zJEjNo|0{E0TBE)d%Tww&vUY0C%-yK5Ewpu*hO=#Kr)N?n!6M0@0PbK0yA@7osh`&X zpZHg-7@H(o7Ix`Y?5qWT(Zg!F&*W$Iu|qOC3||y^r@L;m736$rkky&X>)_Mc5{F>x zJHT-dgKY?o-o3Iw5>qV<5^^OfSAJNFxTZ23`YPv?P}a!R3D`bEXg>$+e2^T7s(!zu zFZJMB9+h5Bd;w}(Mg7mg=f5q7^Vie};3%7`tv3AK2-RGzaoyjxEk9It;HCDY%^@lS ziD39ecl@Q66B5k^)l!{_=v|2M-rdd(pPq(Fi&XX!OmgBNoIJCJqoSjWMAzt7*p@=Q zL*rknt;X~;&U>)C=5!7==$?So^4^@j7_L-j7`=&qh5#|0#Ke^<%KjA^j{G3i8R%v6 z2V8%v;RmViX!gHeY~j%3YX(%R*9{0nsrL~4ysm9dAO2il2A9^D_GiM87CIuTQ^Y@D z%*~Nc28Vv0=+uvVoH043Y};HL{?IR1(H)s7l?5`(;*5BZkdm_W8P@^-HPr-HyIy5)We zmC}5$`qpsRs(UN>*N}q)5`67W1u<_+fh)_qv>t;$Y30}2k>cUc4$7DfJo|zr^|^02 zBxD_v6y^4nO~e8pQoqisen3bWE5XlhBHm6p5fq(y_m&jryky~lS~qHi{Dj$E!lv2L z=Y%+C@))wU6`QfJu*vz|FKn70)yyFnj^J5F(i`!Yj#gVM*}rB@)cnb`1Ejyw~u4J zc`8tw9L&*Mp>vN??{%1@#ukaf7tJDZBmB|q_{wmn7aXag{q=f9RE?bAH1>mg>dP<)NenvB%bjXUJ z<^~dRF2?9q*j5T``R+vXxj4HO$6&%`af0mJy3QonZ1o-l__v+H$1m2+$4u8pt`Ak@`xR~G z3x2&+;Tu8eB(1tAZG_-!s*T$UU{1Ym%sG{Mo>LxJ_aSSWTP4KD*&g#;y8_{>^TP0)>Owx5<1bJ12*BxF4 zF5lq_Tj;+`Y6JfLNs1kCdU3rA2W%25^@e7=}~Y^*+nvkAPk+P?e=! z%QOW~W_IBulDQ%5iWjgxED~MhX|OqY8Nj}(dG*5T_$+jG&dtrPccFljbYH+Wu0jia z&DrdATkvNvF=QZT1~l)oZ1h{Bwp<5=!%)48j?@8gd_-Y< zj+D0z9Q?jl>U$gh%mf?Kd=suu`G7n3DSUrzitpfG1NCUs2Nkvq^a!s_An2*K9OVyQ zBas1(@d#Dx!|?qCh5u`{?%*^th+HqG$oCn23t!>8YLV0MMzHU(6M_#4C4p2S=uja+9^yjR!TcP-|27ESlmAFbDdK!Alc_Ne6avsd*u-Y2IvK|^a1=}j3hP=8to#ndW_Q=zrbowYLi|- zJd}DFkS-GRA?w{DQG_mjGy;pj5`uK)c-_Mji*-O?E&zeU&pG8dZg#8@s*+`g8;(D&Tl3!$ZH|M=w^= z{8JX$YYoH%5)$0i;s%BhLHxIce41!Y}DEj?Ta9BQ2Vj z(Vm6FqV2m(Sj;v}a|~m~vmD|XvKh3UPB}&_b1-%52&Yf|8zDm8D6Bk35k)o!(7aUS z!_B#ojrk@i6Lyl}y%f@96*%OK?%b7@2c^Icafc{uKTCnl3hl!Y#Y2clbZK@H{sUu2 zUIX!5FP)`Hh)Eht8#v@w^Ss0s$nRg;@T-mu#3Vfm{UhS(;%?~$#*Qf9@88L3Ww{CX zIwu%Ki$tA?Xj2yxc|)7_W}q$c3G+!k32>`fcG>FcL4i7dMD=PV11H0 zI*$TYan;uua?V3l5o@_C1T6{_aovZw>Ku`^7*)5Xkkf16!P*iprs=*Sy77wggIv*L z0@q4%CBe{FkDDbxA?6VwZh%c?Kyo9^6nbX2M2p1CPEi^C?PV)NgD$u103Pj6^RcGE zHLcD!ut5&OAp;YT0elwc!p*%ix%$MhuL(F@*%8E_LfuekfDUaw1E-RIaY%89E14)5ZBn{(Jps_!S;{=K?WWbV5T!feBwWM68f-Ed_x)(R^HZs0Zi&! z4cx^wbZ46CnbLrvo)c2xZiW(~CrUViqbjMQoyU=m{4)kaG_ipj@Acx|g(G!z)3=HfSl_9CC zP>j9*_EcbAgPL}r0LA4{bCiXoK@koH_fr@>M8n+`RuNBUC#bs0O{(4LmQ%#@6-7+j z#_|R(`e$CZ+!?e3c6w`7u5y0R7&E9b%&7NHgm^wY-D2u8$(mdOdsLUcN^NUml5lGH z1lVO*n*v1*gl_Cm6_9IQhqt|oyd$tCVTA3-&EA`xj(J2(uT{i#rDT%8cd>#q2Ia5D zLF>0MP2qUb&!B;OmXLo0lO(Qd3>>A0?zH8cuKn(deI$;)OKZzSJUgQdN_=A^cn?)_ z``{aU_XB9`?9+1OkD&j3)aQE15(XR_vF@7^Oth|oAQp}V;u$}$b!U5G5cx>`r?qTP zLI}En_&(~Hb530A>J12K-vEC=fWL@6L;wIl07*naRR7xt^-PZ3BdaV-6+tkjy(1=Z3^$q`J1FS94YLy4#ganua-|Ve&mEL5}NmT9$kDU5>qqH)#yKq zqU<|q=|F5(DB|Ow`%PNRuD=M1uH)A!;`frew!7*h*mr9J?#j=Jv5RD`s!1rYy*e_I zCK`U9t&G!!zej4TFE|9Sw;P1A|JT06qVWSUE}@KbaSea(u?U{d?0+|sgqLdr0pIZv z&aq)Ff1mIOx;W<#kBf+Rn z2Er-2^!a<#%_ZaxW;VWWt?$T!T}na_;0#XEcU9v$LZs&x9y0wp+rGxHoku1IFG6gm zF!G5IY2%m7qn6W3)KTDno7ERJqlfHp$UfP08(32o335jLUr&-SJIWf#vuRpu!{3cy zEXyK6PE-6S$F&wf#1MS>0yz|cNrrz-ToPd4FxvPf`#d;Ts}bj0$tP2!Ji#LhkUaxL zf0mL(aKAtjQoe$akK#+F!p4*4Om8#|)Nb+T-EIHO)9C^+a*vb7JHsU|3t#GGUF0YbgDm}Jc& zp}C}HTz(jKZZe&=wy=3MY^fG@g>UBQmTvf4RiW29w3uU!-PmVwjH~!??>i<;?7-I* zW2!;t;LM&e0%rWzkS$7qSmjOzCl-N+c0AR48xkf;?2i-(AGSxOoqANDM{%qr)h}>M zA%1#W(*a67f}0bFe@f6*sUX17kIg_y`xWzk+D}x*=KtfMU#PRoJCz)b!O1Bl`7ESB zt3&@pkD=U|0-KwmYVR$gbBA? z6XU2GFinapi}WAGA=a!2hOQhu9hfsvHSfKQ(MrZCo>k%Fts?Ned34^UlarMa{{ooR z5u@nb3FhKI;Hh(lKj4OU=q`-x3Lnq%BAfyE`7lJ$ealt@|3rQES~(=M6Xdp$SQ$I#v+qonr#r z1RQJQcwsMG-4l6OLgKb<5BU43+A_3fqpGe3O6>YDjUN6WkS$>NLZ9(~ z{1hbgMS=0LA=sffnz|%6W=qid4ltjC|NkH?d=q~~f=-tCfXOvsdN!)&KOMQ7qg)4) z4G~JpCEYRmh=YFC?!{w5PsijAIx7M4K2*92BKlBzD07R&kBcJ)@jhcYc`9;{^v}lP z@HVsTm^M3Nq*azCt4>M1Ig3{LRq7ZP=+gJmw_s9^6<}$h*bTU!Nw8*TmteIR_(5~M zJL*oT8>6m_n(`m%4(QRjgL6=S1)u+kZ6gIfOFu9_haazyI04F+0QV!*wic1Q;M;N% z-wZ|(w^8A?uZ3NTvtI?leVPKyP!6vX8SF2T!3RS@m)B|^(i<|t_UbyZPbXdE>Tp56 zMv%I3gM{{(^QHC_xW!X_Q`iVXQ|&jV7xXqhxJPcsVDfKqvn=BB27LJ+))Ftwew3Fx zo;LXS)UeVUn(zmf-o{#!3FqYU3Fhc_fPcx%vZ!rx`I3bPE-uZw$qPT3#b|^Crc>^@ zFdm;5p;rwXQo(k{{~!=@bdn%XBZz7egkTV#A+^uo8eQmNZ+XWXd9ZdAZ|{rkmvsHW+-f!sr{Oyq{Su31 zUS!8fI?My7d&CnlQyKnDYThbL0YR#bN!3Ft?g*sA9imI`$pvHwxrEBT_*@ovw~ugZ zetbDO=4q#hq{d#YSLVG=@E{pI@mP|jHP+Dh022o&%+$UYLE~GOSmcCWP9rTzPs4(I zMX7-R?vI*0fk*Q~-OV-JGZu@a{wFX&zM z)mK7IKEO@4?z?w2LZmL=(%3avSh-zoY2Lh6PWBrgCEKJ!cL}iuLy6SjZ7gmo$rc0L z$o2k8x=VCfxOT7YtKEhzx^YW-=j2>)(e3Kft{@M;LQr%Ql&DDN8=Q3i0zKR%TDT*I z7lX~@BRlv)=e0D?B-!p<0oxnfg09-FKI`EIi6qWOO!^kL4jNPw&SN(WB*89q&Z-BjK&+6m_WNnRv~ z6cqOn4Vu@xMg;vQ75k6&c_sn%gg}shCl^W3ZZ>H%L^!vY)q45oMcug8 z=++G?)_0u&e#@9n!g#H#TCR^=A3l9E!LQVRrko3tB}1~bZ>v&2mjD~(e;Hhl zcw}RfN=C*7NjE!zB6eA|w33=o5bRNsbl2$D?YV(uB1KDdm!^v4HwRn|4po@^0@0nl zP><#%=+I0XM8ft&{Rt{vfk--c0zJ)b@S{eAX$!D>pSMD{w zNRY>{^AOoY^O*?|JciwNxC1jGaY-sjw)T7k{a05N*myCjTi&H25rAQU9*6&gYiQ_~ z8K9p^$a?e(KKEw$9b&vPLWaqy)R(%z$7{M9&ALWJ56Di>B~ubl?L$*{Hg` zS>Sh{AwPg~jph~nqn~sPB;icW9NAcKie4~d>kRD{Gk^)&pPBd*Qd|I!d96P~IVS4# zWxnu)jzT_w`p+@1`rWx2?!5rDldrt6D}9lX=w1ll{slX4M0LxlKKvxevmVY(Lck#( zF|(Tc@_&Y}sjm$2^<@lk(L67Yx-RNdP`5>WG3u(QDdjdO(K8xnq5chZ4(jd5N7gG0 z;LKj=(<>ys3Gu8h#162Tk^$^LtI$p)EGhTxk5UPK`Z}@9Ov!8RIFUO#Dp)O*7rL5T z^6yEtGw4mj3}ENk5LH_Ku1$e}xbjlEXJ?`~#Qf@d0|ucPKMG1K4S1 zMRr1a_z&8A*~*djw0w+Qn=coSoIMc9n;HJTs~hVZMZs45Gl(&p!}x?|06WP(f*pk* z$7@3r@*3FI8h$A4hf3GvO`+eV==Ap~UH{?F`;2qN_OIBge(S=~k9D8y`Vi~K2+eqm zXBeLW88ACTVEZL)8o>370G~T_tCSy#_qxhVe*-CB6FB(uFyoUe61|WGN{hORp?*p{ zA--ZP`603te+Hc%X8=0{_vrB5DK3NS*@B&~gh*{b;pkE+(vWfz4phE(hpK-z09>Ds zxK<8JeT2e0N+m%<%4_35%l)LoEjDIo4;jds0l~g(L&TS;ZKYUS5)e2(9^)y-#V>RL z{y9QUg1u4VCt-lSPQgo;ZHF>spuZWw&a8Qn>+7VEfcFWC56U4DUIm}(WS)XodQZbB z91Sn9!^vUEPB37)$pCiH3xqqg>M|=hZxHf|KYUU?;OGV`aRL4mDYuxk05-*|^<$>t zJGqs1Iwu)-^KFUvVh{a%3OMZ<`o|0N=6&NCxm>pxdXD3-q5a{Z9(q7E(hBPSp_w*;jCjkAS$iU}rh1+}I!+GBD#ZApPKJ z5+mgVE@h$EO343pjn4yi$iR?+NCxo1J0kGm+b*JB84hr{L)TT5g#r-W=#mxvN3k8g zA_((1z=jNTmH~WF_wsy*U9sf6Kxc6bhKCFc8E7E`SQXq`t!bg4+ru|(!Texi$iR?+ zNyq>e1o~}>@1fp-dJXEqli>H@iYUpPJ;u_ zi9Rk@ZgezTa9r&26#W}CJOfsqf#Iu%JXazlcG#x^cuoNPH(=HcjB`WBa6(Q7?miq< zXpShjFuXFvcQXbl$6R?l#^-VagREW#hJ~VD{y6Q6IiVw)?et?^@j?M2@$2PcM*B97 zMSy-ie3gh_beHLF5zH{G%)qcvC=-?oj-7dBDHpzb|3iueZju&?3lwn?^lTyiSRrnJ z2{SM(6v9MFVEFKFAi))w-z%^hXs4GPi~sske>F!+#3}uy^QEN@3^-W^hJ`|wClLz& z`Ts2f&If5vYCfjm?h>jwqB&0LC>Egqm12RrN`W1qf(#4`g&;{yL9p|S-@*+aekAn+ zyj{-g-cmoYu-+%d0{3J zNQ9>x#=^H&*%36b0G%X&4Ui!N-DUtgwx&Ez>aBwG$QUQM#J}hrwMtbk*CiznLTI5-)Iq(7@C{s#cg&|RP3;`|87z;}H#;Q4@s zLOf;+Q2Nz&aWQ(@EetG=YQG5hJz9`FKKd5Wmwy{$NON7@I*Ezz(vQXD2b@ z=wUpUE-0UB2n5?X90w-@*NOqY-*7r@%i!NC0Uv*_@h8Aj8Pf0?EJ)}FghJ&qgB`Xr zI0M*2&I#=$#n@Wf6hUuM0dEOO;C~*JX)(G8^%JO~LwT*8I(Ya*Z{;#Rej07@S0b_t z{0mW~<<=BmLH4HT0qzZj{5xy8 zryE|i!cVv074guk=+rwR_}?kCF}xCvNffTkoW_V*5wL$_2g1UChKI}1jmy^1n3)+6 z{zn$@Iu&{D$7kP^G1b8{$&j9(20S0QQ)pq~fsO-%Mw^WI|zSQ>Rl z)U|m;TsrJT@f=Mu0`vP)#T*}0Csx>@OX@qIKA{fJpqnWJn22|va^*y=36LDX5pgmt z_kiy{1DHqg=fQXr$z=aA!|k^ z#SBZ{xlnonrB@oo(6&_QNdvyplcn3Eo`BkiavYqXMWi=(|H2p15k<vvG9+M5}u6u7m2Su!kh(PHp-n3DIaW09x{8rl+VU# za%}4j?S?a;nV14Aexnlb8$|eD)Nptedib+3>h%%7CT;kiaCrSnunh_#2~vMmC0D^2 zx^uK*vcd2MYBvMO{=JnMhzrDTat77AJak`oeQBZ(+jP`$kjIDVD&C*sZX%zC6Z~{F zf-6ZcDFV@@99c+ad>OVaWB?QKhR|dL#&(pt2M+q)|6|m$)S=9q z_W>lKu|)&i2clkqdI{>QrTc`9gC4yHL|tr-NohAW5p5&@GxP}TERATTvrha%QT%sVH6>Np z*?y6tm!bn(2h-jS-P2R_2c1d=&ZB&yyty*cpaAx6NTlBl`|5uabvsv^$ipBmYnZ^N zLH-wREF^34P!K**evd_ceaMGlEK3GHhq?TJS(rQ|n9r3kl=2eaAH%oZJ+y%}pMkeV z1~8HIT6l4(VTx6S;rEG+=LJ3nI{LtF&pOt!5Ps0l38Z|mpq8b)DtE~6>K3hMxqTS; zGG+jid9rXqKbFfZ>}@2pnG1Fsh~A5ua(Osc*kT^|xd`e9QR$wPHp`k~CnG>OeUZ}f ziI|&6*!>#D1ki7P=A6{aBa?c6jtszt?@qsn`J~}vptW2Mzq{r@9P|*?_fgv@bfu*B z`8aUALg8%EEB?X1R@ZaWOZ!L+J*w=M**TmA>6cyNqJLH<{$o7+ImMsI;cK5ckSw}g z{qs4K=HaTHOAoIrR=xBF%Jff?D;xBA-dghwnTdTxsQq7nf`J|STCgW-mTT|eSqZht zLjP$e{?c{Ij)b`BE6RyYCKudEKfqk2>NfS4Gd1fTmq&JOgeCRb6$yqg$ATzvF zp8|nXXB)>dZ|??Q(&1{K@{`jSf%ZD+uVB96Cqj7S#z667wJC;GZZ|A^`ox}BW%o2JU* zeOx3c*yR7lO=XIBF&R(B=5GQU&qiYDJFlvMpU!Kjev_0jum)_?TePzl_(nVQ&8V}o z5>FP{V{rHJ$S>s~Ybo+eU)}1IW#HRA5(3z}0Jvwyu;A zmN2RU-ld^%w@PUoJQsEwc~A|$T?SLbgJDzoz6!Z+;eguN3i zu)q^2FDM@x7uWA$9_cH@i8Yw+fnU;Jj-%fJ;r8Q;;YaTm3Cd9;M-)gPU6Oh!>Ri+x zAQ{Q$5};3CMOMOQU(^RtzXm?_xdm|0qWCCkYI!N_o|LNW(}Q2vVJzF5y?k~8a#}dA zKs85i+zw4YhwvoS?29BgrKOQe&&dB<;lS6WPB6Gx*e^u;6>O~!{XJ0WpWso@<8sZI z2#df=Z=ioR>TGbH5=Qr66b^5T$`v|EwNY0t!Ztm}P^WB`+jls#MjeNgy7vM94b)xUo3l^N&1!Um4TwY#a{n-(^+Hs@6=j> zy}FA;_FIwR(`)RcG|)a9oG)rE$(AA5eIaU7?~X93+RrkXr3vB{4SC8oixWZ;_~(1Y zqwP9fG3#HkJruO>0H&40Sb;AgNcP)~VT>NmYNC7;q@Da{3+;{Y>Ch&E1?R^?c2mZ{ zNzaO;7P?Z?Xn|vgD4jc`QHQkTaDHuN00w?78jW2B1h=^Z(AX1iwKqp8xh$43hnCkryqNDwV&RgXu$L9_hPSyDdhL7a(2Y&2YH$l04$;MMR zphEvOIUEAl=BfVVua*haYt=gNiS8N&SOAu^Y!ER68Rle~HFHq5nXD|R%-4`T|9B>#-8o&Vfs*IDVU^OzhL#_nhuGsX)`wHPPgsY?`2fn1E<6*(ati+Q%^j7R%=U&R|Px;o+IU- z2{@!B=?Jl@+`ymIA5|8g3xth#Pwfuk*0xQ>+$t}^r4RCD!m!_=bq>5Km)d4)?MU(P z=jFm!ZP@iv{+WbBg67ys61LymRE}W(3ZV}+Om&oKD@NL{YAVi7c@Z@I0PT%|;E&Kc z2(H%!_`E|}I~u&#sDD8HkekMzNyj2>bnCyWG#RtXkty(28lR@r*w%p>u8GAWbb532 zPf_W_3zZX6f`MM@SB`~J>`8RsllsJ$gmX zz8c$?&-DEuDSjl*EHp(fMVrl&j0u(C0X@f}DcOH)M(FB9!I01$HAw}QUP;hc0snzY ze+Yg{V-5|(dwQi8r=0H*ylI~X{vrd&_6Z3Sv{KUv zgirJ)X=zcN32)l>N#RFwHP1lY-*jB?XL;#_Te!oU_G`xTBiRdD370mHYa?+|X9^s> zzHBJU3?O%^w^1qSli={_d&;>dxa!1al4ETvQBbJ%%_iSLe^%RmkUiK{KW*5SpYTmw z+VW{S+7TytJ}}$!OrcyVeIj^kud9Qt4N?D0Mo}I`{ctFjq%n}vtIa~?O-aNFN^oL{ zkRzV4w%(-mT#tQDT<1Ztgv?DZ6(lrtFOHk^6c%aEu>W*P-4cpQ8Z}C5|w)3so z7mB&0A18i5Gq12g559d-t=eI*(FlD)LNQ3{OVu&9ZC z?jX2OfP^L^*VC5TBLlh)Oy^KEXN7Nv&wal&dU%2`w)e`$|0RQUgTj7zJuGXEDxO&E z?`=9PK8gu06yz}iz66y%us^98L5lt_ls4B>;=6$NdI#?!A&EAxkm}(B*wy7|?GJN* zQW(?kg*YGVJ@lDINqSSbk916qq|@Wwx1*}c7>Tf>GB9u6Tp?|C82r>c81&QZ4$MG8 z#&~k*akGkWY{#G8j zSB#*v4^8FzisbbvFhD=@BQ2t{%u=!$jML;%Ge5agy0eB5`+f9%75M1g3C?o`ymU*# z^XapSvLkBB)s>MM^+I7g2g4sjr3GU-)C=q}tGz8CzA+0{Y5t`m2?${0%D`~bLz+j} zH9L6Ieor#LCXbyh6xc6MS0?#d2_C%90q$52_J1)>h3;QE&4W>iYb_MU5}dgUbt_a_ zG&Vq`2XW{p-l&{oaMCSSRpQZ<*K5EHU^P3UW(RM;)oDYi$)jc=Zz4gOr!~bV81dQK zhdy9%m==v!qb@;x6wxKmCIW4h6AQ&5sN&M9bBr-Ks`(M(w=)!jNSOiT{MF(eWZt}e zmGs%+3SSAjdv*tE5@tD~sObZzegr4<$j8 z!A8u^=;2;{kYY1|{q#REj5B_K)9Y;f=l(Nx`HMStvB~(^wktkL^(nIX-{e zY49mn*myeXi&5q8&jk2ssJ?O^29842K5H-b-)Gn(KTJ&AFcAJN?(vZm|FU6sW&}MF z`)w|{9$C((pljt9{vGY{krO{u%b2AMa(a~gm8d6kh6-8yy)gi85FiK*{R)FyTRtT> zLq^=OWFrkJy8Z?Fsyj{_a(Cisk>67TId+FM=QA434IERwNj}vX*m(=;U))4U`kc-3 z%rOyg0Htgd99|_I=D|F@*oN+57ZunkeHSS-3{vFpKDfSQ!|qIbdgOZ!f?P)u=mhU8 z6yCz{UwpD0d7&Hn{#TNh0Ok*{Irfao=o|&ebDfF51zf2g;7`SbX+g0c_nxg3RsY+8lkTVPFpo{J|cY`XkD!?e9#=x zJOwuXuC>u5UgJM}PhCu#3}K?UCpq8n{Uu2DucQf=?k}30#B94Z%~g*FVv36K##ed- z(W^y5k(&WJWPn}um05R$oqo6tc2!ajxufA<;~05`(Lh z*k_-eGG9IDdlOxPp|1dUNt_B`_6>~rhQxP(!q0PjBpu7oQrK_&jyr`flL*!1@9aJX zi2e9`3cp@1#A+Wrb7@b8UyHgz>X!=zb!f3bT@IDL6VcslhoN4BDlJz+^%yC5n&C7% zq;%q^S&FiSqsgCUUa~pZ1ra`b+7p`R!p}FO(kt_*(AAjw1&1>9E7Ekw*B_a~n*CEO zfQN1^l@>ae(#wJXG;yfz`R`@G9Xf?v-znW;fLpplSA(V%F=%cbpx?uB?^>ldfuDf- z!k|Na9)$C2qDsq;dmf844%Ni>Ip!{W6DJwKF8q_)gnJh%Vp&Sc+XQaxt49+C1f0(m zU<~AkrZH@X3`~Ozd|wfRGKVi{(NP;uzh>%&NzFU0b5MLe1Xa;EGK(KwOcJrz0rQDH|HoEdzaDBqk}}oh}quO*KadmrYV)CB7p5)g`zA zGd}~!*K~ZB$Gwv*&aMpzaj;*J3ZfOPn zJ_WXG=mk;-u()n4#m;0L^0bm7esTU4oJ~PB3x)WIBD1sW z8}VTJk*=Z$>1GACYv^JM2jV{>T#(_P_E!|VA?Q8ex_m+Wxe}~IHpuR!N;eQyP>t#qbB0}f;I9WtL zDR?C6OHd_eS7`@73w0mpr=CBUt_y|cdiR~k;ZWik&>Veg@*lU{EP{TVTUt~L1wNPb zZdQ7i>mJx1gi0^WmJ~X8_z?6@H{f!`fsoD@>|azf-t<;8`E=6n?@c?DiC=Sq@|H|C zr#p@2>x3r%UFS`6OTn!v&f>FuJoKn07dl7LWf|S|C3HZ0=~YPE2uyQ=l2-kp#517D zljaIZ+;X#sH5K%o9esAaP~5Ia(z*(4*HFzJr<#*=UB}g>eNCRG>q3$G6~Fepb-hq% z0-vNK3eApsX6;#=83c4bOj;)CtH);2pn%gHRVirW&`uYM;$%zQ%lU{cq`)5F#5*c- zpt+RVgV4Hh0eR9~9n#!$(M>>8R-ZD}47ZR2&3#8z&#Kr4)j|LFT3F3g}&C~pr zW{;w5*A?XR`HGy@daj|Z$Q1F2E}?>NR}H6yeHd-|yK@0P%~DQn{#%=9jUg>}7kI?8 zk0PeoUHCX@Hj&SZ6ghpvB*dqPN4ijGD1F!$aJei0`$LOXl=pKWtxS6p5qT`Nq2-qH z=ENZ!dLM%L{Rxv0Q_lRPaB21t@Gp*>svgNs@u`ju;-NQNJt*af?IYl$yMZ+iS%yq6 z4|`(|pxGxgvn&!J>w&S;17l-DNXSda1U>8^$*Pl?h^g+2gL;^Sd@dnBFW0d3eUT_) zd7C1pqXpPH7ZhB2e!;;+Y=)YxxK?9*7~Wc8{EsodK8z!t`xP;XkEr?(TiZTp@(65a z4^CLJ!aw$ISgegP$o_Eo=vs7Xtl2nZ1P%X2GI zoi1>imwO z9u!sVqlKc-&>a4AM&1lZpTrFaW$zT?2&O$8RZwSzZl1t)U-2PHP@Ntsh<_nOBED*5 zMZJ;L?sM}~3g>oJV9n9?Ng5pn8~%Ea3Az_mQZ57N{ixaAb_}k?B!&%!39gqS`1>#8 zvvRvaF9T}WDdcErWu6Q?>BX}Rhr`kvhlSf(U$bH3si|oykZZ3nVbUQ${y>PlY^e8OTL!sC=V*p94h@tH%Pd$D4=+{41k= z0QCyX)@^97--NyFoN)93%kfzAnCuQTM2JA%9t$Qg{<((S>J=^GKQxeo*wCkY6->Yx z1ae|57;F5d0M*PLLV~ujk`!%DQl=0Lt=OsM+)0X6>noB{=h1f6pFi3M@f5mBA}ZZ*Vxv&2@PFo>Iekb7yVPko!)I;(mmW+dbDsCId81tb&f zCWDPo>nO0jfnrCv3(nNaKN6jC_hM%`fWLHwqRt|*@FXr0MZ(341n@f)I?)YsYQIfw zF8Z&IDs=&XV>_bKZO6Wn^a2qdnMeMWE@IDR6EV>Qr%!Yw;?@&5e!nIC7akWxe)_9rLMj!A9P4mX?P$qi$ z9tJqPf5>UcSRdvo)d$4)dP$5HX33Z>U}JCEw&=#1^t?xN@16nq568@0+9fIF@= zFwv7~uzMT8 zuQ3WWw&FMXST^2lwWCe=`iv;3Ux3_a@2~DxcnjouR^fkp7MI8!?2kK%fK#B|r<%dm zQo&K#;PLP;&vQf|N7EH{|NC+eAI}WY1^x{eg{E@!0z;Zp<{Do}) z?++>%4Kpb99ICS!^;D7QDeTx0#TTW{$8fl;^{W`hGyYePoDPP{$f^kKSHVi;aKZc1{HEiaMNW*s;wo#!+Y;@~!Q~&*M zK}@SwjP_7~JZL{V3nDhL4(K05*rKC>SbAVL`gv(%g+2v-BrOsYV39o4+l!FIUS0u# zUwfg_&Y)Q<3(LmUHBYdf+=yRf%13^cV!kngL&29>Wj8c0oY__wE$;@VbYDhOlK$sHsAf6*1kXZRH@eT>ln3y=&LzUNpnrxoehXjciPfnfA}!dXuRLv+ zUM?63Nl5;O4O`oyhHiL_x%0Eg)W(Nl;s3>~IOFtd=dX-2>k;5p{h$u;N9nEP)qoE_ zMXghAG#=F)fS*&6<>4Bb!E&?i;;F&)h<(oN>#Tgq7I8IUXmcHKuPB(BWL zWn6O2_LwZj0wjodB91EHC%yOa7Rd|=Fy(hgVAmGlLlDi$vcOD?55eG%LPjHF<%zTi zPCEQ3fU5fg#-pj%gKavQt}WT$MGFV$X2r_|j^usx0S3=zjQ$6*R$q?}d)G03ghb_k z6xLNqcb& zjlUiN{_NxNNpGR7JI;!@wP=oh%X*6>QUo>#9UILL-Xx&1XFNm7YVu=*y^GWdvj3Li$um8 zwM#XcX5F7ZYdr)#y`%DvIx|_&(T8?mg??vcQp?eyxj;}$q0&k5Hp>MtmVCk&y60=1 z4dq}M%aj33%8RuV1N^fk=7BpVfjfuFwOIIjOvG(Qsy~Rd~}oFrtq1z-jd=UINANsYorGQO@7aghKD56?~N`N1@Zv39&C+G zI{HsXr4w8CqIR`NP;{@RKiY!*?eWkd-}_!3gs&-!#10(>MqfqfGB;g4*`D(Q@|3rW zEzWU;WU#YrXuOTF))xu{y*TQvsB}a?CsxdjR99;P#*Rm4$h8le(Rqi@pgys%e-Sw9 zyfR+natJGZytu-FJkX6s*H#AlBe(`Wsu%Ub{p7r444?k{n>%C6TeGqM(3P*%ly>L@ z<^vKP@b6ChC>7x8g)^ocB+<`}Y3&dQQPPbi|3+Om6a*5f@`837m zL6Ydcj^BzEng#v~^!uUGjWo0fzgTJxc~ZsA@xtVVh23v(<1NV!Bp*;}EfPv!zc}CI zDCcxkb(T`UY52MDFSQCUaG(N!P1^#{t=nqOX;KToK?>xXJDXK2K3a?S{dAW=XOP(&pt1`q`me^C%YB}tBwL2`7-Ip?rTX33cq7X06{&g{-N--PP! zx*cZjeV#L+yXuBh)!o(ARnPUh>Kh(t$UqcHYCD(oQ6fW0R%cP6+ksf}g9!foBGj3zwt6XlC}*U5B5T~} zuowmUc3Qvi=hq41@09fSX?-xsho|#&@-}eaZLypSwAU`#D0a*h(U+;(8EUb;+as}9 zZk1XOyiC%9n|7Pjc^pMBFf)j9p~>nHek|24;3V6#`Vlohj<1r$`KGi_@jvJuGt_DH zP1s~3$=_7B7@d4eU_8x8zfPtrxevbn7|NMNfY_cGBwhQY(Pj08L=lv3*Qhw@??wB&7$X9)vENmfF-HH)pP=7pm@8wv07`=}UkV&jx9cDn7>tZ0{_8K9I} z%^OKI-T++_bu0BQ`(Mk#M;F}#c4x6u)w}};=>8}3BXvxS=x(NCir|Hg(QMd#El3M}cSR8NaA@>l{xUr!TXRrA10qDPWh!&FKjemVK&BcTg>H@W&njysEg%ezSy?O8a8mtMP7fy!hVnwXL(;}d-Y+Mx z(=O@kq4rU5d^;r#+wTh1S5&&p&9~T&L!NqULuY|L$D`%>)A)cLH5)%lleZzyzp=k& z!~d>7RXMsQ8kb-;^!LSR%_O|QNve8_jekLH@ERfGiebR7=`jE9fGr*VB#7%Z^tPQY z-@!yKyHYiwtvrKNHRnQ45^`g{w7yU%8u*ps_JxOkv9!VQtmGZ&g*msZy z_#HI8zflkR#|NX?mh~htS(1}PqYnYU^}f*H>F5Faq9!TLi2{+I?5fpU z3Msrr0gu0hiBu;E^6eFiMG8e@{4dL>PnA>C)Q{|vs#$`=+6;!LJ#y-mTa*v`kM zbY1_p(^KW`1pP$Uz#9^DiX0us#Zy8AdQ^CR}|&b5M^qO$GnNP0Uuy-S|DAg`wJ!Bna{sR$fW`3`rX+ zcJ$nWy;VYN2By)g77~?9h+h0uKU3P}@fO3U$3yH`r75zHBF#zSMF=xLNr-G!7N7(3 z@<`;bpo0U^39>E&P8{`(?Y_zTX1je=+D;s2CG>aDybg3+1$02iI!XLn<&8u?NhntI zzQdRLu+qpbX)^Uh9u;yz(Ul{yU}F(*4N%kcPOw2zCFGHg*m5ljHBl|;P~yFl`d_B> z#5-?NA{+fD@4u4f4@j>^^N9qV8r^#VcoRGXb_!KM+N5QENlfVCR{#J&07*naRH*Kr zO9xqFUR2C?h#a4W02Fsxf-ccprO~B>I%HURNIZ>c(%f4|U8*k)w`ub<1|IlZD`XD^ zddX01QF$i5og+^tU*-+r1|5wr9_|)bl#bO9ze<+|W;W}_PHq2p(>NcZJEh(vD**36 z5Wg^mxREMN8sCe~L!g}|`L*IfS6+*gvuy2}h7apH@ynlZ}QoE~6sz+4l)9T*Al7)GUWLg<1*va+@pUdKZUU_l zHu3bd?sn-5G8LXAoY4Y9&5=mNHjrlNmdm^K86F=JM zOWA%C>Yw6q)IAv5W2lz!l(kN%DEx1Pnm#IUunlFwrq7hO@4omDu-& z423>pZ$}LN>EvIu3>xg#&fjj^2_((3c^&8dbhGLEBQih%{xoH6{820TNkCK zH3qaGNm6;AK`>^I8SzU4${Gh(CG{_6dNsYT0@r~@iF;&L<-|7=Iu-|OgAKv*pbWA; z@m*`>2yy=&-3O%5e;F>DgHngyyA8uP3cekV)lieB3^1rZS|j`iUada9av1_qeHCy5inlhC=T#A6B6_ zZ_7I-%JW%l&X>Y&A^xWDb3m5d510YgGyI{T{y=uEUX)ZOq+)%ZG*hhf_^ru7Z-L5k zAB&5OdS;{?3!VEyS!%6`&;^LbhKt{oEBo=sdSAUCX-*PDi#$n)V(h;I#Jg^N{5iQu z2^ZbMX-PUsp(hEsj1O87Emf;l`Ku&VK2ap)c?k+O(KKJK7%ziHc_*pScIoj&{UkdA zU0vn^g|%|p`B;+eIuPd*Psmmv^VEL|wE6wGDr0quCl>tai({zDK_;0fwgm;6Xke0R z4z*^srkbN=>7rjj@J-X_H3eDak*dNr`PmD9w-6sX5W(P1zjXCTBxuouudb3vX@tZ$G!-braOkewBuH>H zX{U}rPml_1ogLuYeL>1vBtrLMUG!hsBAai@g8>R=GVo|q0crN={AuiyFLXrVq-pfW z%7dQ^fd2zkl0V>V^X*(LO1kR7_NYLzQjf7gzb-V7H`&p2`LA?!&=XXH0SYt8ipkOD z5X52!|24Vpm*7KCr09S=1gMj?G=e{&%MXkwjngG@q;k)5EqS9Ny@vjoLu}B&RvGSy zORqef9V`sAPUm`HHIP)xf7%v zkd(?g3vk{CuoC_U?$oK9>Tx6o{%9<{9B6Gi?93RL)|2%E15}7PL8v^FloJ$xsg3fV zC)L%D>ETY(yIZYQnRsP(^dwm~q*BWb_G8`1HD)SLr`5XIJwOt*2FSU~fZT)s+?8vv z6*C51Qw*kT;FhEzk^7N>8an=4AgO*&--8TLMHcN?O$P3~GbsfFv$y@1rDHLvOO;9w zV<7|1Zb}+d+maZ(BlD2)q`rCj5;8!&2wsdgsr%?YeQ>>Nxy75fEy#tbuC0kWn=P_; z+(f<`>v;pd)d}j-&kO`ql6sQMlJZo~81kJ|cR!?uw{1eWtEEXiPa}cu&HI7xPBA9B z-|nQS*Z0w5zFCqOsf3FqNuMMwx-~GY@jhE4|MpL!!#XYgs5S5yXq0^u+6{d|A+>)? zs9VX;4a}o8L|porfyP?g;rEG2IYL+PEe&Ze4b@NDA9nCF`pni)zZ%ow->*CPnCPCr zgPvBqCTjE}jcl9m-2kE&;G_nlOyr|(e)s34u@0IZiZZ1nxOU8QTaJyd@e zKO0qRxOO5TvnDgG0JLCnY9W8fQwoy(ch(Riq+3RbLnTCKa~gDa@_E_j^!~q(8KAPX zdJEK7(@+vxscY$iJK+-OJu=j9bk5aAujaiZmNvRtZ9X|vd8^DFwyhGXw=o_1TD{tG z^~N;*+ZhQR_vMB#5k^rBO-c9al3jcGb68@Mz07Kv=< z4$Ru|pBB7LEofdDc;{tm20ddC15~n`I#%O>J4Xa5B@x-Wjqq&L95jHdF++#nuY~%j zbRF~z+7+sojEUaR6{^?MIRk|;Fz9ILykVYDM^Q7Zv#N1>Lv)gQ)p0pG{|eDpPlKkX zJ8K)ax1J~Dn_Qjx5ymO~->*YMbb6X_27DYvI9FX$Qb&WHUepyaHe*Encffa0DS>{AN$2%C0a+nQozM`L0@F~LUk^;Gm&XJ@?FiLbOLuj`^ih)&SCXeC!6%BE zlTQRX`&eK)PZr34pC|%}N|5aRfV9H{(u_?)6MciRf4cujaz*d1%{E2QSc(Q0mTUOk z>F2tgcKW{L4ETv6IcFVna7CS_V*+-PX1;D|n)WBT@}Ad}w}`(VS{Q}5kI~!hmQ8OA zf7QZ%KkM`pg+b|4QMDFnt5(AkwS7sgZXKEd{fXvMgz8P0?$prqw3em_O{;Xor(3qK zx5@KO_HW;2pKo>s%F6%;!cdUtX-IQ4ril4o4&Ju=n|35w)VL|@m=?xMgEsnx z=nVL+M|4U}6do6-b~Yy2UExi;C<5FQ5vU*3|Sz+ zmtO>=@gyZ+z)ut(XHmXJ2Lrz$&F?zw_g&6_ zGmw@6?){ep7X!VR`DBo4rX%@+S07L7Yds&fz6mr}RgIs1`VQ0rs#{$ybL7LoePOv#45NDm< z%ERsfqB02?Gi+BmT(dLa3^)VMfHTmI0WMa{g7*hp!jk{Fnk;4w3v>q$$xYz;-@9=W zYrnVw;wX!#jQkaFu?ofYI0MdrGvExwV}J|PURkbiO?ltr{|xcG8>b1qiQbFbA61wFN02^x~s=hiC%Uyz?lDW2AlzBz!_-G04LWCL6Xt@Bp)jp zfY)h(-_}MGZpFrRV=cz}@q9uzx+cf9gX6h3R+IUAYq0eESZncqT-TMbj0tdcDezWG zmp>riMj2i3?9M}I; z_`P<5^gWrh#(~A-AB!>@TL$=j4uACGzUjwqO!hjE?46Wm@wcC3KLpgX$%H9AA1iB^{W>9b_P+OUMsWcs_}Vmlx`havFbsp*8xWM!__$hEgA3zMN3+IV@VkJ%*c-; zI5As|>_5rC=LyjHO#{7EQK{I)L2R)ot0B}aEtvI}*v{7UnJsu`Qem$ZDYHDfs+G zREJ%eGZ2vhZ%{-e(^Z);urpfKu!t?wqVQj_mDcoG4D?%xi`62L{2d)hPoo->-lSU0 zD>WL5^xLA0N z2dB^8HmB9aD%LoHf4B8K{SFJA@+MZy&5=bfBkIzD7+JsBP^ABBaV%(zj*Bx;S_Zs9 zQQD$$$Lb7lBGn^=-Ru7&fB%XL!8$Q@;_sX2v*`VpHHM$~cMEzBjiIZi;}yOw9!p4l zl$dLN*1s;Rl~MhF=5OlInkb3MX`@fy#@{C!H~4R7z!`7`D#rjP%IUz0U}a$PvZ_#0 zuzxDBkWWymMDX6Y@fjwe#CbYrz!?~#5$dahZp&JeWXvnNV^8VqSOnM{4?HX5 z269(N<0*FH<98$axn~L&g0kSF7SGZk)lkvW(7DYz!PcIkjs>LqZV)L65@GX>0J~|D zJe9zWC`oa0GoY1ayNS*bt4A^FN}K^_ptl&{)@ z*mOkfIB;ra@K^@t9w+b6*nV}=hdnji)W}!?sDZf%DD=G&*dGeSMOslA%-kvNH2ctb zcv^?LpY!PdG!$8u89Ipa&YIO#^50cW863~)mDPSUeTi}Xk46)Cp2X<aV^eGctr2~-5kiUf2+L82_KKl;AcIn z&p^qmz}${AP*w&w8|aQdmYk4RoH%@RET^0FY?D_EZl~G|P;b7`RCi+i&9iZSLM*4z zGe@;c)V+5GoPkUXa1z)h;t55ntQMjg6eqUskLXMd64;d^x(YJj4T=gDnw86(bY@4lPI$53!l{#uPC7dIxHtpOK#mM>Tj9eF<3qn37iFd3KS~htG4OUmQeryDZjs<-0OMy>te+KWvy}(|2l?aiFz#;rVMoq=OVio3IWgc3ikygUHp78(AlnXY-k#$ByX0Ao14pwdqD$?>B;AWfQmzY&8WetE zNkAy&pkq~o>+~3EF0cex5iAdMR~GZafx1FP4HCWm^*(SfcnqlP{$1*g5A21AZc?i+ zYEY>07(*UM$rA9N%Z&j3FNM9^K-QPi-H6X?#~{FUbZ5XD6x}(Bo`QqrcPRZ?WW_q* zSLNW*^UbJIJ2~Br(&Zv3J_jFTuh194tzuNb?F3lXKv*@{RtH}L-fasB2}Kv5OTaBa zul;^IuZthHN-5N>vvF+O2+pZdw*q{c-vr>Z8phWF9SgDKVSHBu#l@HbZ%`N$+^n7h zM%~DogI@1SZcdW*|G!YM1qaaQSrs+s$M+lAwr2D81pi+m?K~E~CGa7)r0}KVOOFv2 z0ULmCgZY3=E&f{O>neUhWx=<@pms09}}D* zS;GB@yqU(q1bHsbBNn&e4CKxL2f+;q4umX8wIuG=76GDH z7tn6Y3~S`I?m8+j#G!`6{NR`1L*UXs4Cp--KLm4v$~H9ceJ`M6vXkhT-Z+l~7CSno zF6rb<#C=vhA9+w!85@;7I4Z+%3r9If^qf##u5-88ZLvx7#n+(A?*R+ty`+<}(J?VI z*cluIvJMJEg-eez@G5Z~2rdNg_44DB*yYD@rm-Do$JX0MpC13}QL7%gx)?Ix4GKeY zyQ$`&+K)7U?3OO#el=oN;lO$$qRz^yf`5%;Ssd&SzFFBo-0`w8a4Zh#dHplq$QW2O z9CNd<+Q{G-Jel}+0eQ*4F|;0h=eBM}UV)X> zjyEVuQZgKDn*DJTh%q%YB&sh+q~3}eZXxa7!y)zrltL+A}tRQ?aa@i<7wo1}iOsDEplE)rU2LjzZvzt!V56sVkLsD0Oe&&2;} zflFrwH1+%U9G|-5uAFd;{s^blLzsu$j}a~Gr~2zs5Ce@Thk{&ivz-{=p!^~Gb>Xy< zA8-&JZKXVxUU<+2OXDAY5ld&q^yoSKbKvo2P<~n{t*3VF!rLL&4 zQ97Yq-oPm}46Q_sEA@i7l!O6qP?V$~Lfqg0)m{1x;L9QDyQCSx{-rn|Kj@M!x8202 z=f{5sz4opT&8E2>Tmh~G50&*IfNwn~)GIxjSrKehgBl;bcJ9-7AuTUmnl68MKM9|9 z1+hgvA1e~;JFykJK4%~b162OG!0*80Kr2kvMXMreWy_s_7Nja%@MA`B7f2(DXYIm+ zzybWwN_k6zS3obw(*$uCSPt~s1*;5ICb|!l)A(Qwa5Q)s^n%<=5OYQ+E1^Psma{c#Y%Bpz03$%7yv3i3!A8K3Z_`q!pmHk3q~JP`L^LXUpR$CDFN=e}f_7`+ z%iqhv7NGEhKt2F1+dT?YRi4N3--4yfQV-mZ_zY0KD}rM{yJL%8rI&Z{aCK0~u`j#e zW{_1*k6*&$G~(QX;K_te>gG(3*j)OZ0V;yl=Fcjpqo5SM7G*9^IMPXFXHZ4C9jA8( zdK}}@=L}E}W&l3`4}hx4$2hzO$h~oa%~?U3hQ-=Z9SR z!>8~M$WnV+E8DWDgY>2bn+;3Tjq(6|>fLI3{X3lK|QK#{NOWL9D&RZO8z1!7jD z#tQi=f0ij}=;m$_yBZOz0G+JLF8{$nJttkzoESIIcMMRkRst7-#_?GEEv0A-)4aW2 zNW`cy9cLPrz|VS}LyxbC0V>m4h83!=S{JKtG@0(%zr;Enc&HwHNxyXmbTF8{XA8mu zD=h=myIH{D;3H6GxfbU%o2+Mqc+`V*PY$GC)H9@cAYlwpspia~Vl|qm+$xkIOcLM( z;7^T#mh88li~a^o8xoJFaR%~afOkL7z+ z^;EX9WFedi_7C!ZD~pa4d9?4d6Mx|R!4ZjML z+Hv(q9N3^RC)yiU*=gMem1XG#F1N)=oeT0DD5?59D;%lr_pS70gF>ZErBnCR76p|2 zhcx= zJOCbSz+;qg-@JmlcD(II{D**Oa_A0#3BxR$ois zHYil;RKOMZx)BtywDaLqz@NyEvI_jng>MgmX-eed<@mBE-04oYCk5W;A+XgNut-k^ znk}d&$$m4qMc>qi=d!6QZ*J;?8jD&9Q%j1MMV`Wu72v(_CF0>njcYAgKUD$b9192E zEx>LmP4;zzqFy4k3V9X(^Il!<5Gv!rbwA4T4IgXa%ME4m2R|+Z--D}>CGshgD{!nw z4I6@xZfyAud z8kYtJyg|`G29r?iQ@6A^?LP-Qd&7;M!&g?| zRbvv=XxI^K4Dx)gi#eAD21fH+Hx6fjOQ>6;8unH0Cv{7WP#v#&JW>YH7!W;z{BK^) zz`>>1+AJq~8YA=#;?p(4r3C}tplCq~l~iK}{tmv=Vt4FK8mM`GY^9<4h;@9@o(6UZ z&10DERCMnHAMY62FjEbeYAkFA_5(|r8FIz38PK?_Rr}3I~NhiyiD*=PhtJFDZTmz72{Phtt_X-4De3}Tc-iKnVbC}M{o8fa6a%dyY6N z*D#=q@I2s&2mxxaSZ<984!oh@L;QXX6xEnG8ru^S_srlXewSL{YeKL$cpK=s@FTz* z6QwRSGv{;b$nk%Ce0p-4fRvT$Hb&euP|Ci zO?Ui0(B1iTz`QY`0}R}X&5uFejS02x4-hxV!l2ZR33!?wTmp3WrpA{yCLqBjn1QuP z`Jn0#avhi@IA;L~IUb(?i(*>67Mhunx6Fyb58&xh5T%!gct!&a1l9TYOW^7bL8(Er zH<*;=KM!82;bqF}BYsB}_?;4kbJQ?9-}8V4 zz=E~!p?vqUsBxJESE0(`v~n_IzCyBo3sT*}8JylXbt_rMOI z-Q%Ep*mp8Gp$c^gKg%Z&{Y{Ye#W|zN`wuX8`69FNh*dJr|SpHo8W#{YPLDvp{lCjQ_KNFF@Y%Hw;!{ z{0)BoDsOU9*i)TX@6tj!RGXeP0e|y@gTYgv>~a(imi}%WA14Rb7C@$ER#mPMjn9(+ zU0Y(`6r*yGJlC@abBw^CYn4Hi<+I^w%&42S^ar?j#?SFV5qA%J#VBWM9W{P*XJ1B9 zck<34%3w5WE~~B|o+kp^gL^?49_U@pug5l?vz=wH|(#6IF?4P&MH~(F31}LvNz?ogjHILmIaJOc; z*&62^zUt9uo-!O`n)O$RV7sV6@9jALeIZ0t%_!^@HOR1C!D)pzEo7CuU{_sg8q|}g zT!*pBj4#30i}NI>$<|x^-wRZFhDGibyQBswN8N#c8)%$WQSxsLS7nUSWcZr*3svdQIb-;EUEul(-Zd$V04c0Ka8!)%!I+$#X#P@HY$$y z!8TdT*YlU30m^wZFlOm>zVnpNFt$?p8Ty}x_^JW1c??9Xmw}GKTyFBPb6MSJ!QZ+T zexoXNqSSsu6+({PzM)F+%1s29JmVP zCD+7_ptUxFnH1z%fwybzNqM)z&pCM&I(A+IOP7}o_bhJ)s1F*{`69?muFX5fto9%# z&l@7murPb%i0*6hDroHJnzme4{yl$21}KD$z`eji-b3m18C~p}9UEV>aK4SsYuRpg z5OxhVMFRX)&&`8v;)%WaDHP70!cEW8Ck#+OW(Im6MIJH&Bc-2S+F11R7u=8sIW-%4 zr&4r5_w+#501MGIYs2VHyTW)3P(TxaoxyOBRkR+zsoj|fa=rlI$U2muU7$IhTqH*;2X zqmp_lJdH&D2?!lDbQfti%OhCqObfmMdB`90h{?hR;H?mGK}0qW--In+@N zoHn^&T9*=jpPd6gGVv}j>&-#82I}e>5hA+g=-M-xHNUREU|(glaJ1URH?#Dy(%QxDw0Yw<|OF zInVN-ZqWUkc0TxaXQ1*7P|-EMBacN=-onnTRVEDoX91Q|(0*QJe%$wRGeF%v09eW* zcM!8Y(CVPpaw`TZ`Ix9PgTA+~8K6?@mB4w(`Mp3iM4e?w)=zqYBafln3{Zdf zHLSzAOl7xb7=A7?+eGbsLUGaoQG`D3-m&i?q00q=w9H+W2goL zRN|woDl&REs0It2y(Esj#*@v`*%RMeN(QJP>e`$t6 z+zhc?VMN%I=FYnTXP}7z>hdE-_4&>wQVnvs<*l? zPA>q4fe?9>ME?gW{R}XqY>9EN5JEDhIWEMPs-%Gny~D&xavS+w6~5h1dj_b?i&|A^ z^!C(wlz8$Ou-+>@JDOFr3kbdTen8rNKsjfl;MlT2PG*%4QE)O?-Tv^-#{#h&4ya}jZEac%{WE7%S0@jQE9aKi{hw?4tW# z_Ulo?6eX<;)+@qk;hgF{7Yi&bVvEt^g_;5Ka-exn<_wrIK#kNpVk~45Gp7qw3{f+J zcPt2N(D{o3LmYx1tAjIuZW4=-ON)$ujBTPmvxvys*u0YMr5KQiAF3FZa&_T_Z|DHT z>AeURa<-w{uG$$0Vt|VMSBuJx&aVVHP{BmRrUCws8u3vz^@kbI$u5ERNw}hQ>8XU|&Q1V^m{f8Sp88G?2ddM-7n!&eEVbF|sc) z)P0A-x;TcSq&l#BIC*wSnlC~6KXFj)lpuXolUj{ff2^v6xZgd+z#~S{ENrB=G-^5j zt${O^1FJP=VK=LQ(Y+SB?+0aDVC!PIeK$tjsT&kHa1Rdb6T^wfIyR@^a(Po|-EZve z&hP!}{|&x>3g4Fc4O~vG((1(cL~4&bqcaeX0jqjw)ew&tc?3LVm*_Y^#R2fvee6!r@+MI5wM>j=8VnyuN716bW~t zZ#J^boiLkq@+07KexOG%Q6y7?LLT7E17Lc7&I|sjZ6%Or^YDR6vLtq{Hneph+#Y7A zzl^FaPK-~&;u8v(u{FC}cB0sIhH4MM7$ZvGyQ`F}KTjQyX=HVrx- zimkUn-@(N3+lK!={}WCpA;_r>0)4?ir>k@Z(lRhSZN@J7`sx)2oFDb5+43>M$jFVf z1G|)8?A`C9P!knaf~&gB%8yfH8!AMfE*M~2a1Hnz#Fl4JIJtFj*cczY8{7E?eSfu% zp^W;8fA$6rV*V`Gig0Bl-+juB0V=iz|5-@S&h+S1I1qW61(`LS5AdxUbt=`CbWZ7bMfBKgJ z>bccLW$k`t6;AKBIw7O?keIxpZ(49)27i_J`#?htTtXOttoqWU!};Ax9%iFnax!U% zzF29nr>Ut{qM0*&E0DUD5wV4?gx9wP>VdapfI4n<4$%yVz7#l}7-$)3D=}%T;p|ty zCE$}5j%(ZHU~4dOUlwdH2Th^Q1+3&P6zAGFDqC3*zoz_J$oI<@tNYWx3{b&!fv}Ko z^)IVKw1oA{;8P1?YdS5)clA_}jo(wz7zRUy5?2p-;e6dmkTc9%CO!i(-NB%Lfgd7_j%axgreC`WH5_69|7 zma9jV4+DLF{BRz<2CA)QQ!IvV%`96{UFTQ^ z`u;>amI?pi4D>hyoKH2~{!*hbkL7wWr;+Z;tMvv&mm;h^>bSj2vb4LOqw?>aHggZ= zv%2t4(1TogNY!P)>bz@p{8W+YZE@P_1(vt?qmR~A!m47owpPupKgDgU73empCM9NG zzh|U*sF7Y*>kOn}z^XoKAtM(U;6_cWQd-S=nG4-tbD{?`;0=nwoQ&NI7aPYTeZmF`!k1EyU{hvGCPgC+Ana7U38pL+5jSuo_cm zh%v+=M~Gho<`@K>+(!seQ*Fc2Rs22dtxU>Trm zmcE6UYi68+zTJpZZ*5K{IH;wt?*>K5OBmiAOqk5`c&V{14qgKma#TD|druRDziL4G z3%$pbM^se?sNeS()bY{ijNK5gD#e5Rh8wL$X(3k*GG?#=$Cm__?=0!Yje0Ux?H1ag z3P`3K$+Tv-j5+OBkH*ThjNZ=4-WW4*px&A54Qzgd&gqFK+WY4Xd@NL@Vf~u|-ajrh zI5+MLzyNjpL%ybnOva=|`%J`2ITY822yaR0Q0Zu~w7y@y!nPN{P#Vtu$> z-tilE;JhxRYc_5x`1iut*BFhR^YQ~*YGhe;j~zr|cw?e-VOlNlrMl$e3>3-$=a)Hf zAa-LyG5G-R4kgQZ_ceC^xkHjHyUxgxxm8~3$&}z__LZqIAy*G=q7_cbcDzxA?_k=DPh8WfAPHs@QNfm|6_)X19Eabx6eA!>h# z)zJo)SFAM@W2(LbWwXUp7)e*hHbQfQ;;u+WE!6zjLTL+~C$`uYW7AJ#DCq+oRwu?4 z`+z$SvHT2J)kCY}ru>WsddLmk2PFMnVDhBN)L4lkG)^`~kp^0pQ98B}1~e!jT(d8Z zFJlz=G?TSo6y!YESlYnO>u`Ijf!_Vp!^wAQa1|(nynqvf8b7H5Ym*866Bz~iDS9VuW7apf zU;w`UW>glw7DWrbeN#RRP^XtMs@E6f6G3lSp$z6XDu<8JJ80%)8rIPB6C)p!s(qIX z!RO7k7in4|?}H722+~S}dxFcsTOd!l31f5Ph88@sl$DK?pNQ}3Dsl;D;O6k8iBfKu zD77bc2I4YcRsXDxm$=cFL>uShXK_W>ve=>?(D`C0#Ya7w**b=<1Ufz=?SnwJzl;x( zX+i!yCbVLv18aeO!D--O@EJ%eHGY6G!T^=_jFo!#7ZIdIgJKKxKHLuk zdW@xFU`r!!bey;(WPt0CmXbb;Y~M2O=PKqZR4C~uvo~I7E1d}=Q&34e#c0!t91riF<@2S z&TeJQw}mmlMgKpf)XOkq%ObVLN^HHQ*XIq2Aw#TMlGl{J^vmzy@kTE0zyUwGk#1M( z42)%fdZr%G-NtT+`{RVT>iSZf)p>f3eq_@d6hnrrW>oN+rQni*0q!6)D&AtgxJGze z-8E*2*t7N^1KShR)CO_g!|`#yf!=;odACu(n#I_6;th%+L$)#~bv@gB)y^ryQNiYb>r8U12g-2P-d+=(qcg7bu=i}EA1gvF~=yU*Km1e z1Gl%LoUCS(7`W>ytHc2Hb`AW!$-w7N(K!`$SKlrf8K9iBguy}?)ih`C%R%`a*P(!D zjW1Bw&FmoNGiNRF`6_rC+{S@naZyKgSFu>sL`EO$YS|McVc;(${%w*Bfob<3oi``~ z$?{~08Q48>j<5`W^~OXPQGuy611ENaVpgu7i~)QVOsN{=6`W;@7E5}BUF z&*RrBNiwBOJ4?!Z-LiRuq8mfW_n)6UOHhvWgHm}SXCN5^R`u$gn2c=4$D0&Z7?V4D|I-oYh@oG?PlANbpa_Diy^2U~| zo}Yhg?04U(uMKXpm@~cr2dP=tWZxB(2Rx*9(ziHwJ;`zKo>Ls10ljt9LZ&oOs(NMh zs6MN^o2Wry)jG@SobrDVLrDi676mSI-k|6}dWKzhWysqp>%yIO`aWkMAp`T0KIRDf zx_Lb>cZttHl^PV**TgLBzOM$waalAN<{d_BTrY>R6st!bqb!~7W8EW+Vz*f1!pK!u zTLA{F#%7JEKadOJZUqi8oA=A!S;t z)}B>EC1sdBlTCw%EyU^qVBxFlEI$KQ4OA`g<`SO)tM!OJiSOzdjk-4K8d)Z}Ky3;2 zPz>S6*ZJBO{8#@AmVe;SEWoNT8pHdj@lV9x-k^v`W`ioL^0GRiG`Q|R`-lOn`efBL z-$zB$GE}SbGP#E7+Nf(Jk^G}&H2H2+n_*l0Q5$01d*In{E>HtQqm%P~R;N49ov<&l zdNUs;28mS<#T0`q`Gyz_OdUf>3mrb@r3ERzDK!Ho7ZSX&s{g42?U9U=8O1TmNbeZ6 zx>o9f$)BBoRqt)P5Y$Fk0rPswac(`)pl3Ynyoa4D)f4pix78i*G(FB+QQ^&OWcW=Z zy{@)D8PI}57GhQZEqtw#PAyYyA-PO=;F_&P|AfM2%p;G&y(rFs*NjYSl($QK24;(| za*W22MtWUse==ZoUa_kG{aH%mqPALTvhQwG`n^H%#<)5a_18R6wYjo71Jl)iME;&J zvOZVW-war-6W|RBn|fu{ps;$RZo@(Zt^MAhuUpFWya7}r+&7g!br$o*{mrlu%gI%Z zWx#5Dmaj!Imf|Qs)`+5Iu#!gyZ|eOm-k=yVXk+dkLmSPZ;wS!@(qm78{NWW&u{AclXPuh=I;$kdTJ`{>IQoIRi)LOZht1-uQkdx z?&*!xTdl%r{x4-G%PV%TE5gHQ48_sV4x{{jYT-{UxV&p>a#s@%>f@L{p_ay?ueTm`-W z?L_;Y0q23AgN=d3%(%AU>BS<61t;eslSapC{%-wy?!=0^XLy1nYj6-*jF=v4op{te zY4O-&B);pda4r!Tpqw;-cGU=~npG@8IrZfrs%9eme|83_r<#gran8Dldb(D24_yOg zG&wBj?X9V!KqbeAsdgg;=i&mK;it(qJYqOS{A=NuQSld0QKo0qk8&>MmzpHJp+`_ zw~WeYpY&dh%ZYDOfY*(D3{`t22^SpaRmxu|nF!nn$|P&23@0cXfquy-*b9Oj@I+l1 zpnO&|DkG^~w5tQ2z!~Vm0QG2o!#etEiUw&eh?=SVjPO^{=SF^L{d)IqGsI)s+v{2 zz=ruLr@kDW-Aso6PsafDQ|C^LMeUxTZhE6PU9k+vMHzjW4R;LK80U`$%+5$TWqRC! zf4a_H5yz#dT8<*NA9d0=e&bF8(O3d4MP0VWgxoY8i%_csKb9c_Ilw??zp6aMC~%Dn zx}RfUz%gND%hmQ61FARRVZyR#Oo*+6dW^Cn!`a)&_#Rms6E(j~uXPz>{~>jJmrnTy z+>MiXTN0n$DMNw#4yUkwVrifFtp-zlir>@V|0qlU`$ae9bTzTAZxrvF=v|1iddEn= ztL-rcsE?Bo(j#C#qtNc9J}z&hyRXzzR(fOcYeqp&OgUv9+>eiQ;@=BKK4w*WJ2AF> z{Ly?jHfdICM)^me_h&}B$Et-Wy>|Gru^Zz3(6Z6{#Z%Y!nzn%ftI^0ap!;nO>K*%@ zWhbC31JslCNc0h~YE0;jm0Nao#1n)vaA;`4gy{~A(U_1;^t{NIRd0F1um&X$ZzFJU zOb0#(Ws<9Lrn%uWD9TtHur;qy@E@Xgl30HByB@gQ)To>q)jr1`H85P9fdLFqFQx?d zHC7g*-`^Zy*#D$vfbyBssEnjmz1vX*otuMB>rTjS-g01~An|USygh7V@84{nK9Td0 z5@YwSHa=zDe0U@mT@4IS7`tUHkih(E)OuskYn|$xrqZ7kSZ}f>^Klaq>l}q~O4b5t zlmE1cZVpm~&F_KHZEWYc`IbS>g>1mXMZvo{dHN!DE(N~=D}mg4BieC+4@&?mnWLRu z-=3TS3TYp!f@+~x4T~v~d+9l<&H&{;F*v71ov_;U`>JzRCjTiUt7QRH{?U6U+Hr@i zS%Ge({sGiO_8*Xk9M;aK;O%(16nHX)w;z*7^L&p5T1NZJKm(U5Blv68OJTLlcV)PZ z?I>ln1;|q#$Jhd~<8XcDV}Np=4dn4?qp|*euY62Y+at)myOH3CzmF>$GsHF?m=A0P z4h8=LFN36_#>y{}#5Z7;N4Jb9pPe-GgP}m9;YZX4knpp&q!#N-Mp11FZeCKbIuV2qLd))&*1`D-_37^Hs$4^z0m^bW zexFePANjk|YYf4SdR!LGnJ?K3?RJ8KC?o1SbWQwM7!GjOg_zewk|Uta{8X#B>>h$W*wxq8XqDPHs^P zYdViFI=)`D55Mbyq6RTNjctD%QlZL4dCdVH1VxE@LtG3Ppg=V~&q8#5DSW)20cEbz zk^w5sb{4ga@*DR0|T|nX;e4=JFFi# zEILLCPm9_Nw<^Q{y;`8gNADL{5#WD&P}HL^RgqV~LIqOLH>TnFVG(X5K6SirYLZc) zRLt)fRZgk>wUOJdwuu3_)}2e<(*RY*jk0f(TmILO0f<-Ew|a_-l4meHpJ9lux`6?> zKF+Y9t==Kj5J7c+CYm-{RG3r_4RX`8z^Q>=1O6n_T3+BgH^B#S^$1wZ$mmyz$>KdC zM($QyE#;}{rKf?d3W`LpINp&mKdT`7J#UsW-k2aS0Y!~dxB=T+QpWH1JlQ1)kTTx| zS57u^=W@z&Qw!brtzHjZTjm9NPthCT9_;DGk}hc&fK)y2-T{vzaNGmj0YXKi>Q_r+ zFKHg^Ocv@?igfA{*L+}?oEd<3b%kpXWf7u5fy?F`a!;Fs&jrC7MHD7B_1u21o+h}Y z!NI%bYM81{ddXuHL6@epCYhrACh7kSmX6{;uPK2TJ<~o2JO^Tk4&*Oe^Ms9MVmRAI z$9rs_(mDp$KbQe{UlJ7gd|d;7{Y7Mhizavr{7nUldYtt?B70yuh>@){JROKNh*zzB+~dSXmxH(f2{L z$2P5aiE<~5lS`pot@N2%87W}ffedE(t)*RJRu|J-U|J(P*Ac^dM!H=s3{Zwg@nznl zm4R%%n`C9`!6zAX^ki1bP8aX%z#1hAQ0IdMD6e-* zok{R>Y81SeNlDzyzbCGr#Z@_ENT%m5kTe0%N$){Wmd1oQ`dA;9LSg7dDwd1WtP8gn zSjN!Ly5aU;#9!vdgo7h7?V9M5*P^)qk$jPNK zp~A%02)UMk;RIM?g=yj}V;MrgFr{9FQ4<=?kN~l6(LdA1E zKJTUyD=dK(78Kbx9E4t8ty}L_NSTa6yEhg&p?a{X zyQZ~6)2B$M#~(gWGX-(*HYrf|o*J3Lj49NVDa+o(q5;q5Q>4ofG;uBlv@q1K%HU5z zA5Oq`$-jUWEpo}g032#C{DY{lTz5z}q>pBBvtw3t%lBP6Cdz;3PnO--zKY4UK=9Lids6T?nq7bT;JsUZ5T;4QM=LNc8_LXKdko?V|}IQJNccb>|z~TkbWYb0=#SxxmFGQ z87SKrjZj{;H{hgErPe9X41m58V%Fn}UBLsO46;je0pOInWv?yBx#zL_)n=cn@E^a| z0Z-=4n-&4uw9XH|wH&hL0!g9aX~kUKJXK}9NS(sy-*B)z(D}|%wu$a|B!vX62DZl0 zT?(`sbZq%%Bv;3%iP9n_!i~_TQKD(?lGMd?5;&J`mk;^w34s%Jb82d$rECjl=UN&l zLO0w^h}|`S9wBW3ET`w9K9#Hi_ru!dBnFM<)~N0xmeA2ob7lBLh`*ps1 zS}2R12=FxHAUA-^Ym99~R}VKUqx4%qjiEG;1pi6C?TGygzN1N$21VVQ+QFzhBn7FK ze`BCJp=pHc1>i~o8O?W33w*3bfWwS~JOM6uH?|Q~J-keh!gYZzC~JZFKvhI1_C?`b z7o?6toU@SNAyD;!pdI6^;LbfLzvDakP1)(ft;TFsL<3i^2Umiti0{R!INr)n_}9#X zJzDLHxNSvvx;vu2LRG<;dbHFCTN|tZG}fvvckx3v{bvyKtM!eszoRxNVmsFh`Y2@G z>D+G|%TwrIii$GeZp+waNA<)#4++#@*Z^qplxaZK;;IQjFN?}bJRS?5 zsTvWj$brWr*uGDzeZI|v0d;AwMj2-Ay`$_jW$_s4Gx4-MO7%Eey&0#2%iwO5wQF#D zAT|y)w(}ACrzajgwsbLIz#9|>q_$JZK_kBPOnr%VX(Dac^Zlhca8eC&#n17{uQ4#{ z?$zMPev$hL^tE6Vjnc?~N8MoE2dp1)=-5^dZk~gYG1*_zF9$*?O0`y*b(hm|Kv)E4b)nLF2tk9& zNH;q;47?3=!0C?s63|bL3Bn!I?Q7bYkP+&^n_zx^s*Cq+ZF7mnz$a*06Mm-wCXESs zitZ2i`UB{vbLb+(dmN~**P-v@K&r+7`8GnAdJR(LCts-OeCv&gP_{Cp>!*W3udAK} z>;SZIPUHF+nvXsLoC~%BdOTqwoQVDl_CWbsCI$v7y@*(bfdP*v_`f31y9UMxSzZD^ z1=9`8-gp0UosUjEcmxcEWp$zJ5sOQD2Gk?5K739N{+(V;qMW(bmqecBlXz0h><*r& zpG)|@2W$rhoO2r8VV~A&xr%L9G;TNgt<^6zt0!vD1pZG9bgj@eL)Q*nL+YYyi>@)c z)=Xj)S1Hx@^dk=nQw@XNfS%9InxX`bCC}beMmLm@u5;(nV9yi^UnS3Pz=`f49*2H{fy;YT0PdS#I$|| z=cAxk12+Rzo-e?8AZBAiz8sBuo#3O3Dic@%#XCk<-g^o)-ry9l8BllYdLXu>x%-Ii zgPzeJ3Dm=;2E|W-#s>7W3@7-n!ii*BP*`K4RtS1*8Cx{iQ5W3Bfi5-=#x_u}zC0Qe z-+{vALCnU4&iyeP6DkH>qjasRKPu5Rtn#ym@+e@D7fm2t1)=FhUjupi|0Y**XYgQcKCja?~VdzN;7@OM9FvRS^StT+T>Yna}civa~=RR zeb;&lvTZP(wW}`t4V+3@l&*`Ia(E5jX6_t9;=LOa>y@2yVOQPmS}boBpa%6?pqJ|b z;RT5Xk`IMH^{tA2t=x(hj zd7i?Z$J#jYs!WatyII>RK)==kxDi|v9eOZf{k0;B*A~=Pr=M&#-+0_!Tj}QJ^2yHBBM@7?eqN%9Bk3U$9KUC-h}B>8}Id z0j3u>^v?k-WZpc>+ig{c0V>-q1{E%Lqj&(J_^UTVYu3T#;4{!GvebY;4gNsXP9-Dj z#|B~crb-HKHt=rA3Q*7Na~C+!^r{O=#znI`AF|rRqnr64$f9_tgk4H#t%6JGLF|9EjAY@LdMnfukf(f( zu@gb*Tf+EwrvWkEOHsyyp&*~AUlzR+sd=Y9~l!O}56-T7Y1`qM4jf~5<#g+l}}DY&9r zFb4azP+{c+9(3cUYniS&R`QF=5mSW2u&;~d=m@2tXMleJvFD2yLCYYU#5EbX3*;@2 zV6b$LLGWpPBO-F0;WMb9eM6xPP^Tsb9~;!I(+dqOz&J6_0Q7#2yhXi1m0x(VPBF2} z40J7uF)l^dMokHJNx}f6X%)<;L8xf7^toW+BzCHvmUx!|nr)G{Xk@q+*(r_S&&38L zsLQpGQTU}HwvQd5>@^TMwrGI!bY-O#-xdUV=~dpM3+`%VCHVE`5)ThG@^kz~?ysMxm8K80=35pQ4wtod;U(6Gci2Yw11^?|t zj(FlqGe8}h27F>rm!2&fF~s;2pjll-$SD{t^qf()@^F9poB@bI>#6Gs;kx+=mDZP$|CzhJz%c*7yVw%m=B!mIiMA zJBfpl(`x*|H-nswm0t&a<6|r;4>}8f%z+PDKj8zT_(Ig`W+VET zBy?^7-V1S{mPS1?x(W2&ksdylOCK5)aC?w-wY1&y3>1Hd0?p1SQm(}K40*+ktzQ}i zdtF{JxSjkNpw8@URBxWjKbrqpB%W!(MMiOjs(p@xbHwHVozsD=ONU>Dj{4Yz*e<$0 zXJ8-$RJQTJA3#j``9Lf7|8Ra9P-Hi!_|u(%##)&7)L`RYU?Hd2mzG<|n*l1yx)znC zrgO18RjM z+UrSdde@Ks3zImMAgvyq_*xHnRoY&+LuJw+OSM+5WxFD|B)IXxan?Zw>enE+C1dk} z&Xoe~r%84|Y=2!}{tQs?^8l+m`M+96gzs9{AnzryG1*eiVQVhqjIi@&OAq30RB!6u z*5&8=dz1kx&sreKz@DsCcg?a;Ng$d!Ru*{>N20w)16|)Y4D6t?l%e~PoB`^^0zeB* zS;!s9JqpW#v+7Z~)57VLI{!qzTn9K}PwyGZOHRU2W#0P~R*O892?JCVU2xPI%~S3& z2_~ab2$&i?o+lAqY{{3eWDHA>ua4|uC(G_bvij%w^JjnpUldp!_b;P6>a49&l`y2a8nK*cydd;LnKVK})aD>Fg(r$JqZfij8K z_}B@gx)UPbnTElfS?2O|-v%;3J=oB&F1(NKC{rWRvkiFO(APAo|4OD(tmS|oKT8up zggk06E;z7O`MC8Fd==IkTTjgpe)lS(Q%S`dL((L2fAR#ctIj+qKS?-EzMmz!LPZ2F7QRjWf=8i zzI3%BCxwi2xh8?@X!=~e+ZSUD0wuO8V%pK+B}-NSdS5PV4l9+If|L0<8>osuv>?N~KQ z4atyJt5T-!_ACiqL2eMI##($g16O%vy&gjY8h8A^(AfAzK_q%2QwAvGt&Ge0L-fzo zE(rGNk>RDrKEzP3nO>>JC$)>c=bnsqVybLk$$j;4); z-enIb?bg;7APV`ExyEYR`LP1Ha;5KI!wA9Q^Us29mf{vOL$*Ha+|s7C>sVs8)D~1AO9bZ0qVwVpbSe-m#v!KjYB5y)M!_F*o*nvf+x`ztr3JSjj6c< zWR=k6Wqybql-hqD+jC3cT6h({`~0MS;glrC^GNF!&F z$)}9Qt2WiwM1`0I=s9|)74u$W|K1?C0ZZ7L89WOt<-j6Kkiawz^>E7oORoDV{PQWM z87mf8}C61VE34pfabh_cFHME9&!J&1vID2unO4fT?K z>daxp^V436DMc(Fljj@Ya_Y~2Q{*?vLfJfy;zdl9k5j66cOdSw$8GXoMKRzFilUfr zW0!;QD0byFpLqnf7T{p~yp21BZiWjz?>z&oU#KJb8h;madxA?Smr?neu7)-0g+~5s zne(lx;jxLAx1x0$>c}f5+9N2XoHV{nHwSsh2N+osKJLrInA>R0fHx>w^OE~k4!&J5 zdUB42@5k0k9DtwZXfw4b_)%S54(LLXcqPKrhRc;v4ZkPAL*SW4P>!$jzbAyU9!ek! z0KF$c-@@WGOvHCT%JT%R!MwLo)}`r%=vEMvCJ@fnzwl?B`yRlS6ByL1zkM^!lVtqo3~BJJ}vYlsC??*YApC5Hc03q>Z#fp{EK7ti!NzP zy}Nd-o{f{+UhvNqCfdP)k_4)c2$YWg0{&4>%C*GEUyzY=~qo|N}4kAs5w4O@! zGB)Po0Mg(jv&ICmXbp)Sfff@Q4&DJ;CReND?F&jZ^%E{W1!sWi!5D!jja~UV&>%+_ zXCNyBFQ7m@VpG=Z7~fNY6F}jO364pOIrr? zK8$rh9(UNOj~)C|eLfb1%I75fQEG!JGGb3}EIvKd!4&C!nZhm4l8^y^!n8Riu&a@bR298OxA|_%*9xCGdT)RT+G8A97*f z3atDY+)DlZI2VhNj8JDcLY4eaBZ_qyVtzVJ<}`WmcM9^|2v$gwzfGPe*}f=o^wn6E zHe8r)_6CJ1z3r8A;LO6_hrtZ(Qw8lgmILLxK`ApN!e7mxxIBZ3dR8sQb6)*VFMPv| zx{1};+8pcwW(O|SVnEYrj|Uno`4Dw@D?jL$+Qycu(RjntqwKQIgo0GT{5X zeBB0gp3EZW;`_E)6nI`|pfU{TzyS|{B%&9Z{WPy2v889LvE=!@{4RqXNK;p?UWT?l zI1zjXT=Hi?Z-i8r`o>@e(DOG_#P|$|C0iG9JmLHt;P!+;=#9+BfV4fSMTFWDHhcb{ zs#+;=5Uh^Rnx{P-yU={rZgWz7^`!^aLOKy)fT`*OQARmAID2zNUbxM^G_- z0bT_X^ZR-i`5 zlHe;qqu8eaRTr(&c{9+I=Ldmi->5;Y2Iyzh9e)lE5g|f-(K6J!F^MTXyEtA4(pOE&F<~FD4d-pqvwgkK&@e-aUU9Fs%~L5QUv|hj0HizCuspK zWvq+-sM@#w*P&hkLE{hfT~9mO8v?MAvrx`o#pERhW`9O`{@y^Zt8@mOfnH;P6VY#g zg=ldf7iYj3$cX_C;{7ZRWON>yQwVOx8E^)w$^a*dBaKc#yXVCT{;v&=2hRb`sjtfi z{J0wI1N2@27iSk3Hn(AC#R2PQ>)y;LH8*ZZzTYCTtIkJsO-|P%H1O3hb zXPgr(&N}Ga!J1oad=qH)OHvs|1`Y0VaRyQ|pgIK7EQF>yyK8F0ff=!}Be0O;16}ZB z&VVz}FAQ*|Im_Z~gU-z@IYj@mU{nO(PqFmVb@wg<)V-4;)IZhXZw8!J$R-Ciu5r z1RqEz4B8E^*rjsZ?Anh_C8w5;?()+A!X>Jg24Jhc8o zbV2W?;6)HB&ysMn=#EreA)IUu-Uua;bT0!F9??4q_!wBo5!OY8(+h#o5uIP#+Gp4A z3^)TNXMhvR%@Iy28dNr?b*R{|8dxR@wu~jIvj3zpADW{xsD$tLzy&ZXAmF zo}1?Qz82fxW_=i(3&a@Itkq3joB?N`-x=V9GAVczq?MP*s4izy!Nx4W>g8I|=hWlt zr687EU`lR@l|!J`bBHCE#SRt6{u0Z%COzss&?6mF!G@;1swXF{=-i=4H7?G8GvEyT zj{!~!JAfo>IcTAtALhj$wjKu-a(C<)aPnIQj+(xP8Gly+r-G3!d{;y6-{1#eveVy))np^brG` zB&Gy9xeN!*@(LRc1m-;wjg({Wgl0z~{Wlp^k8c(in4=mwiSZjh*8y*(75{E zg8mq5JT!;*Kx~IGpu7ASj}DrB)&GCQ_P3Kh>xaJGtq9mcMgl$=oKdh0eOEn6cM& zs*Ivf6Rs)WnC}njh9Z71$1yQ?M18Kx8Hmb&Hz=ag>B=HA@LFVjb#?2pTHvVqpUB@9 zZ;pH&f3Jw_XJyn8`;|C5(!gPhvKoTFTKRMX1Ao6T;=#aGSJ{sYc!Q!JOT8j7b7KAk zR}YBn?)T9feVV9z;0!ne{loxwlA4)tG)NdeFgfvU2{r=DfmwhC wnd-${!+~a3T*N@e$N6?~2AlzBU;qRE4}t+Jib~eb+5i9m07*qoM6N<$g3lrPHUIzs literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_network.png b/selfdrive/assets/offroad/icon_network.png new file mode 100644 index 0000000000000000000000000000000000000000..3236924f4dd90b40018cad92538b397e246994c2 GIT binary patch literal 39872 zcmV)hK%>8jP)BYqPU&cJ?HhvL=~*PUd-Xb~3Z(Ti<+BGD#*m zGtJ}>o`3%NwH(Y_Gll0o>dpbphtt&^C;;XO%DxTci)@TcU@s!r z&V{?N1-JlUyR_J6p@{-#zU0^BudI?x_9FsdG!iFH%0NlFEl z+b`W6=>lbdCIMV*OBpyOxcIcO9ja|I%wpo>Qh4%DF<~gieaD1lDy)gODeoXoKn&ro zfkA%xj#2;StS7w{p4RrxA&Jwa;lZqxgu{YUfINHB1989(u*FhIB z8JS3z*=2zFJlMWc?E7Kad|KT;dA^oqG})T`iJjyz*%#wR>@sKh-(n^?&ZlSlC3dT1 z>DjNzt}HIgll_|PNLwdM&;OR#=1qG0VmD|3rcA{+$yJQ2IR0-jjqHaO<4ngUKc+ZZ z!PO=C?={7j#sR*UI4FdtiWv&&y~Co79GmPU&SYB_=YnCfE#jJNhrN#biU=@i~*;Zi$^!?Pr*_SS5D9&2X|` zlU?sLC<&QS_FEifZEPg3tzFT!=r7}8i)UkJvT+&&Gg4*0CI{GFQ?wU53HkUJVus`L z>G}O)-h7(tzG@3F5i8cL$)-r!CXbd)SqnJ1NNS=U&rFSc!ce%w4ROIyHnlHKZ0$S< zja*1c3wU!8h~{-uF>Zn!|EyRJ5#YLFBsDNcF>Zn!uQpN+3Olbfxk4DZn^H*c9TvfS zZ4CM5%wrqUht42kYiaXv(XQ+)@C@BxwjzoAvFvM&#IbN~_?4XnW-XHPJx1{(@_CD- z@@cYPOegGScjdWQCYCu_8f}oxyfx>~1XPwZ*fsGuf22fFcj$F@XCR z6AF_aVr*WtB$eXrUd7! z#e62aqKzDv+L7>gL*m6n5QEK#0A-FOZxOHR*yO7W!(>~;HrWvOkAa=ZV363~G1*95 z(N2y_Y^~N6koO)_eg{7zoNDoE4f@_4>`p7%nhH=BSIo=t$c$C;8tg_2Z)Il!lDHy4 zTf4r~zvk?x7qP02bNOWVM3Zg7W^h=v9V8TX#IAQ5%rZ!Nwx9jVD4p$Rza~3LGudW& zw0~VVm~1nywWmQc4?X;>DhRf}u1eQR!_T$0Sf;|4=EeAJlA#z(8HzU9vB_354nK2c zzKXvlKSi7V@qC$WQ1ceB3@HDbHLrY}*1n5R8(UKsIKYAIybiX}OdSOuy3#a~66H+6 zWQ^TOd0Uf>c3j>c`v;ov3pRtpqU}f*$P6S$wx9oXR6C!wv3(crrY=xPv<$p5Q-g^W z{O&f5Zprg3ty39Rinc$J1cQW!s*2Z}PHpWF?-n`11m^WagjN`&HQt{njYX?DrD=J#ouiPl;S^My;9RrG> zeL=3*qpgEf!qYgJ%X_R80MN4c0+P4}$QPt+pE4X>mL~C)UBIMjFB5&B3bd^>AHJmp z@d0bA;Ca8Uyp3JJ6(mm}f&GyOyTYlgOh&$9YzX(6j0<)jG1+Lw;qT78PZM@NJ-=_V z9q9s+!Dwjc_a@uer$}3$COautk>5}kAk!itg*WAGA`ae97X1_pnx$hqROX=rjPA({ zt9}8Qy(+zhG#5TY4^4{#jBqbeazt^-SYkVZ84^+EgGw3cx@ER`{{sO`02n@+HTnU1s!Ts|rbII=?O!0X~Wu#5{BrYUx9#j10vGQrM-#ZIn zAnSofmd6)KmjM;+1lVM2vJ=~4u+3|-6Re`261$nP8;ppxg)frKj*HGDzQkdc#p~CE zY4TkHewZPC#@ZtRFNR_U(!W@=kz<415+*y7Z82|l?2^C4cBE^Y?8INz1x5-|RM%91 zqKyEW?0SwcmS5Xoi-Voq?Y*;zTjXZK6Pv+Vpa|e|jFb17@)gOLY>IKVd9WLKud#?# zbu5deYiqv>ppf?M!m%9w+Yl!$Wk>Pd55F+knBv6V6mJo?XVC_zpZ1z;pTywDV0iK% zamLQ>2D=%l{k@`%9FG{yh#0wxJ0oevUJ;X&yJw^h_D0@Q9HiuSjOWN=^Ar1`)1pmQ zusS;vRz6P=*JNL`3GuBq2G|fa+2jjfQjqNoHY3a4i#E2$YAwK2xMEG2Y)nLL@@d(q zwE$B=#v!f~AoW_J+pK5c_%}nGSCr-$umB7mEV8iatNA=O_C*`XZyH~Ub|xF!E^v9C zWZ&Vd@^LsTdx(-Zll`|9BXY+VldWc4(O-6K@{y$#eur+A4Rrwl5n~fr zzS(5yCR>wTX0P#U>(gW>{)_xfU0^N~Q2_r{j4y%})0;Rpae(VBCf_F8krp5sZPhb5 zNg>XKzfpj37Qv8TH!OHqw)m&!)zmup)=>H{KD~Gwl}xN z2j`~nj@Af`v15cZ-C}%3vq)A$fQ>_`^*Xy$hmJblO{XK}-1vN~&aZ}^!41Hs;`0U3 zAf3mXi2IJ3PDfMk|EW_t4XhIul5cb*I&vLa=VKD5@8nSSxuqTmUY*%1lX!C=*fZ^V zzN=!Rvu_&&SDl?20QD{-#ag1Q%Qvfoyy?X%nNIE|^l*D*Y-?0WOZj38A*~!JO)X z+hk?6?MrkaY+lDhgvRFdI=d`gK(qbgZ|Mk7m1zXz1wzH>kz*Ike&(q_uQ~!WW)U9c zuI#m0@xfhz{hPAmy5D}o88S0A0DvFH%IZ~76X=kK{(-9qwzwu=sm8_708Fd9hJ8)0 zN7vQ!`iz_c0F-rfYLyS(<}L-7ikFZlS+x)Lf@}w}3Gc=N{+4I^fQ!R^xvX#UfL}Uv zXMVwyPZV#G9oPJ>2INSc59JZ3Heo1J$pJX|*8yu`OJGK#0eVjj*qS4m6e93>X_a3W z7gadLG#gy>S>Z8pIEVf11)crigbB~TziR^%Rll@JaTD6yAB-Zgro7> z7DIrR2l)Lxrd!#V_j`J+sY6+8=LEL(H^8eN4oZqpSNZ*HmDl$gMCHQs zJU%#;rzo&&9}(Mq1t9OdWM7_9zqBN+7`;a^BI5A}ZLksSU1fHZOHLtbp{5a3j*K}H z*3a~Fd3<-}YM?gA2vGT~I*0J9-2OQ1TFoEEp&*_dkG07sUyG3&HgealGSJ&SA`+|6>-)8?wYzX$p}z7jOH^#Y^D7180K&r>UlQ^@*u_=cGp3P%!o647ZUwzOEZ3!qB<~s1?a-}lZa?3z$IA*r4zcIMDVAhol zti37IcWufgSiKQIjO&0iKpV2QSYWOW-a#35*{=g$4?;K+YVU27`7_0Xx1NBS(#qm& zcmsJ=S^i?Y4IX){D_`&j4WQ_(>KM{LsY>ssZEayACi2<8U)I_73%_igT`s+H!j-eL z-Tj)ap>UN@XHU81zZ9)oXD8{Fcuoz}=oeB}!I-%a3DB8VV11)P_R>SlZ>+(Ma?icS zrzF=l`Zl}d@r=Wi80L+t_AQ5|6~VZ%3a6N6gImm#`mu|y z{j&7_)mL4)TyTrJ8s`8-qbdS6&cVCM1ylS9F5z8OzQ-kvavUv%ap5a^5o+_e;0j=o z!$?HlAQU{0mF>G=W_e7+v$WKIJ<9te<(<=}TrSvU8X8A{%z0U+EIt1#WC$nb<4pU4 zDZ!LB+2dYNroQsg`Ts<0TfKty7H2NOmKd154^7oz%WciE4V3LSHRY4!wQUP%fi+}e zi(6|qglczS{pm8`<~KkdSxah+3@G1uhBD4?TLkhhY{*{~^&eYoYdgH{Rprr?W)0pM zmMUPQ}=3*o*S7x=wH;5b>NfCC^9#@P6v!JK-8%eDQ2>B_kIG%t` z(Q=isC>BJ|msVR0V?jPal0_Z+$MYsgwfFGm=@P=d=p;!eOsYyt(wx3d7QL7d`ezN{ zUUGCI6U2dyme{26?juAFu_Wwz^Js!pr+YDM^~A3B<63pzgRTM~Adf8{uXB>6cUJWYW;GJpoD4~+5nt-btu_#*(O$si~uer3ena3MvyB>mjZRRZVH6dg;xXcaTwA{ z-Q<`M)=RpUf;zdvHILXkHvk;@e4j@3B@Lf~j#C~w%boE3g(K&eP&dx?={yJU=>4lu zAeSeHj^&=X=4ky0rE|LR<2uqhwHS}eKcTC9{|1V7^SS2ss3SWU03R&i4&hll$+U*ZCbv&ya0@hcee3fGPi(J0E^nlV$9ZDcnu@0ysY z%@$DXT+TyP*e*CO{F=6{C}ZuXUNWv=tjzw@?AYS>LG-JABI`5OGbbpREm>#?1Gu)v&GKrQ~UKO z^AnW0_A960%7-J)w=Hj(j-?}jEiiUg!x4nP>44cYEhFuU)26*g8RkT*+R+!>3pC1Q z?71$j*0z8ym{KrXTn!OoV^H=r@$nxQKQ`qDS4Ik}4k*4&n4u$p)pvPZD<7_v-@%o_ zj8i~(`E2{iE}YTqzB+qwtyg1}VU08Z93N3;T#SdnQpLF9F?fp><7$r21lMIoTmzRz zGG*Gsk;y`q_SX7R7Y7tEM@|74RbDpa0Vvc+{(QRZyWokv4W`&-0sQx||1kM}l*Kji zi{IVwGY!9gcJUWO4;Rc@eFe-W*c2L^H``!kHa3`Pc&vMk6g|MQ*6p1UP!UUakbO(3(i?}Sow4to_YJ4 z{U4X&)nv>k*ZwyOjMvR)sM{|kRY<7A>8JmokS+Mo(y#Rz2ur-4nGJbgyrFZrfY>;z zJ&yolizWVS@Wd_#rr_EH2j9P?Jg-#7tknp9QkPZ_*z$T0t^xpftqti2Hh0-z!q53e zk_~PIn^(Zq>8YIt2P)O7^NKI{ZIt;Oi~vO10&I@6%Q67dFHlbrZ}r+zzBQV#vN#8R zy)3r48GhYwEdLI;M^UCvRPl7c8jL8;4ZucN2O@Waw|G^dB+UUYgE|ge)i-E8I1EJ2 zNSS_JaO<=O%lcKl46D@!kdZJ6lf_Y}_p|@4?AYel2G<6sXyZ~@{k*Cld$uW;EyoP2 zHwPfo8pXnv9RIH*eh>|o)kI{Fp?)Wc$`_iMX!Vo_7OGmH?a>3|z#Xu9r|4`FX!UPP z5MXHwzk^Yw#ngH4e+y<5ugs?FD8hM658UKR6jeA}#{xqo@+-8T;lNPjkBU&~B*x1+F;QVE^ zMwSL(xvZOizNyL=`uN(!vKWn z@8Hw+R3}$44_M&-%fd#mY)=<9a89Ry|048iRj8t9ReF{NPOW&hSYX!vZ{N(X1LljN z`1dSd*{=hh)dbQOuTDP~oS8A+vaEoG_>UKkqaDJ@`gL-|cxN3E@NQzWYMgznzuDN= zRYV=H6w+nr{Im@b3j2RHc1kujL#CChenqZeWn3__X#|BVrH5dBxHM5e;d3^SaN6=k zwuQ85?Uq>gfmL~FWQkKdtb+4Xgs6RTStHg1@GZUc!^i&Q|5^=3FS$-b#d6!O6+A($ z0YF|>$edvz#JdpUlqx$#AzX(2Qc4Y0oLs}NT1up!P{&8iEH!-AY4%)0Z10-%UUFUK z+hEw(SPEbRWh6Hm%kIT^3s)-1UO0OK8MS-)U#c9|WO^|7+F zfcTRt@>;*5Re|A>w6%+Im2HX*V1p{cxwM;e`^DWDw`!{}rxgj9j%k=$FLljS)jrvjybeQrg)7~p6dS;$mPIU`bRzU;Eiqio zK3ZY?hKjTpNw;f(YTgI1y5^>Gw4MW0-cVw=wc=wdWEF2)UsV_x4@<1mz>IG6MG?n%m%fj2-aI=EaJO$X^#8A72ttz2SZ>!2*NL#6J z9P4mD8(_-za~nGw8?{q_II|pfrcr za9nm+dtGf&fo0gWBTQ*VLjpWpzKmu-aEdz0()wF6?93%Yk430mH(-I$GqE9Oi-q03 zmUx#tU|KDz1n)juOiPYdaCKN#AQ%mBoHGn^4)56FU{|}m+yQGwL5ArVkHGy(1@@iB zOeK*OI3r0V5QAtkd~_s}IpXR;rji|Vw$a!@_R%DB%pgO_4!I68=NyeKffz)S<2|Ff zN@J?-(hV>*cS@NU5^Ve$vXw>EUb&TJEXE73-c1=vupw!4K5YZ5R}jeAltIIWGA;(r zUA9=M>L$EuTa#@eBiUJh1-w^>V!f`_x z4F?t&0~15`k*I;O<<1Cza)c#~ftii_fpPuLZFP9{5CeK_}_VTnKRrt!19?Arz#TwAQXovlW>Jo~|=_A=WR*QQ*qSn8($NZybWpmG)MgN?p%xuJqGg=t{9e;U;9BwSHCXy&LaTeb5XD-s+`!iLcsuQz@ZEiJXx0Q zB$N$qnLks!OPM6Ut$zpH+K*{~buO-7XX0Os%lPF-fGdhdCC9ZBvkbf>|4=lfYhPjj z?|w4X`W*sp_uv8>_mo|hfm;PMsQr=(KvtEH-Cr}OL%q+oHQH3LEtU|m!4ta}n1X8) zV))j^w8hKoogV>gbm-aOXiW>_Lo94EJgZm1^2BYio3^v%Xj@r*{>#;s1H3=h*_hJ3 zMgRe_DX2>!ZSb-J)Zw~dWtcXgu<4oj z7NCe9p$vH!v*i!+`;LCCD<2=bZ+i;rABt6dvxE1ai5e8<$JfI z7R%TazyWhG`_FKP<^Wlw0A~9&zyD)Mv3j&ygEN#|J4_8(kI#XFuDwFp=-`5B!V7Hx zR+B*~jSEq+H<6Y2aSgG`?}BU6bZ8Qo6W99nV+h#3(CB)8w;hFYwA0*msib}hF0mVfEs-)3wtmLV4qcp{ zVoLdJHL}&bui1KD+KCf~u%e9<@ZRo#DW*5u;HGHfSWYpwswnI>cER@61}BHda0KS` z7`WaAjg--)jMz@IrQwLXpe?S^&e56G%^`8*fcrrsu`!6Gj8!X;ha|8q&QKYaN0`OEF)MeP>!2y%VMKlZ37TzHigKO zvT>Z*S7E#0WO%9lQa-s)|4bP#moipqWx}_?uDS{sVA=o;jM;G^+Q)t_pI`P}eHQbl za!fg%Eh)>>CGke;E}9B}Ew)ty=rfX4Io1Kfx7r#*b`~L=54L&7#V%jA{{HN?+|lwu zTid?fI~?up%%v4N2AMx}AwU82-osJz+Idx;j@29>pFzmvkL&iOwb$8n>1G9xdR9`N zHm90nUG;W31!Nwt$#!ghT^o!I<|MLls(f_W-c=i~-sw}Rt}WBGAQR2rL*wVr*m`A9 zrk7U(kjx$gt!Jhgxykz5q_#e%fUI6h*T-cB-ET7rgp97<4FIQdbK~%4ir9InP(WT) zZ!a)hJs?AtO=yqhczL$bvTt)zXvw_i0C~qkCVyPEA2L*xVNS$&OFiX(C3=tGnQp-V z0%TLMHZ~cl?sukT>om})eDR^u00gL}g1ZT$h-4YiQl6%6T4r9Oby>FN;u*qjkYSAQ z_U61!OiyTdU{A^CpRfHo*o0Jo!q3BYWnTo-&zTdl;9a4TSAfR20NWj=M%j;ZzB8MA zp_?LzfR9!PTb6WrQ~WwVlUISV##a-+>*Q6;q2!2oZ;g;P$yST29cXo?odWXo>oS|h zS7W38`LYR7HHdabjc~5X>r4n?xqYyl&O32 zcgsSA>+&|LfOO^<4%=>{vfi+@5KGk73e-976mV3a-v|E5K(L`>Ruyx#=YTG3DD;I5 zbpGz9i%X?+wrwh~f%FH0&8JsYc{X|pKmlbzKokF<@Y9T_pH)?=1Do^;NDpm51g~}d zzPuWn0ifNVAQ`>$%QY3D>-@egqRUsRfHW);_bWBfNtjs%8o~}baMdV{%mAb`)ihL6 z7odI~Rzd1OIt6MJph;hciS=hRYv9U~<&zRo@6$z{0U*-;4RropWMn3EoxiLZb@A#7 z(B4*;Mh9@rliMuPe+bbY8Ah7{K>BgSnNwZ)8GzSICCoVN_BsXHQJ~*J?~3gGLfZSQ zw0%Sw0A$G0CYs0VkG%OP^?i!41)v+TO=J5lKBx2Bg)vfqI+Xuku`b)9Z0A#lcgLiU zzjMKVT}&TMw0&>>2(SuU%^0=eCMEs!NhfRrP?=@6#EB9(f}HzS*si>q#aS}xTypRajQZ> z${?m_mjg#3XNxkPM``oy@ah#PtBk<-SJ!)Xvw+WCft;$c2b~~;ZUVwe{^#)=ZgSXJ zYv1gE>rQz7shxLcE0qs)IeVSt8KhUlk|09+dp%r#7KyL-y9D0r0MK6kWkHP2e^mtW zrJ=;?{8Fb!%bzYx90g=>A*i((+O#|&h|ym}ba|KHN+0#TW&k*okJiZ}7VU5lLVZyS z6rS?`<-VbXSAsJg&hwO{b0&>)6rjFJ8MCANOcy5{FUAyZ%1AzRWL5>&%&5R*sYJ6{MumseK->U}{FRoYM$vwr8TGOB1N& zKzq0qn#)9_`cm41%BSq$8f7K`zuNv?YajwbFh=KJ3VwHJR1oxJ1|c6Ci4mTF=Ug#> zJIuHW&@QA+sLU=)n0}nLq4ER>u2CMT!>_WB*WLt#Sd6pYo8hI^`DJj5)%iDqXOzy5 zu775$3Rc%}B@HvFXbSlvwrN#`CG92Jq^Y~7*`x!goT&}`j)M1DhIr>FXhwN+7JkP& zlgToWc}X_yaAJlZ`m0SWj~B|#lpp*<^FAE*qrPEg;;Iox`KCIQF>k8=vJ2o#yuACl7Zmoj#ah_qMQ#o5l;FcBjQaEmv9ccW*^^M@19f}37%K8e$ z*UC?MUjf#Ip?ERM8?oJ-2H&@bmKlDFgK=jlPBDL(mZg^f5cyUSB=i^(TAe@EyZO7p zQLXc%;hg;j7u@+p`#x4^HAKx1$5n6;-1&v1l$TI@C)=e!{f=<6OCC$x-QoHnOWRU2 z_}xXK|FpdX8E&65C6%60M0rz&fVlN3+*JYjds(4%F*`30#WCbxqA$K7$vq05^6?4z z5QTPl4?KUM4XTAlxt|5A^u!Y2XIIMolYsm~S>Y-7Sl%%dsdKP4JcA#X!%w^a8UKa1 zv7+!D+))c!UX3WhnDCORbd1hF8~kMC4GwTzoJ}e(M&}oPv1UKPWseN-e|=q5+)&@| z1n46wV8bB)9zOItf?w&$*$=TdqZ*l+8J%bfEo8L{qs^-?q~=1Ti@@Bbj~nGjOUo$a z0Huyr_-g$MeiSJ;KNt0jnyxy;CDhOKe+7`ic!oD zuXFNoFUlXte!n3XqrHzQ#E1`9FgP7T9+d?bIp1%A+8McH?_F)p3`DkqYm_h67<{Qk zp-Zg$0U5{J(Pf$JAmkUWa^hPq1jCSbR``hq-T_`R15h2H;56uyLo)!Jebbw%IpcfG z(ay2jo&Wb}Fb^i^HFuZ3G^3JtwpJ8d*>?8K(<(AM~zC6`C0M)Y>DVU(p^pXJko~(;6_mW(G^0Jq^8zOwez3 z;{L(5Rx!=-_?__kp<|v(bGRLZ!RITDJQ6i@gqys3p*5qBQUt$I3MX05|FD25g{RPJ zj@}Fa@cc|b1OMBhAaHthC`KXwWrbtk!=yVux*f>Y3l#84w$RQmI-QbX@~cvQ8s8Vd z{kVW@2Ke0&iU+r!hhh}+2fyhDCzYF>IbL#d7%bV8Pkm{IPbz?^te?;E*ebX0wM*kV z%qwGcCarrCPfI7om2|9_VGZ%q4-17jqEXA!os&Z_40%_A+pLCo*Qmo?GgR5bY2T`J z%d|gO+F6;wX`bFC06UM9BY2d`yi&1)ON%Vd^%qVP{*nYuK7~|Ax@wcRN2bR(o;x4c z^nPf4Yu7d9zYR{yhU%cq>sdGj4NUOajxwDeTCQCF{j#aQTIbJ!d+$9 znRkIoGKO@1_^iw(gJi3nUy3F?2;QsKLI)6oyef->47edtvxH=pyy&EQBM`_vvjHHK zTR#64`2){=jZ28U>jU!#p8LP_%vYAp`_3?(Z4W@FmI1dEFaMc0WO0?&J(^ze;qrb3 z9ZplgNEu>7`Bc*aFqDrHYK21?sg4N&gVP=4Um^q}pI74y1E(Y|NuVLiRd3FhFR}gi zqqo;hU}cSiKiv)=ne}N7O!B>nvqI`iS)<-fz+FQK8S-?^c8?wJJz)#AZ zUy5~HK-o02&Kn9wXT3ZWqmX~=!m-cc?|d?q<&jH(^~w@G<8SlKmuxmh-EEc09qxk% zj~DyoYdQ}+wKM?^2q?Ojwzvw8&Y7(&{6oo-JTG=#T%Y^o6P2W$9sNF zlFUScA4hBQQNp@j38x1m1AyiYKuvBbVaak@&ER`Uak?gnh*&@L#9qlWpD`P=QPmr_ zMkj8O&$yWztrs`OdPd3s5Oi0v=$BDf`x$=GMH|QGC_DAK@k)dKg))yQaPXAZSAD{k zKAFZS&s7RsU!j08fRF(|?VlR-QI{E@`|l)mAAtt_w0}{IIrlck+C}6<@9gH6#vLK_-7sDRGsQlkxLDb6WM{&Ts~B&uWyl0 z<4oe?zAn#`@Y}7<$dryA+K&&9HTiLjd$Xf`oq5PYsSI27sa@|T3F2#BE6FFo*Ui}a z{6c3n@@d}f{3e|C^Wl=^fs?E(lg_6Vg4Tw^N8VU_tri&toV(E2d;JFG(QJb%U!sQ6 zljx#$;}v~^Z%V4`Bo(g?nqol{;xIW=7p?E zobCc`v0ySY09G9|JPNGYu;t7U{CzfMPAVM@PM<)(BWGx+v!~HO@=V}4C&xFkEt!uG z*ncG)e;bg0C@cJA(a%Fekva$RZ{C8Qx5I5#sHi^q(WqZ|Y4*`xe^49Y3U#-6;n??3 zMm)8EekX*2QIWpu+$&v2s9gCD-BQx<@&OW?uzi(H7B}S^)B_y^solQvWzlGBf)|0~XW{ngJXfE6 zZC;sP#Y+H{Q8X(cq=Ro*Kvb?}HN!0MlI!@O0I#P2ST+cxJoAE5;e@!;zHQAu_6=PG&=vZ3Ku>}(sp}c=nRbjYZI#~f=1=Q>o@RvI0yovp58hD!9vJ{2e(rE}h94pF z@u4X2x)Y2OLvf1vH9J+mQGUJXL-QEEAJxRu#)4n)l(&Y{y67Cd(ocNARocHS_|XpQ zD*>u6^Dg%9kpZAjd}E~oWH5Unwk)m)3XtCu0C_5)8sMgOjRnUKv8hZ=OA5I`Nqj2N zFN;Lv8PS!Xa*v8Cp9`KbI{(>lyed=!_?;ArVaUIIF|M?sLO@nR1$WxKL#e&|vF|?I z)H-Z|L+~oHJRUUn<@mUKoWlMr$oQNBP80~r{2G9Np$xt%WuB^q2}e1>{Y48ehjSl1 z7s(xa?ZQtU0pIVHxjd8cAC#8O0OSVQY~@&fDHQBBznsIl;HEN=45RjrDI2H}vOt(T||n`A>jUjLt7*5AOVZ!L&QSaFZF2 zTc9(1j!iop<;J4iTANr7@1Nyf{ZqidHRr==*WYV9IVs%CP6Zq`zB~qNTs$@GM(;?A zZzPVN^ya50(Gb$M-h>JnhftLd3a-=+p}D;!)laKAZ4rpFo@ZI!&0^5R_xzUrz09;Y z~A9)av;>!0EV+@2!Qg$$T1!xZo za{NF(PI>f*u_pq}IjR?N=-C7PR7=a-YK_EQrP@Gv-5c78E(3JCikTZ}M| z6OjsI$n6q?U;*>X6%@LpmK30leo?5W7>6rp6%TUT#2^UfxwagwE&=jjLO6e{xW5S_ z)?c;oBJ#{rTn^5+<|DfO<`tl>Wr54DV|%8qo%>4}Cpf={wC|Ut2gKh3&E;+LTU`R= z!8Aq4A(|DS`sjt-N=zT?FU>B=zdu zM+P9d9XQLY<0|(LaIH8V{N`#ye2YE z%=U+F@_oTQHT8?g_c6H6>%%p;lSM3)lt=9`VJ1!_zIRdq>aQzjoV#DM0+H%c?b&|D z8lH=?e|L7Q{2TNinVjzd6v;83zv9g<%b;;07&UR4l5|Lan{ zumT9%UsW+yNZUCEad>^$k(ss(=CRt--X2_BvZQ;tNhx0LQW78A zn2j7hi?Cf$;Pn8ScHV>;-tI|a%VppCCgn%W0T zO8o3b8$YWgEhswb03gf|Xg7Z3PH5DCK+($*wE!LX*eM|A_t>Okx9i3_O%q~K8IK~E z{LASsbP7aMfVTV?;B!ZF@B;89wB@ZM`_TLU=XFH;BiU!_>;lv0m4SvZ^7Yd|+%9{k zfXrqOmd1q?u{-~)O?3X&s#HX5AVhh#+nQ*d<5m@*z5bwqHhXc?g>38+pja@(+>E%( zit(Dq{aJ@5WQR3L6_Cy!v*>NL)!?PTzM@dz%ln1?lP^Y>uTx+GDDe8WI=^T)Yuf@+ zc=;rfTwiIAu&1|Ow$A^AQb7Kt_Uwu!x|z1Wf+C(5RBM+2Cbow6f0vtVEaU!; zxG%P}?aVp_tQ62XNzpcw>36MN0+m#6#UtZquTjGG;duJc=p)tT8V&~KYN+UFRt zoV$-PlF&tzD8Q)u8yR_P!l@%&fZxi%>5e*}ojcP7cpGx~&)xmu<(^OUhs&@WpYIVSq zQUUt@XO#=S3YZrvV|u~0J^&y@luvAfo5Tp~RV!Vl)D+kw0-;yXMn4t-*9o%K0RRF1 z4BI)J7~31G{ew|^m!0JVRbZJ&TzTI$ZYfm>M-_yp_YGEBkd(tSdj9( zhI0HemV;ni2+qkCGdvVbvIGFqv$9RAATR%fr2EK7iGHa>Q%7&Fs6$DL_MQmX@}-}s zAr+mCJSh1SF-vcBst^h1A2{%ys^GGNP*#BYo5P_F#dK+93OzV*zvjrp)m)xFq!%c~ zF0LhUw2yL=1rAp^^5~hTR|Aum5f!qzPaTryr7=_k_aRR{w%ODcBB?zE5auz&>|=g| zYoGnK@u4gqC6SMl_=IQRG@DPxE{~o9)S-N?E98^iTT+ke_jn@r2etn%pz;)e!k(p9 zr6Wj>M(X_M;>ox33rV?W@VgPVT}0Cggmix4dMWi7V|KYlL?Pt=3#fddNM!~9nP_K! zI=>3Xd}ToQXpRrb#|7*!48i<^~o{PZq zo>)~A+V(W2up$Q z#UTjZ0|1Vf!tsJ3&MWe&+~COL!}q!TvF1M5vI?vV%_lg{2E)e(Si%q5_8?k8*dUn3U${j?cb zMywfD&;%=BdB1z()hQ5X0SG);Afa_Q8y)HyEikz53)XR3cqSb9dg*Aw>f-DapkCz# zoSW^e{j9X>70%bdB-Z0WueSw#X8^Iz{>LkK{`nC+YUc+(+6^ARW;;1@(N1oOT~a#i z)0#fuEH5U-3Rn05I}ZSeGCPjcmLld!BhY*E#|rz=ULMMETR*qo?KZ2x*^%AJVz2X* zeSBCMFN518+j04Ip1LB)4LDfI#fhcuP7DCDI!`6Q^D2PWRRJppxgX98mnU~Au@#`6 zqb)+qabJsimg&1nh{*W@cy8}P(q{mOA-L-ER|J-qJpSY&gpVy^JL~7;r^{2W0CoLx zQZFvI&`Hs(YdFVP!_X_JD^I6O0EnNgBj*T;_FC-dou3lO0*@}VtN;!E5-6M+n+9$F zIxQb?{s&l5{#OP(Kjp&H=?n&VjI;kk2%@&00E%*RNP9pjYPvC;qkj^*=(Ia7SAcqN z;*xJ$>iu`+EbLR@E0>P4NJu@v(Yjw-&j29&Ms=ny04}YC3&%~tirx9&)pdTY8q>p} zPSykMemz7Z(nZEtk4X65N4DENvessyA8cJ~)HkpmDFBUe_P+%ombWEaXBUZM-tBSl z{XjmV+fPdY+Q73gvOckSu>U=6;N>3qMzX+l4kDizNeGX43XXzZ8>|KZh|UMn!?kGc z26IC6N%w4{IpBCEvGS&0tRNo;T{#wbhpVRmZ6U_VDo=1R+JegZ52y-``u!yMS@mt( zky8G@pLUQ(Xj+|L-b#$w`Q<+lb)8?k1;oQ!A|7-P`EEu0RTQxXPz)@m4Gt=HYzKhN zDlmMLR`tzj$aj|^PA!VgZ>y7<&ko360qRTI!<+pP>T}Y;R9;wvt1MP~tlp!u#oKIh z)HZAix|I!(qs@~PT;+xh{A3`R-_gH|`35e=ooyNl(7xo7&}(_DWeI+4X=h`$nvIdG z4Si#yx;(Yl34lBRh}vViJ|VToXz+`9y>|u;NoAxjs|e`7j5K-kOkOFLm0VYr*-nIb z%DV;SkY%gW*e;{IQD<+F+sF6ezc=Lw4v~0-a+~PWYa!O6bruE#4Lyc~K4GhsXWAyjExWco3;v=4v;= zskN6!IV#q>uzJveS)@@ z!*jM?Z0%eGsj|i28*F`g*uB5Xw{MyU56Kc`$*6A`Z1cf;HP7;X-`0nV9bE4BTr;VB5FrA$tT+$DQ9gL08sICRB&*cB!r@rG zbx2u57r1MR9XooJo3>CfuVNkln0KqAA0}feU$fz2;BCHfGLogmo92w!^+BvmfL0f z*1u$OxmLxzK3F@iF|7CGZSln#*Urf>xyPGLA)~YN7BWD2j{@zG!(FtC0GX#l2vy|$ zyareB-(2CtH|e%AZlz}>@l=+{GyY4=L=N=KJIDsDg*cEGDbz#NRLRE~T>nVE&3*Eg z3Ky0N~5SXMdt;t}4YwmT~`fC`fk!_?Ey`ZqO4Ih6w+ zF4N?@TBOSA*jGk>3&+(}Bg(++ruI2AMo^66690i0ox&@B9~FIE5V8(?rM4tCcc0F3p*x_H2ri~Q-9IH> z+PjR<;JQV7%RM19{cHt@*`xNm-!2tk3J{3c9IPDZ*&Iw^F%z{TO#voRTVG zU#}6|y25dedAtgO)w227+V)ygQ^0f^8;z0zU?_qPDqggHiM3h8~E2-Ib%tVICEI-UMuMxQE6 z8@TMt=$M-xa1{j-w!0~Qoqau{$-_AyIOsn)-8J#Toh23k7~WBPT35*$gOT(4-Iz>T zZUrYlA#L04#%4XNYby~xA|^cxrI0)CjJQ6Vz4f>nJ-hf!)gsQ~!q4T*Y$%x{ZNg|A zq(0qtPgjVnjI6u15#;pU1F~OkW}&>OQ?Z`frZ)NqxGfQ@Nw|o3!ON74Z6(h!P3xM! z@{NHQPvVY_qP&BAe3t_Wj+|@$ITQq3kAicU_WrP^#IHQH84-CU_# zt4~k?1&Ha2jefE0_hV3)%!J~2&REg%IT5amxdsxvNBfek=o>snj-juw(0yjImRb!8 zAnDkidmhu}0dy$AarGCl+pZ~iYlWBJ`u@O)7x>^~-6^rLE46>$#XQ>Ui8ow>5bh_d zWr6l{JM^cqf7O>XHdd`Zu(8La2W&tfS>j^qT^ddnIzaCyvu?be%B)E4X-lD(TgXGW z3DNZ^o<42Q#aBBQ&|+pVKEFL8=*L|&ity0fP>bI+cj}@1NWi^XkDxpZHRhEr|1cuJ zTWU4T2f@Tox<(88uBP(yQD(OBC*H+5;dIrVD>*;wFX?KFxDFSr+xBGRTepD=gC5~} z%UK$_)~+jt9e3wHsebAMe6=Kuzxt36^#L}Q24vA;rDKZmmvW>NJD)jcP*OBXWGe@yWBT3Qa{P?rrGe$&i*+tl zD3-Q^X7%bdY%y=|3z#=hv@2ulxhUvGXF;!#tkfv21um_X29uLBjYxms_ndJ?*ITE{mkHJgE(d#1nHVVbIJ3V6(L z@m|dR0N2x5Sj4X8fETSge9=jd!s1A8OzVo=f}8v)g&aGs9CwkC(AJ(9K)3gN$Y01M zHNMdRCbc+n7?x{nl*pAHdp`%*c~jS;&7)dvvKf3s3@U-O#P(Ly;MA`Ml>O195I#h5 znhCJ`C~D5dbk}lfRi!aTtf`qUbvc#kqUU2f7%N{Ik@lsO7oZ|~1_Y3JW-cz`j9ic8fYz7{V_ve?t1>d5 z$D2;+D``w44V{Gwxh947ff)z=@nli}fx706uz3g1wx<28x5DOFbe`Ivkrs@yZ&m{= ztw!WPayydf)gKtq=6K*|?MvXX%J~~gP2SUoEm?%#CZr%Fd_H%q-SVJ8^VQj(0|(^s z9;+Co<-!0VoRP?v6)IW?PI!nCSbS!!&)#e}S9Q2WYXW2JJ z45zHsK}o28B`UC{4|@IK&hXL@}#+blU9^0fEK3%}RX_O{FLKYKVZ@LOF8SXiht zF2CxH724B)dh2W2mzy|w(5(ePA80KkHwHzSX85s;!iAr6uKQL!Pnn%w11w@~=hxs0 zgR&`s433gP6yfW$_*MVg&tTV7A;h`2VbQ4CtGF`u_2Mz%+vz={G>BCXxZq$F!c9(L zoBD|^d=R#UI}JrC4Q9(|q<}0Z3^w)vO*@lV@yLoKgInq}NG6LGg1G63oC;|#WbWn3 zdzv<+c1^0jKy9ao>k(lj1*LHj*KGP-q+7Z-ID%4oF4{iGed2Z8EY%O6#k&Nl^$bhA zumo^BPkXITsW5|$NiRmVmy$UG!ZJI z3)Tzzkh2IbXYp9juKWlm`_Ew9763gwwor_U7D0=H$?i}UDNaX0l6_Lw8rS%f4cp7`&Xe5KNbW7L(!Y5XEDKi8dOunHjzv8ABi9cyHL@;!(#BCD`G>Rc%j`61 zsohkW){3XdmHu>sTpv-VfZDc>+p%N)LpeSohLC5fI}Sm2@S;ba8{#t6C5iFkDKp?b z!q$#4#ndT6z1BcWphkA?AdRuSV7gthe@oeldZCkcscU-l*&;UQLWAV-b@1*7VmjR5 z+9Uee3rS2Sk;;u8X6EaC9 zPVKL&{gfBgdzWl%! zu`OZlZP%Uh+3XS<524#y48Uq8ECZd8&OUEFmK2?!Td-D=Gyz~D6&>)~cAY8b4^8er z6T9!enPG~hC~^PN<=`eI8MV&BaY<`UQf!UWvc7i9Xd%;WBTrKOY*6IcS`H?xX5=yJ?=)UdUI&_VM`b@&~_s3uqs=fjic;hoq z(p_xKG$d?fAYCYfWm%$ttTDAP7Iv8M084j||63QOl#m3k9pa#^@ju()q!u(b}QbR#(d zw2iL%IS&Nl`vQA1cd%qjtv0f;Ca-0f9&31-2oU9c2X;h>`7ll_u=vXat!Ni}rZ+C< zW*EiweDNH5(RQgWSKthR@~$LY964hHS8h>rs3iDstXV7I43)VMMAlDmEx^YtiMS=U zDbCB(_IpzbDz2>#IwR?F%zbLV2kJ{9fP>M^e#(AKkF8Uqw-X9rdWbV3>NP+m8#BbF z`nRrXwjPF~rq|$~vEjC;c6s8w=wq?^oBV=t^@^MB&#<+JkSj9hPqc}*sj!GkW8Ax<- z`(3B+gKtR208fL28RplqB4eCJr*=PQ@2wK7o~Sxfr3&u5MD4zF`tjw11I8v;$rLJY z95b&pU*?~D8f^~C{j}24ljMBAWZTfYA0z?_;WT7B0r%=isA*+A1~|b+*e=U*I4HE@ ze%VwIsV!bldJ#Ubd4Y$QMBd^s-q((Obn%Cq**Gj_d&9o3G1wi{?Ucd2?uLEMXN}KuPwf66uJ(`8(uAM)NoAZ?s_iVB+bkM00 zS6gd0kesxeBV5I?#z%JXC1b|BECyU*#s2KT?DLe1Q>+AA6+kxycn2|7PKlp3_)&k) zyv-{!8&4ogdv7z)OHN&1TqYB~BldE^J&sXoSOOn)WvoPBdj5w$zG&=V1TS*&D=h(o~Li*sPhTf`xpk(?X2)MZHemsF{S3M7T&U19J zFiwJrH)>>SWLG_VF~=B13`!Z{@ET-2$#SIsxU(UGSLj*LkjhmIH~D3$TTt*kAQYbu zSCJJ(>KKk~i*>*ucIY=FFWz=bil&Y$pUB7=rbnE*5%RFX0uqv@fFMN)PB%U(LW^gR zvmAZ=r}yT|l;d{Ypvn<9ZfPry4fu`(A5{apug$}8BBra8)@O}O`Er44KvQAN7n2TC z4vICi`4bg-{7>S$P=*NOsj1Vy$_65;bc*}WIh0J-T#H47b>miA<7 zNQ8|PNrNzp>ox(-}asH^9`;!A<3+|fJ(2BrhSRvItulh&^1{L(Mh&KEOHQ19+;}qgF$3*Iv8aUyLhL8xllwn~$OCXE5H;G? z{#2)Hwu=!8?F;HmpE?giQ{;NidGI*kTOcOIQJO`M;Ki8+wX_R3^^$O+G$%>y6@zc; z-$ansrf;(=En9sc3xAeBK! zzEn<54Urr9Y0gWcZrz!_vvlN_n!5v}EOctDYlN>*qZfj~Z<|{wWd?dWPzveuNpn#)M?i~>GZB(=Jr;L#O zW#hhK(5Gf7XKGUb#Pg@A%=@NymbbZT0e1}fItj!Ji;NmH$<0jqag&HQ zVIfQUq?G~8O$j1|o=WDu5>8lGAz~vi-?~n9F*Zy8s!_VMCkCd}Kr7!Jwoh-t+mmf+ zt#((E!`(jyVRtlClo<1-|9zJ19s{PB=XqBYG&0)@HcH|ZOw29T<3*Q24$6HFBP!>? z%^rXw!l#t5K3h^2S=#Xmn7@>FNKPi`-^87@TD!i6+D2eQ5A#p{dFgN$0U;`tRTsz@ zPV3A>e?MFbxZXP1o#B1rjIfHezJJGZIUbW9X1%qbeV_eAMBwfFt~%dW!)YxGv(n4c z+C^XHyHe%eU9pQ@VWh*_-jWL=!~dqCMU-$`iY2YsbpD*>-odf{3;*mlY*W5N*fps^ z<0*SakM(@5ELRGW%;LE{k>PlqM_BX$9EElbBCPe^Ya*@6sU!XtWaF!zp%=RP`mNw3 zJ9ImhjuqA&+x*x=Z2Dma#HAc`h=19PVRQn!#|5AiWuBQS^l<-VXpW}rO{>w^pm0tQ z)_B*Pj#3bVrWGXch(xb+w$%UcwW(tF%QbOh55&n-+-pzbGS&C{Lhlo~XgD$iv+jNT zRQrbTdctqyrC*(#ebA3<$+a5XR>f@4p#yWG%|hnLS$;BLv&i0Inwyi8ug0H{6N&wz zQ`_)cjIg==@iH|G%Qpiu6CH8m*jy(-YKh?BGO?Za{YdcXd^y5(%8-RTUR5x;7RZko zZfL2GdPQp$C>i&}mN+7!F-*Dr>&c2G%nr`uU?o6*Sbjs+6 z1$hvzkdGFk75Xnwenzgi6A>U5L*I2$oIb4Y+vfo%svIu$KJ^Cb*)GM-{at-G$=9dj zpeZo=KbsBNo@?qq*J%?e2ZXz2CmdtLqXZGORq~D;OQ`$2OD?8nZq!c7N4xQt{7@m%8k)$(IEyH22SV`g-R;F0AbtuddWbz7}xG4!qx3rEA-)QyF2G*`Qg zx)S>hFr>}uZgrVmM>JR5Q2>fpgPDKlOuY;-9mCyYZt5&BKkkJS?M|#ecR+oC!*ltx zJpExV2KA5#F4ck`D3Gp(6f-|aF8Pi?HQyW6)cHlCUg84A>@8!$gX%@8Fj?exT#Oe9 zMUh`OPc6ozPOwC->j%rkz+?Pfcxd`HaS!m`6luM|9L4gI1a|63?M902{}Y3l^l5aB z{rjjiV(R{U#vqE|^NyQLRJBbFtj_$-^m&6Z13*m7;0&VJ%}`ZNa~#B8aUt6e>E!*^ zmA`)xunKkR)FHd;s&$@UthZoN>2sunsr!RTzpytO16VU5;iR*_k6*Rhj*H2$zPZ(T z_a3vK5>C(^=geUO~-*X?vAQ#H7n9hlCRy{96)2{z`-;f68z07ROn2u+OI~9M(R= zu`tXXD|V^NC1FE)m4_Df9&wnJPG&_-gAPqM`E0F=+La7|i|4gr`4)yaS^~ zy+;p5pxbTizqmu&fud>ljRNqOFto=5Usxj<>-9T+0Y-^BrG9Y103X5mWSR21`S(M+ zBH_|uqA9Tqi+9i|-^|54a-##yDF#TrKoe%AZOp59BeOV8`d_)K1)zu|$MNv+uz`Yo zxI0gnfhquLok8U{z+Rcfz1Sn*lJGMv8wN_`oFtzyY10v(5-Eb!oRL+*_jh`b$#fY3 zv9o0IVfFQkkcSs_V|@Og$IP}T>Qvcg6e>_!bBBMWanR*X?&mZM3`Z@ViNLdJ{`!M| zuEc;{GUO~k5W$3A^yBJ>wWVC6U%b~zSx1~fRXA8m!auQZuR=al9%$Va7jbv}*^`CB ze7uCCSO3nIpYb~zPW@<#LkFl4!N)$;h|&@5aO>8LIX(#1<6HfDH59*D|HD9AYy^vk zIy3B|%Xsn`p?m#%xo9G6Qw44);FM$3{e8isOh7X(p8;E~tC9Tu+=3Tv%K8(ToN{pZ z#9QNx-M$2OTv(YUph0+RDE0gyF0IaWjsfczAUAMV6gm5Jm3ti$_H7p~h_AGO_3%)3 zIRXDy)4Iub&(;*BU@N2Ub0&uThv?V0*!me=V!#g+1kLw8<-#Afgz@eDN-#zUdy3uK z-%0$xPik+uw?e^J{wC~5Fgk%#VM;LQ2qvAU)V!~nbCgFh(G@`)ej$+d>_Y^`z-6vg`-D zYLsPuO|2j)h+JGa%3#vT9vu!P?5m*4(WD~Hmp=_9#elQxi5?KKKa9SB4Fa3ko^_u1 zyFib9M)Uu?YkxM+{syyoE4TLp0v1GEy0BY_+OuVm0ZSQXW&d-${SDLAl7g|Bq~W-@ z6=dUi1Xnw}#tH=r>GO^Fy6T6KO^aJ1Vwj5M?99_9_V^(i9{Zk)2SNdFaD->22(z-K zYe!fQj*{sswzI4opCw^H8d`63L8?DdsJOkWTh6st2hA@<7kB$%igl$j$E2D$gTsVO zPRMnrBnbr&1Q6)*VPmtd|9ZHB43oGtoN-JC`|B-QFM1b zZTv0(OGheXj9l3=MONZ}Z$sZNfsJ)`Z6F)*5Ye-0g$;_MD^W2hocR`n*uuVQQ24op z?!84epIQ+?KrmOl_!$@qG9dn_5;WMvuxgqYr^>XdijLRpI?XTzm4YGw z+-9^LrVV;f9-nU|UKw1LAL`Urx>-B8aeH8Rp;Lwj^7Fgaj#6;FdQh+9I}uy~@Bnu& z1#`-?w?OoPKvWEmBu2HqAbrWRCxJa8#{wa3cwxz~f5 z^nH*gU(zl3eQZ98ZB~IRvZc5mb4U^mQd{rJp5pJL@aVxM_}{n$!^Re0XS$5CGn}Br z7W&4aELw2^@8E+F+wn%;(yAYO^Q=OcV7h+}`gY-HBF+BK09Yje(_=fp@cOLtpGsy5 zi`B6D+nj>F1m^?i-^?0W)^+7DUV^Kwxi4QMEccZEuZK9Q#+qKSs}M<+pveRMOA(Mc z&UC#h$*$)2-W`?cTJx0EBS$nuTgSet_jKPg?XF|0-XGUY-H?9rsAQT=YMYLydig-Cz7v=9lh&m?{|uHdm{H zDG=|Dj--fYFq2rCy=tVv4T|`9z1Vh)cLbF>&7k`G79vO6+)oA)ZKF@gQNjyKM<`GT z4g#avOb}NI8ZFBLw(*!6HWe>jD3D&jyuE>dO$_`}}R}T&wprg!vE$G8x9? zbD%7+`Xd{lqB>f?9&tjUr0Xr{a{Y7U-?7TS2JqQCG<5tYG_`=;c|A%9BPi-}a0YMW z69x8@_;sHkPL2vLfKjGP+?{h(JYJy0>g|ib^q5_PRXucG{U@fS0Mo@VyGF4mLDR1t zIj6xnrsozZ7efk>Y@ZeYDxa<~4n>v;@&L^)?BuR{DVBQyAg>IF~{?E(q#a_IjB z9m6N>vJDTle{nQh4UwXKZz}q~#&DHj25r651Bh35a0{HS z1wcZ1{!aR%9H0b%l?vt`ZDpl{~c})@FFztK_bu=qon8Cro zy7AD>;-B}`rx)!xjT8T&4>DfJ06*4}lHWPxjXfntZ zc2)9`)b&JT@haOG6-t*iegJ0-_?l*) z(+@L&kRMC@YukINBskudD7!KM-Z0!=w_kiT7u&l8nwOzN)CGGRb+<%r)5A&Z`zxs)o_?@5^ojt8m0t& z`ri`>*$ukvSE+9Nc_>iZH{-zozT-}5D|OlDy*O|B&L0Y#_+#=zgHDeb6o1azvb`^o z0rI{kT;A_qH$cx1Yy<~11he0xfbKrEN;l9{M%hOVwls_z*e@v9;CKSCcDeB$2*>es z=10F2R7-?*=;3q25|IQVFV#u~Ed;$FlLUN)`_+GhM}&lMl#t!4-esF?!bhkkI19{I zOwu1jK_|2{I@gWe6$$o*-KZ?Qs@Cydd9;7U0Hi%SpbEzW-zikRW9n)BucbE$8^QR2 zzkz|)4@Lxe4YN?g$`T;@X+?=!WR!KJ z`7@6K2zw_gP1T#(CGaTOKFi~inrAO?m{G{f{^DRUl-k%_hLeK9~s7n zrtjPSaCku30Jx&TdxU5oxdITJl{vdkO=aY%qOW!XK&6y7jWoz@Nsss|UGvbIx$e8T z090?9rj!7XS>l~B$wGYiqgm0^o!hYf0FNU_$y(&g(0E7VIUbQ7f||jLCH0Xfk*$N7 z-qc_#`p3Z&-mQmS`$vph2(_EPI%T-}z0@Xbfs-0TzN^VnO}&1SgHmX+<*_Ux*E*I7 zN5NPUjhL@m(G4GF>^x&bDEx_537aKg@6T$C_Df79O zo`v@2ccNceKGaC!4Tm_u)107w{{0vs_h;OTN0mMd>2Ya>)3-8*o3KIu)Fqh z%jv6~cKf&Vqj(dh0PFhCT17otQRMqal5vk{uiq+1-XDUHDnmeU_d*VyVzxS+tN%G> z1>jXj*n%2ZK0p@)2rT}GDoJk!jMsubm`^6*S$bOb8X_>7R!H1 zZ>Dqn0>7Q{3q<_TFO|J5xY3bYoKevdtPPgfzOVvGJ?X^vQ4~=LMb&l)f@@W;ZI~fW`wUI&4Msp56XF zSkJA-1b8AxFZWm9)##Nb2*}q-I!`MRh6yTJds<$IQM}2zFa6}#>D@9!&0u~2O1Q`G@np1SQ#>z zJ#|$O?RH2rzdDkbLOkz0!Mp-a+>>UWx||<&HWW<$<&~z4Ju0_l#iXU7?Li4$uap3G zL)PTp$yViuB0Z8$Fo_8_bYktEiR|~CMO{3DncS91$TSwBe<=d6R0)0=7>Nm#mP}G^ zZ8Kowu$V4k#o&zSMmwL#e0^JYE*G7FF1qaCdqwKNxxvmKGB~AZc%#I$Ad;`ZK}i(| z;+WczS0KGn8VX5eBF(UL1w8b~qKV*?{W7r-jDD6Mz7-gb(Y z>4wT?I4trlWx#Hi$RYfeB$iOQM3P)_zj1K)T4qb+sKw(~fUYf|3oXf+50W2i#gO+B z7!t7Sa~(+Wvu0u;_eH|jG^1O+2RbgJ&%d#}`8qg<{s?svUM1DR`2!oRmxjQ?8{Tlt@bkDk?#L(qc$-zPw9;a+mka)bZbx zc9t7dTNb|&m;IE=8af`~X5Doqt%^98ttJ$o9NliV&a>)!UM}aBO>svodH{Px2%wx2=2LjxWBu8I z8@dT~5oN8guZ;9~qGmt*)htwS zv9vV3m4hza#Iurv3Ia+UHm5nVSk+q^w3&~CG-E_BbwOb%bOLfp=kUXXDk;cE^p3i* z{kszpTMX}gZ`Op{en5aoA6UYi?2_igo_7wj14+h(NfV=HuIq^wom-%({PAcexHeRbmv}R95=6V&3eO*0 zExFnD8Ncu7QNHyw6Ez=|eByn4!5cP+XjN?M1r>*Z2JE_QZY2rU4=Y@K*uKrf`&++9 z+0wITux@5_A)($jk|fAjshwUS%cJqyHq0UfBK$fG9nReW8==y=zX16R zC(}=>J)Y`gMFdf{*-_B?ZWy_8X%V`PfViEDr9A^7{ZRxwaJc0tfVOyJJ)cCu@!aBH zb={@naZ(+e`th=12?zd9r{#-43<~>6diC4G3S3TC0{5bJGYjfdBO%1+`#yVtX6@x zJ}()_f302)F)Ehl(o2BX!Q)}s<~;KBiZ+{e!SIp=uF-rAz|Yy+R1EB->Xc_x4H7WQ zE3u{pS4fQ-aJHfQDn`RkyXkm=SMb_=*)g`6tRP9>B8xURw;R4Q`pJ0>!@dqoReLlX zx*&;Kh%n^8e2vN7S4IsE=lCcTkPS;Hk8x4nTLKM!=;n#5PP-o0gvaJPYX~9;ow1?eMOS=V%xSG?kXQN?=(~v?8Y%1MS2*8OP?f^?J1TpSZVS{ zfjZ%wXpEs6nX@mIFDD~&CBjj1umIm5reu-@A;sH_b~9c>ki9_m6%XKhonh9V0mCSj zV(+=;NoedOE#?q zkhF+qh*-CpvMd$F>RgBz5>ekW>HP#goV98tTuW%#%5MOxC#E>MjcOPZ!r~QtkqJx= z;GWo~TIpkgX7QB?%<}AIvwi=Q?RKljE&&fF{@my&Nd-=IEEqrnD?sQc{uY2!U=Gr9w?J0rgxJ^oHSfeE(Qs%13 z_SUNp^|bDzxjav7Yg*q^Qof#ir?_1eMo2!Qt9>jJhDi*|d)7ME@J0gE69OBBo|XBl zB+Q{lB_T(&XtW|}uo)y6n-Y!wHg+V6QtdiUUbL$#aRLjT9xN;8C77$9W~2f_Pz99% zw4jo>7xq$@g6g&J#1VoSn0>C!w@jVC?d7z%QtD4m%3i#m+K{T{fVu9TfcqP_m2W(d z_tT1;7p>x{U8n1Aym2)_$mp50&MEf<@cntan+`fGfj=U#r#uLqc#S_o?>ZS#SoZg> z;u%BBW~VgiHrsj57W?yK@kK6&%kvP%_tvQM2bB4l<@8pIV~vl=035PE*ZTAem|bD7 zD%DXIfjy>lw@;ixJhH*^2uN+&jif)p47nWWtT)dW4`Y0>Iv~yu~XM$V$ zTM)n@p$PRUk}$dby?5azIcTP-ow19yV90$j$8VV1Zq0k?4$Et-a|Z@8)`No%t`n5^ zsPiGYd4sqCR!iMQH-0AlzVg#$J~_ zzmd$+Qf8*q-tS0}W_!jXn#r2|ViFfy#{D{8AAb@2kRuSIe$98>*TK&+?J2dLV6uk) z2y^z<9`yP>_t)takAFnML2kbsEzbOo_>nR_>lCL4H3#KQ6eL(7mlNxDrHAVKF3&ws zswGbY<&+mv5UhQ8M5^-Jp=#!W^4qH}-;d2XEji#j?ewV)$XO5~f_6wYrAC*( z4yIsNL!KK@x6|u4HwXEuZS4(jV-2qLlif&iN{<3zHrao|ec56y&Q^HSML(h?3@Qi7 z6>UJst++YF*p&c1E0yH68ZnMdC!H6hVu#;(voNvJtf+v$ThdFo$>S_sw{MN?sy+3G z`tp^e^V7~2;~@e!;dliO4rVF%lhV9JAhw4ymy9bbVHGM8L)qI6`iy=bgvxMRD1SD0 zfl#W=W}2WVF-Fzvg|+M(GpTccO5_=v%-tUAT1uvMVaf+)3OsR?2qU%a|K>EwYvQJ} z07NBty_vIO%k40o|`OeNIf~EA{k$SV1SZ@zohw*#Dx5(7XMCZqTT5CmVptHko z`rBdC+$0o0mb3%zHvlM!2AG5wlJjDz7%YPj;mFZ;Z;DG~rl?%JD(h-2c?8@b!Tf@Lw(*Hx926|#kLf&7VwCdzx%t1Hs1 zI#;YILC(mg4;>W#Mj>@BY0m_pGV)E?)#TNG<#n&op!63oer|eDrJtubfn=P-61Ksl zd@%irKLR;Jt>+V(uB?a^cR@-OOky*jBHVV$x;j?h8J4m(x|AbjgwLY;dZ5|+)4LbJ z^a5+z3zDDXa(W5q4^51n#S^9){w*?3CWX9ig@b>5us}vN)VPQAFI1s_@+My z7!`Np9n4I{vvD}=uEOcB_Gm*4WQKraJf*i$O1TkWpbomP0xJGc!KccIq5ZvX#4{#v ziikkXU%Ht7y%I*PjcY#I0T>GeuiTz{(r^2!{k+R&pA0#I1=8O>X^DCQC4T1&_tE%w z3bnQ2x%m<~8re(~XOwq#xExyw$Wy4{UvU$!7{iK6r{S*3>4=AP6Vmp{Iy9D%b}3or z<{|gaA;l_`X%%Pb&pz= zhPbH7e>siusH72BqswE6_%dyCRO2CUHslB!qyjDC!mQU)p#a#hk#D6HY=gD^GKI|> z`nRSUw*pwl3WSHm+Tp;g8&1*z>D$(y{?N#TrDWnp?$T%c$Zs4c!ypb9%@u(U=}2bu z{HBI!q!3K`bNxetQE5-HP_!fg+^d385bKgwAFa7{0De|G*UU}a>DN%;Yd8{nJ*iFLRbMo+iSDK@&Or$8T z(yAL@wfI!=EO;f-O146mL9!`WIA6xiqexpGKxk~0=Br*r^zt%+l_3W$x8K^3NSuKp z%Bb~TVU$$ra@Q?v{|~>S=^lq%%LSINm8QDhN?^x!X|JuRszGV{-dx>05G9_x@KnTn zGy$4UE+B>I!%Hp-#Y(R^{&TF^4lK7%w2=(m|MEuQw;ukCR2JLQM|Q?bBk70ud()-c z$e6>{DgK7N^Uh5|?uNtNR{dH$FU^137PjONyv4d?QB5V#JL^&8H(Bu2R%<6`ZZ8h{ zgU_0q>?!)RuzV3k?MjU)S@N?cvO!DOAhl3SSo=!No%iJA$FgGeJizc-pm)u(O~DP= zetlh!R`o*PFr}kxgE=07%}rku$1I0;8vJKroBF(ycjFvQOgIG=?A0uu(M0 zv`P?lwJ*R|@=^vyEKKh4^G@@N ztP}9BBX$o1(vEQ*E9~anf z2XK_&yV}}m;7Nu zEyWri32F2D9yrN!vPT*|{IQ!)ZR8M%9V(j6ADO|8%!p~m3+X^lw9!rmHEDYwQ9^yF zIf|YhZB-3@QmpE3P%1RJS8%^Yc8}uOul86@lCX{1g;vjT-+uOOXevKe{#~l&?&sb_ zlwuc}lUs`L7r(R9B%oBf$PhrIPd^1joj|pUQIXR=; zKv#P2zh(HxlCEo`xBh&E^q&}nyKMWy3r*xaZ)P)Y#Bh)op229IP0hd2FlllW^4_qN zf66b3DAQcEbOiN1ECe$B%x&&DV&Hf52(jbL*yOwcj<3&)uO7)GTi+J!R$HG$h&Wi8 zsOJW>7}S-~#w-n@OzXc||G1h8E2QZpmS) zG}3>{`2E8LxM_#lFG$|9O}DP#EsL)ae12?l=TF1%&aSQxCxg3_+luWMJRli}3#-Q# zI448vfPaWhe*9LXcVT&3s)tP-)*f%}-XN|c-haiA(>)U1@kCqQ=E9r^m z_yELhl9&!kZBQa?DVPT8Uh-ob1Vr7>@4>&E{{5=Yiygp$BEwykh+Mx11Td^A{r=6Q zlR4|5-C+;Q{igoNkpWGL72C@eF2ya${NKSL!(UdJFX690qy6!){w<`xKEf2-V9Yf? zr3g5&wFvV`kz#hR{u`5@vOyL!@N&(Q&J-4(`A6znH47wxYP9)#W=rIKb0e!~ojWHm zC;3M~dVv`Br@5JudX3kl@W|5Ui&D7?tNDeeDa~7T`7|4*ZyMEwpp^&zm}nJ2+GdTA zB}N*PD7&{!qYhq&jfXtf$+m}_EX(uU!yE4n*Uc>co0kJ#SBrx&j~OBP%a3Z}IcKD$ z|ISJUh6jFE*}!X)!u-m|CXlL2QJFXgXp_S{#%_3>0%*)P3C{@x01MKxbb(?SDMsln z5(1wJjHzu2NR2v=m^}eLi*Ogi@9NSXB)P@ zw!<`tdejymtN~{WIsNzbgINKkwjr3o5306+=s-i&9#PIdzuC|?Jd^W!aT73k)ILT~ zn&r5Axq$DvKlzL}lJRs$0a0 zv8}tSC%@8`=+OOjrmIhZ25OxlLqJz29j6?}I4|;PtqDK^=f^Ts>DA)o9-1~iA_Om5 zlpO2_{101oYe{%t{0&?r_ls4Fk@Q#WzU$>Dfzb3z6EZN)td4g_4B)}*H-&iVu8c?Ip@=85WsqVx&1 zR#eINYzjRQH}hH;!HfPOT=X@q+t0T6WZ!$QbdLXX*UW2L)LFjB_a@`(m{^B9Dr#FQ z7AAz>nmCAR&N_S%n|I>Xy80z;XL$!Y;S`e@;WaJv)aN{rH}H?`E6xHBgL(U80L?u1 zMIh(FXT*)}M7i8GvZ;-7OZ7-!RdqmeeZG;xTk{Nz*Ak6jeyG~+h5tN9S~Fk6Eeyb-v(;GqDgT9yGpu|eJcU{)d9+@|629ZZ6&Mpg;4H~PR=1L8X zu+eWf0P_WWop=${n>ZfzWZO=cUOAwi@$;sEEn)CfAjlz&&@MY%1f?rrPvFcA!*lT9 zspjmUu6!LU;}F@%LgkR`m^8{e{MvN8fQHFl3&-7606=h%nk=gOY1#*=XNd7Z*W1JS zv$TZ6Kh@+7hc{P*QGN&!G8gVP4)pY7gfWP;8~Cfa?PbBQhRGi3kr7N9*?x|Qob z!U+I;G?JAR`v$#VwvZ0HAVquWh*wRsWO8kr;Fn>0_xldENo&6rI!W_+ZzC)}s$KQcJ~+;SYEYq%Zpa zz#f*3?H(R%_uXmOLFjQ;YUqdVBeSRWK{uDCRKn>A?ad9W4}&&{=x-aN$YtFj64Z3* z=B$iw7tip+t`B^FD2Xucqxy@_p6l1)FybG=f;kG(R!Eu~SOV(+SY7GxL+J!{G{#=3 z*L(ia=y`}ilYN9AajkwH(t00N*Ha~E1`u_e*n`_u>ZIUy{4Ye4VNOMRZvupXLgVm7 zcdCGTKAf(Od`=i6%Yy$GGaAh0^MdCW0@VgGiZm`lk_VyFJf~NOHK|dvERz9umJxtn zJIxt5xFSOs7eNNOFw%sLhjeds2f)g_Nv$*uprT&7mWKzo8$8&|WAaCN0+$%}IO3jE zV*Eu!t@8hG%GM%9MAmE^G=?Xm>Ii7)(93XmvuUVv{|NlMk;HGK-dAap?jQq~heJp@T!C++<(vB$@EqKjt@2fiicUwS}g2BWn0QfFX!DzwjKnox`Dy$rxPRsw+y@*DS6XE2Rp3dZu$D&vW`R$ma9@l7K%5Q(dQ*-@ z#Y6`Hp0t(Adm&57qZKKDd#Ct2^Mb2$F!q!)gN+;N&8=hMZT`liDE?0Pn}wc&_8@k3 z*1w02FWyq&G3xE&>)@6QKus+&CZC6c?}WlrT~35QDJR;7Vzu63vhs3f{q6q&p2^uS z71bjEDiM}P0e0lU)$phVIoAS+6b!#k@pJ99n`?s&+Uvu8>IA5O6S7E9X6>1c$fviFj}+krxxG z-fAx@CaR`mvEBht2Yt45?f{r5Y!z^wu9~OarIVYlfAwZ-SytwO)!U+Xp#pmz5SBV5 zX`HNr=X-FsLRugTe(*XCy%=2=oh{(f^SlB2JM^FECumWkhF%MWk3+wS&evg9-xC>% zTHhfv5BYjp2YxQ*MeApNYzXCV4PmJT3e7b+@HUn+@2S(*c<4jT-RU zlBC5sojV2%*eKd6}NYRuQ7m7;}nXhQPZ1k z%L;kYjl^jioK(;JB+@*SYfA~~RN7Sj^cEY6Xotl87Qn*aHsH9y0+tjEYr)sEDgI8p z;Ob}$S)N|f(EoyPHA{rd)zIUpH-_uwVN`}f@N!15S)m+Xp4zv~XA>VT%Ps#;rUnCtAS^hd&3)N>=bB;L!F`?*dn<->gp`UQkWcTvGt@ zAQAI((KJ90{cljl^MLfRfD5iR0mmo{SW+`Ig}W1Q-?f%sKyEvObr#(26Ae{i-DIIJu}Ork_D@=L;5&CX_OMaxZ-xcRiCn2orfLPqqmfCau@ z1;?Qlu++hz4$4#TW~wrUzbC+@ImmHn$g(xuJ`!>QEMbSsCBQQQHC0|4;OI!oxW&f* zAkq>-avTiZ);#ntgr%~o=HvYP=?wcwPUkIZB*OJH`>k#408_w>**kES{ z8#km5-tus#AyrcXha&;>15=>#gSirJL!a8npX!3|pe&3d$`uQa)@5`$V)>ht1#?q` zaI2}SD_xS&ge`q>^2R3aFYH!$+lR<5C@jKqBGTJ`FE~>@UsF;?0CY#k&DKW&b|6Ex zshL7Qj@x7QV?U;ISykum6}Vd@*If<*Q||V`%y%4^D$~R+aBJd}vN97{X58>MocKd- z{GS2;LX>BVjsI?73#IWt6%MU5{#qD+7HVBabhO`zIO~o8=uRF&H53!kx*Z0E_ayIN zS6{zVugAM|RQw_Ar4?6NRl5@0B@Pw&A`~8VB=x`0{=P6YX;&53&zg**ZEq+4pC<8N z50rqz$a|A7Pw=`IoSNDeoRY^+!sEacf2Uq>_YVwOAKBBWlivPSw0{QRY@HDx!9ahw`Ws z{niRF-EV_=S<0=|#(!V%h0^$Iwg2W;$^d0@8?ab!{6&{uJW?Bf11V5+FaMulkBb^#;%$OSfOp7`*cL2zQ&xrJ= zjp1>6*Og?HRt=jFc+*hZQzpRF2cZJ~ANbp{eo*%z;BqRuK9)B@t?UD?N5n<-0!05* z2JT7qwd465P!^_qni+-cObyTVg}5Ep+1>E}`@`pbhVWeu7Bg*23NPX4Qd4NkUn}QT=nZRra9MBszYWfbXh@C!Xm~Z# z_`{v#_RlZo|7!h7=Eh&C$vpy4p@2r=1%CId{BQKCMMQld#mw+Ky!8julW4=-d*E7~ zmJQ(XQ4h9rnS@{M8NVN0A=iz?1Xg+52A-@1h)HOT{}XU)YSauK#bF4IzlyB;^&Jp&A{v6I(KRKI z_BC{72;_Cbs3`$ez(ELDd!iS0N<&fqzCc9l1wllMf`tEJ=(M6Tv??Bb+3~25Xanyc zG{idP8E~5#5e3h-XejbaZ{-w*R0)P4*Lx!=!7!xtLuZ6QUJZ<)^o-}QPZ}0L4@6(8 zk)AA0lL#~dU1?6F@rM}($d{q$(`cje3ODXw&5T6nU@2Qr z@bpF10SrNI&X%g$p_=Y>!I0)!UqMY}V(sM4qqC7UglIe3$QkU-XL$9M_$zx67 z1SzCX>#(#oCzw&WDx&X%dov5Qg$q6x3=>IA5g3Q_ieQyr2KB{C2haKr%h#`&1q*O9rR&5WeZFohjHyOT)0 z%r0AWVoQo|030?oyTO-BX_Wq{|bKdL&zR0EnLktZ5#{Pi;Y1R6@?e^9fHzw)b)4uB#8%#XOd zsNVsI=5Y_PgcJTgL)Qh<)s}GOz_JEmKZMuga@-SxMg}4S85!W&nh(8$;9BLc?_z`~ z2T;!)Z4mgqU{W0xf?NiNXBGiey`I8^!l~ZVcvRc(LXbls^3T?Q!lPCnpJWYJ4m{c_ zH3)9CMj%RLATrP-1Jnt_h~lg!qw#tB42-WsozT>fbr}hOTOIUcYAr%aI@P}Rg~vj+ zkr&zl5NOEUn9Ke89f(-%1ZYp}gJ@x+G#>IpLuy(i_>l+O(PU&Gcm}9XS0ND(qe}#w z7%jG3oqE8^Nse=RTBk-v+WR8b;^- z#=k?d`y&-Iq!TW6@Xi$(f?5xvxxmfg`9AAFBfiLhO9ptxwJ`ZKmo`hXHHCQl^Nf!x zDgK6|g=39+>su^3jy)79ZJTwe9RRTl;aaiUKNP0Hsc+41Vi7M~E(R_wqS2PY&_!Dw z^&NH1Yek6+v@HWX*DH~D9p)4AP=6)=G~{pftzX-eUqX9Vzy@$F_1v1m*8tQYR9`3> zSHs<^)5biIFQeV90p!7&gsuRtR(MNLx%e2KwN4;PWS}h>p#1-Vg#Q<9g~oq3!;Qao zsJ(-R)cF4aK1)5cuJjQA2-hfp_Nbz)11Kb06;yCx_IF&D*czh=UzocmK2W@ zLP*Fb09Xw*w-Pjo7~B^{-=y&9a2|64r%$5lScP%~a~g-Yz;my(0MRcp&`JzY-VY-^ ztp?|*lC9}8>|>A zGEg`J+It>y&^6O zZ;h^)oVrcnO&>_ow2)JA-T_eRNT@PMTiM>%{{e{>F}_PDU{kA@;r0zwoq#>8Vobm_ z3-{*|{GxMYpp_WVbX`cIwOji1thVh=vkIJgc{i}Vg)U|lV*;*U!Ryfpex*8l=>RB2 zBv^|^)Cn-T%3c^#%fKg!9Awf|h11-$}<$MeYd^34pgMoVtWY0c2{_exp~<0e`#WEtz0bLlaT@x47VYPYgeL52YomI`CRe~#(gnxr zXg!2#FRVq;IoHd>~CD9Nt9bJ|G@2$86bk%~!Nfbg2J((5weGS#Lz$U20llO*#FE;*WOHc$> zGy|0PCx~#$PWy--2JSjXxONZUdCTG@&6q7ytdz z!Wj0u2W&&gRAsJdf#+cW)FC9kMV*l~;OrIOK%)J~fDZ;D_vpw>wRj&)8vGMnq3DLA)1}Oi}qdh=zjwd8~Vfg_V7D7X4{5J-#MkYdR{MFH0 z5}r*o{$Q~wG@?7BAk-_T{^m9O#ScV=nxifYTIPTbN#PVaW;>!dI4mM<|WIGB=nJ0D-Lt z1?3igZ&mp}(CZuE-hjgLTA=tN?8rc5ATrQ21Jvg_pzKbxd()Bmi$GJM8uAZni(fD! z0M+>l$y@XP531b){Hr!@I{*R>*%xtH27OQe2P~Qv(5m_415QJP9vO%XLVoY6C{Ymq7TSxSp)U?pa)$Fz%tAvS*-%=dL4G97>l_Y}12_`O}_|G=->L%KGFO}))1k%7oS zWFRO8sE;+oKN?*kDB!ihYJuNC>SHb7ZV3r`3ZPaFkU83aIS6fqz4lt;prboasg>5~ z78!^PLGCmkKn(_{pH{{BMYI(f|CW5~ug4QE&ar(QdTFLcg@UX!#C6CGlkD;r!Ou=_XX%0=*97LHkCa z*dy%7KxCkG8917x>ElEp%Mr8{EjQPnlp$@?0T2OX?AxfmX18Y&A%VDW6bQ};Gcphv zXdecK1e{cjT=bxQ_+!9n$PK-%Isg@R$mB~=EfT!6;uhF-mB8>uxRHU#Ks}Gn2Y5%w47RYsUAUGq;$UtPEeHi#xU`aiaHsH(X zGlAhQ3~pO@0K_7h|36ec*Uixxax*TUfKOjTj1n1$3`7PjF>r$=Fez9b#BTxW{kA_} zrR_Tal|n*cxC`yZ|HCV8Mz6bqQ{T*v5*dgLLDnG7uSv4ESMydTdX0s*6e! z8`q&d{iHNnZ3_k{VBOK<(V`3WN5r{DTaXwN85xKSv=sx?ZA+ndqeaUUB0R9I$c%}# z!vKYEJM<=WI+{mj68KtlEjy`+NFoD~fyh9)3{dCIj~;-&jOG=+C|!xJTQ17hk3G&U zmzc*C(C$Rv2h}Hh-$N&{{bVNBD3O84Kx7~?P=f*LO?^ygi4J|2I&)%;V9}`n2L2x* W=2VBOcQpY30000m07wjFy^8JdU zU@ssFSV5^GpaLo&0-{u^AubM>F;Xu{jHSUR=uzpa}bThE=PCPK0o0 z8J$H^hOKipt5Qn3Ik!@PJ5y}XrgPGurXD6Lomv>W)3%4cEzO=Z&&fPYk_M(#PL}D@ zdKy79$Ve;HcOuH-A0q=I#@74P(nVO)2uU`4()byt%QPWHinI1hd5v^bmOR(n#{!~& zCKWUx191x=@BXCB2J4T5C)t3N#O2vIZzL(NP*kSuKeFUujX-DUdQyb5Nh4**b_-ZQ zl{^tKX2Tp!Gd+2%Q2NTI>6`Og@8GOT$?X6;VMIc5m-qFmq~KBKCP78mr(y;xk5FKq zc%d?GNIlhmEMBkc<&wBlV`Fq&j}cMEpb?uv5h2{drBqFAwoc^ zmTwAvZrJ}oQz1jCFVEN`WMkU&4s~yJdYp1^e{EyL;<(`r8>0w_X8>4nuMy8!{L{w2d2m9xr zzSET@EDfB>wggamuFt}jwY?5z>O7Qtm}ChRh`fDSAZu=4zGA)CWtA_&JVi!Yp|ou& zO7>0J*6Aj2|0EAUo?X*D&lI;`oQikl3D&-pdPP+-_a}i?m7T1gr6@)2Td4bkyu;+q zEMf8OWdX$NWGtT--wxngNxF+)43 zbPsg3{dHVp0zJu0Z_iNquG3ld|&aq>-JhKZ6VjEK{+n;;4KCAWcV9rp$jN zr%c&2U1{}G$&iAw0Jq7i0cW24e_S}l>%&VK+R~R#r6|^n@Y1?DlPR1>tKPr10|4YX9)m)PQHu--Dg!1>VN2WQqcJozt5PZqpjpyJ0ZG>tK_%fLRVG44)b@-x10i^c7>Hx4 zvs~LV;>rX>DZZ`6<;`5__F_OAp5lstc%wP-jJQB83uu&*`x>r4$CKQKuxeJvYc7)K zlu0#J^sgFZEJi+pd>Q#p^2y{E_s^0Fh%vBfI=+IsT19;Y&ZmH;_8s;jOB64P%2eI& zRG^x@Du5>CT@vDih_(qxlIMbuMyF8-cxfFH1UxTc=*N=A=B*2ZQeGKv`{t-F_4_#& zAWCVPQ>gN5A;MSd(2%|&PvQ4GY?}KErrK13Ni=JS3M5P0BTZ3 zWMtJZ!kQZ+kozJ8r;=49I17-^?ITQArs>EdDXsk2HdRhbV}$}-0rMBraBEv-xXuJs z*6gMN`2U(_LzeVZx0isl3Lzd2X*i>8RqV)(5s^Us_l<-+%xMJ8AR?_0LeH1rKBig? z2nn-9L^Ab}fH-FCNu6dhUS=#th=BM`E!Sc+DI|dPBHLOc0wA};#}ZXJaoG@gWK56Q z%qvtCd{jP7X0)&De_V!3Qj+>-1j}TBI_mOaKPDiIK{6J-1-L?T)}G!g_n z#-XBayWZEDet|7{_^|&h_CGsO*ZHc5I320abuPK4z!V}{=~T^);@m#HfF%<)9$eGT zR;nfOM(cUX^J2tl5|CDz&3mP7cd%{j@*i(a)t{#)3$yCv>^osf5ejFxUrwcI9BK8Y zch*=)>Z~e1Sw9T|G7n<=_>1;Y#WaP{zBFOcHtIQ@xIC^C*=nT6B3)(v5daoX^>}9VBPfyNL0TD2?~O7J0ekO|K*;C2t+caNlV+7 ztXF0|DW^=GWSOLltaa+WI9ZqVO``JCF+v;Ip||FeBUd$3z%@~YyniXm+aK*qdV#i= ztsBW0{l5TNCndI}uBOS4;}|1C5{fFMYKd)3s~_7v<6K@;K3+Gu95*DnFTS3k<3-dz zAu5-4Y<(fx8U1Gnigu6vmjQ>o^CeShta62wGI}Hq70aiIjgz4LGdw~YGXOqH<*Wxn zsy3D~WQ>)myHb_}$xp+PRzJ-nX1MPNu&xx>FAF|RS=qWd0h0w%+p7?u@>zPbR>HqwS?887%@+cYhYPk-Q~=UpT!&DIz2=j|_I}P2S9a#=gr(pep~#Na;?isC{YM zqitFBqW$szR0Z(@$>k#DDjx?>rhHOI+Im7}>I8-Hdhzn{?ODr(F(O%Uq~N>B?eTRP zAEo&ACd-jL{Uc|_ERAv5RY_3Y${rC{I06;l)b;W+AmNfaAS!!AT*-)ez2(z+5*AV| z5(K`HN5rkiJ7%-KN_<-z%d*~u9w$QLKp@2HOaUWZl?R%}F{UjyIyBM*(m*$=m6X_j zNLrb?+vZ4}`gM-GE~Z-b@RpSoU`wX2)>2}X#uFU?%Mqef40~85BD+Wbr*v&yXC5j7JQ}|t2j4$E%AXdE8Jc(S=;;lP z7eb37j?J6%)MRutxcK|JbAXNoV&t_h3?0e1$}zl5ao!^Z25pY^GcysC+c7nUxm?k( zOR0gIBJ>?Sy!9!t{m~HtwH!i*$5L{bQ&V0$s~@vT2V~{xB?Mf&j?x!>7~(uq2y9)T zBCKxRA=GQY-M^u39akJUixeZzt?UqqBgd6py_6Gi0r=97?nj2MJ>vgYK^P90)Vb0k zC&~E#X%OIh03w6GqRnHkC$ws25wev1i?<4JK+53q`zd_pZfe#1TqNl`yYt*unend- zdJjscICHE2C#;#O(|7FSpQg#w0NszIQ=Y!n3rnc_T)MjStzJNw&>0M*v!A|oM&%|O z(p98yZKB8O)?{ams zIm>TCSSw=|;uyep9C<9UKNN=$)U-=QUsL+TsTo_QZ8R%ZnS=YGv5KtBh!kQwStw=w zPL$Sq!j~c|cT-6`xiSLW>HI~FEE~)6M|)2D!dRrJAi$eLfZ;CTh*FlZJ>Nd{GHzre z|9AVcC*Ih3I>7LeX#cc#uyG+a-W%=6`Y)>_tA27jdUs%3=i?HSxH?|n0G=;!g#nHi zK~|yTMQs~*iZZ8-u@{Exf(B$MU3KLTtzOhvP3$Vk`R~xR)7a^wNNF8#fLTC*;;Bea z%lkixz75IqlXoTmfgDtdbEoAx;7YdL3nY6gQdCg%cj|nJdI$8wku#b$8(VN zCs*=9lrw0jXc8HU8VlzrdvmBrRB-$Cb)PkZL*)RFPlpgZV6)AKTVW}AdQ(xn3 zCL)~LiWI*E&Q9S#a)ZR8MSULS6wju*z9TcZ)TUz$=@g>R-28QL-Y_yq4Moy@1xpne zsC1jVg4~db{%MYHlkyI^D?4?-myw?=GhGqmKEclYk_FP%r8sSSm2GX1Sp`p8*&;jJu%QS; z8t&w_vN$7MV~ty;a#S&?xXyYReRbrzs8eKT3)p9aVKo=FfOT=?6rK$to5!v`qK$b# zT#`{nUmg};`-*V6vRTX2(8d61OUfCoe$+9isasD1iS=?#%kM$|y zgrpUY?;kDCTUL2W-PBDZy~n5SbhJ@AqLd~Qo2Dm4P22Bs+XzQyJJiutwoRlvO@8Xe zc)_L$;(lXcLg_dlIBPEto=U0=$1YGPaC)v}yrIfMWdI)w_ARYcL1 zQFg8BxJ(uF&rq9Xd=r^7lvLc1g{h*LvEtZM`tuh>`b#;5v{xaqNa>h06;`TXs35kr zq9O2721Ds^ITCh%83xsOB`!grOf&|<-|4NwOXcI)}k_GRl<#Zo#_!~s-Pa=)C2v_M>ji)C=!Ei6%T zA+w2$2#5Zg$jPb;hrbb#>@VvOXV<|}%P9mpA|T6vlQXtmbRD+93 zisT4NRNAd<#StbAwXB?+cr?jX^elc zT<1mO2QkLk>7~z3(E$76aOk9eRr~Z2IYRs&P?{J`j#hP^#`#4?l;Se0E=xw$I!()? zQg7ndPLbU;vCkvUNlqL>MmUWWNmekj)a*FPdWrQzG58IMZ8KJD5;{XplMQN_GWEf# zN7)+VP&<{?RYyT7BkBlF)^XTqk05&q@;yl%0j_Iq2n|&{#}T$xK6KlfQ^ZMe=pb>i zgI)F+71BuS#3|xH%t7L8OfNfsls+xF#Ddd~W(j>Wis&ea5qciZsG-6n#hyXz4_Mkh9O1I)l)(Ow9YXM*A7SPHCu#PCx-Ixf0io+a-ld@uSOZrOpOebN9c-k) z84l2qHZX@!TST9e+99uDy4)9Bq`(i3fskFhB&B8Ducz9=2?lVC&fBEZJ_Qb;K0_N0p}UjoitxIL`nvn+{i{LZ zgf!!`kmw$E!st)Sa!={VHrd05zj(4kVwY*tmPl9Yp-PrU${qe|@akg@<<$~}X-iU3 zABS<7G;2`Wj6*JUjLB;4^Z{WjyL5=eX`pk55UXIiJ;KH6>SIjTU(s_M9|uw<DAg^XfSl zilLeE4(0p0WowVx)FQb2C_b`r;bA$?9!MtlKZx8#7E`+SY2oG#*YBi zNKWSV_GVPag5mRBH8`#8Olf8|K79yyn&7-`79H}~d14>bDgtZL*Gj1=zm1&29HLTN z)h=9v=SFj;*X~o)02;(tf!Zz8VZ|CpzUEASXRDA=_#-(*mDDQ0fhw!Qx60O~q1Nf6 zs=^wcUe}(%*K33O%1+S+sKK{vLj!%cL8U&0Z!itHnwaWUBQNcyp@gMV=}3X#N_Q-) z0xyl&3QjRVdsLcvuu6MWi4;}tShhNRY!dy1M!pZbzgyP!s!_gBE&^|t(2}XvgPlSU zRv?vul5G+do0Tdgv9Z+YLlP79GFPjFsZ1fZqY?wI+o$mK;aXuOYprl82C5v0wC8(^ zgyu#H1juR1-g{pYa90#5wEcbBy zr3%IiQK?jl*9mbMBNii{Qp%X(Lf;S3#w4aPxoejF0-wh!inf@)ld|aADlDMh5oIA)>|+eo~|FhUGO#gMBkz zTO5lNLS069Tb>V`7l7x)GMIW+rnOH!lxfpsdj{zg7@}VBUwYQib>MoR%e#zI2zcBv z>YP3ntYdwdIvB9%$cRaB2vKr@>?LWyjIUHV(oRPTfL#u%HHwhMJ*uc|mHlF-O8Fs{ z?ULKL?s%jqbO;{}A!ktXA-iuf=P=O?7wA4N;w$bH(YCyQXEVzH;#!fAr)*O9i5Jp2 z4(QkWj zMk?tWTDd8H-pMVPvJ)LUv-$XxUACzl122XD-;^slvy{AR=GO5oQTs-xk3xqSuU>u) zEGLZsh3F9f#FFQeW&hL3?<0qrqHm&o&KE%1>Hnr>tILtfDieP%{mx2Fpr5E&FZ6039%`g$<)bh|jTVE96hw)(Mrge*^uxXmzClI`^_A+7 zQK!xjqs1U2MV-dAI!`cQPVod6b(eOjTQSsncKUG8GDACsSfp^^6hjkXPBF9=bzsjR zoq}*a;{_K7TuqFKK{^Gk_rS!opa(;T>J)m9asdx~O@zq7It8tF|3tK)2P22<6lLGK z_CRZ|MgD$}_bHN1;`_Gu!0uD*u1N8NB#A>?SEG?mEo&ELf1wIx%MYm>2hgt-DOSR$ zYldW430n@P%zGhVY6d_!cmwN)q}3}EWrpNHvUef|?xr<%*=-R=dF6-Z6oc+)<~5|N zeKABUT`jMV#@2k>SQRPTj)&DBGs>*g*zR1ot>?p#JXD|4k%znM% zSt>=k>hvk<)JcN6KDi;l^=rDu6g5&^9Mr#sx|db0UpZ1V1sVZt<0y-C)%h>7vjzN* zgTciCSoU`RZ_xKraTQm(eI4=|)T#8X%m#XTS=E(8lr=tb2$i3X6j~|c{Zt;Sqk45y z8GUtSH>p=-V+*(s0mGY`*buK<25;Qvc%+ESX=OPMq!on@ltA!v9Eiyk;n*RL%~dvM z=h$^6$ES^^Me_uf-;R>g1Aa{mC;#AVEw|2 zVO!>Bvf9Aul3VaT4Js}vq9dtu%tMMQNBdExIW1hK!U*M3S%$117C6Ks8TFiPPBxAM z!G#Wijv2QH(jvtY6ui9%kZS|lI0|!Y`YrZoO2^a$wu{-J+4Fp+-Zx?L|js zTR6b`Zm=9w7I&F)WwB>*kQFJUyRC^o#_Y@jI##IJ%AQ3!%97d)#+=$79OBrLxZapm zE;CZ7LRoT(NX}B8x4o?HJQ<07=Yn(7#I~_jbpDeKnvArS)Fp3uy7MB1h$;2mY{)#! z1B0`B&#z~9WGBCAZAS+n^T^qyQscTSnl=b@n9yg7Bf z?aISccOPJPFAKOxNABrEl~HsSf6p!wr2RS^%ap592K}=sU+dOy79M13EaP{p;BZ(r z_pWJOJ#vVWb)O0^H|CWs)rb`o-i*R!^Ay(Ehko6J(ao5uX?l`&WNb*~^Q#JQT;9vq z1uL{qsROsHQ&b`JDLBSWj>%NSx*C})yO!Icyuu^24i=DkS+}U8IaMBE z|43HMSJooa?T45p%L4q9D;Hel%=Osq=akY=UX}f-hE|o|u>ALZ;;YDOna@v-nOiHgRRmS4$2*3q!U|Y)wd1^FTLHpYQJ>Br zMQw0jDN;n%S2etj2e0#AV)S$`AD4r*|t!TZ4M$?ndHdE?A6&C>D>Qy!Px}u3g2zR4M5gA?sxT?M#@ZXMP zxcUc+K1N&l{mHuevB3$4N&VPyAKMm8ZZBGQfybFaH66qGl?gaX4LmL)x9olwjgZvU zHJ6P}A8}*qk|P30^TuU0T>etS`khsWhc}9hIsoeOpQg)Mq=KQf`} z|Bq>q*H^8SEZ+pTONS6HXOSW@vH`%UiC!V+C6TPE|I~HvGVnrZ&9~^`d_@uu`<1 z_fN6S%a+ZP(_~*+{ghjDRJMsje9xCdh=a;UV^!iHz{v>dG$%v0#u7Lmr%=_#MEP~V z`tQUxJ+sgNp{tYIYpkz`{2A|m){v7~#apC^G-AL8EH@r8rK4+<-o*b$w2a))971OQ zYlQRr{LfE5OzUiK><~IINM0R626&GYQWB*RInk>9muKKnoWbQ~d#+~hks_{LZqE9Q z&>Ame%QF~Qp-qR7_EsZB++2$qaW>MIM+Z^*PLEq#jTCV^Mh5>mzRi}W8Cbk4hY*6! zBE_`%ELhZ-X5$2$;YHJH9W4am6p`%{>>Q8b43&o=M7+8F56UTI9F8G!yw5M?n#j8H zx;#x}VeYI?kp&2nbon)vvdRo#`?Vq47@SkY8$3qbmGSL8UVhccrp7n(d~y)n=_Air zPAwXVq!CGdN{R|WJ3*4npd&>REacuFiyj(b6>2&!!r3>65TU(tins?r_MI`}74hB{ z-{11`L+H~m|0r$JvVK!nmH|#TAJb*7<8&kPGN(!^i!J1Gz3NkhOk|hXa8k`_y6q@$ z$A4>cccCjSX|A->$$udKk*t@(OO1`8tfc@Mus{)DqePGh0Q$7Z2gxsvwhi=O_bLw} ze~Ew+;t-jE(q7&y3l!zKa$b@^ph*-CAnU8Jma-X8Ao(Og-S8W;ceP$fx?0FkuprSzL)6o$ zCqp;ThVk@{dZH$;mh~ud+8mG4eT6-8irB7UG4N7)9KRWsNp7sMKoR4Sz_1gmzm09O z#mQyhZcJZ>!13VZQt*W36CWrD4i`bkGoGMi&`X+D^eXZ-iF_UFx&f$xQt^LXnrc?- zWL}+Z>yp+m!kDp?|nF51Wo z(M}3}mio#7PIoyu!za(XdbHNVlo=$N+w|8{)efjd>J)^)ipoj!%GJyX*6<9a43@zBHn1c%xG|(&>r_J&8_Yxe`Yq4Yuq%wd{w*3y!>Goun7{Ogo_ce&EFOD%_wxArKv zwM!4k+k~vk44*+_7UU^ekf`l{Rd{A%GvL9S1UaV47v@} zn%vY^TAapdjWl0InA~A9fd6acr$&JKN=xJaI>x*uuRRI~T9m9_gs&j60|Y5qknrXr zCb%gB_~%RHq{z9psjQ6pw{n>MC1anH&E9$x0RIUHU*iPjOd-d>yUz$cQ=@G$1{^Uk zI(a&hHZEoqkj6JUSo0DnAVM#1d6Dgl2nSr62xFi$0~{k8Q~2D{6{;0njpJl?wJQ0g zonCri{5+#*=_5#NVL>9lF>P;u7{Hg$8~L-I0=iCDaU34vQmC^78ekg&?0lEtMzZdQ z(1kq6HIc?Z5DakaEDn%6Jb<~AV`m8$a-H-jF!WP^@ew4pw;4B+EBpmoxA zeN%pMj!ivGXq+1ND8TVIP;A;5NkYJgxWralH3o*w0LRnTSa_OiE1MoqjRFNm{TqYU za%|Mu81-z&GEJN@&?^Qwww&|?;zlN{N; z-z50d3KS^R7<0`4PXtIofJ~P1apc|3DbZJA~U{U$f14U;5d<&Q0N72)z zNRu^UfcDb!`fbS@jq-Z@S8jLeB$M9$)i{9jM*pYLj{4ZKCC3cVhPxp0SeIhG9&-Tx z9@%MfY5XL}g8V0u_a^_-X+yLl>|xY=m%RQYw3SO6;cOk(O;iP6=`#x;^&!?DR}o%N z_Hm+GtxKN*xxL>F*E;(jNPcebjj3jUM)ZD>{7HPn`OUm)P{J#XUn~VG%?9TxJqFM7 zlo3`cPykS00eAW8wgm|Yh1X~DcRbnk{T@UPE@`CUUXva`@EO;$)1LsRFDmkuvVp>B zbO%@|y+z>rw4VlkBX|$)6XqUZ{TCRw!=3)q1FX&<;!CR|>&#>RQDuLQM3<0g*v0Mef@{C6~KNWS$C~1wadVfxY*0vRoT8ad~8>=9^*=L(Q%o3 zj{q?H0K|esL2JO%&gAJtaozp5AW^`Zr`<1`ZiqPx_w%=^CtaP1<-pcckRP}LAgc0Y z<(}P(D(4AK*|#3XU6iuDcbnj42SA_FJKzR5Vn74?1~Fy_U%UmQbl<{7`U1RsJWWt$ zpl}={dOgt$T&x0lSCVskU}*%~w%{3f6ohMWfLs+k(hPtuk5za`jR~n6QLK;io{)j7 z^5!h%l?Am_0s9pY6c`jBEKL>z7vZlOl-8Sszb*jS`yBy(82j~E&#{zshIAGr(6->1 z#z0pf`xE4;1Vo)>EJy^}R-R$48~MTL{~ez7H5Si-t)UA)Z!Bnzfcda{#yeaydK47; zI^|t`li&{+q3ikJ5_T>ND81O`>}G9nMj9a34BU;tWk(05YuSzEDX=vbG7^A|W3eHv zN8u_+%oSRYfX8D*rV@PIM7AK|%Cjaz&Z3y9rzlZ!_SC@y>yT<;24G6q6mU{{WVr=Oyo-E#CGd7&vy!K_7qoeAZV^lySOByXroQ zt8{53Xu3y%0hh6H&1gr%|IGpX*CsN+qd_DeAnS5SkAEyxV?bwur_c_1g5x#OR&PeZ z_q{3^ws5tPPIBL)y{>I)D(&$+Wa!K4jT3mLVnjSpIJ;xo7@Y~I%RuL20B}cdyo^|J)YQ#P8h3*rAQ_0d3_MMdpVaw4Auv2bo?BorX7{=VS-oHw_=S)} zPdz>t3@igug@NblfF$X4>);Z&el2hS>pXx3M^1kLO${NK>K@Xgu*;7AG@Ov$%kj5J zzaUTDfY#{2SM&|H;hk%i1&aQ8!A}ViukIi0IfywY$>$#HEB*<^{aFhX{c8CW2@)^t z7vyxb){9N&CD5%`X-4N=0C#Ml01Z}*0fNL-V2^F;^`Zrf{xqL%X71J>xD$200-4IVIpgc%4Q&MOrd`P3KT2)S7RECfpi84fH$&7qk=63 z%z*Au=miqJNMb2q28P~ExBC?VJ0H;0qZrf;vasnkbU6&DXJIK&1{5f)fdXxuI4sV% z>&DjyxcvM9+B6uGEKu~PDKG2~)appNw7Q^rEvwNM0}2$^wWZATG-H5X#h;r=u-e8z zJq8pgG?|H|elV~V!QvnNfNCg*#DJc9EQLY04#}tquqE}|3w^g6U$mDK18qdj8{mD~ zxtQg!iRaGgQJM0DFkl&qJ~4n3P5V$2+~$8x*z;QVahiDUs7K*d zlL!m#&DBjj7oN?v%u=+0Yd^%$lCCYtbyt=Km#6aV3P>gU6 z`N^B6{oA|9hqa$_%acDteuNxE0@hCiWUSlRQTI<{IP{?!XXIdq9N1o;R}1@1@1)(n z*+d0x^%Cm;x`~Vc>o)!XR@^2ydJ*fbewuKk{}$SJ87(IR#kp+TcvQ&e-!uT9N+9@a z$bXMd9g{2@CmQpgI$Y33L%BEhD0JxKM_vOQ`7gWTRy`Fo5<{_?m}>Jf1A4T>3PuStQVe!9h;`x zCVr11D*Irx;P78Vj+I&u60!lk3-h;~LwhD(6r45<61w)CcEp|%dYzn_)M}6rSLjp^ zM*QvUiMz4(O$!vR&%FPOJ+nL+Q(7z-P8|_jx{ejhWI)~D+KIE_K2&~9Z2@6ad=37z zQrA$x@LL~#jm$sAZJQA&D4_13vuhya1@)C{AEd?!oq*;2;js4H5d?|1!_ilI&eIBT zaCl%gtmzQXi~yK=^92$%qCtmplW7Kj3Kp1mH#>UwS-u&@w7Wsy68&IZm2kd4b$dMm zQ@&Hze$Vwbb0q&ROuQ~BYetVER-m>+#AM8cb6gT%4`mrL76r>`q2TEOj<3Pl?sakE z2RBpKf<#>cbLzpZg4a)Tij>|(8!w(#I5SXCLDAnudK!j&-i097GO%%5WPZrC+yTnl z0IuFw*Dl&$z0)Vxtsg=?><_gkA$oMXz(sm*mXJc@M~$3SzsmMa;QG8O71}C`jq9W9 zpKa;ulb$9A2)up(Tff{VdsDF92nWG_q{!j%nL7?7vqupl%+=lLb1`a#nA~6%afAz+ z91y`6;ugprO*k1jaNmQ(rveWW54mb`>`c918Obl~QK%q|uAaa%qe>0`7X_5w(&pf z-f?iTYhakh;J~*=fi5t%vHnWw`!AIOh445I7Ms#A=hnB=e@*PY4J}Lh*VL+pJK??2 z8OgC9v}$~YvIXG8$Lk9j>Z)&c%z5t3%Otu|mmY~qE+2E9gYlnA$Pa22=TTSM<)v3w z_T7bI&AP5sD@f2*`^s6Bx-!Cp-v7>_WTJwEZYSj4yiD?3xkn)Z_{rM*{VOS~!TRL@ zU#mg=R;psR%Ns~-VEzTXzOsoTYLHfVwXbbi(#80Pv#$fZPSXj&FhkTjr;}+Htui za{5qL(V-7GX_FgWw?`A(8^Ex8Z5CRl)mD@}gbf z?ntM4T3#o5ab*|n}0(14DI9oe1~)A&w*QlRg3_?U%`phy1s=D>se zuX0fIZZaHvL2rG|=YfyXL$a&t_7*52Adqqs%gaXVj{o)HAj$7lf|GXv_`qI)4hO7m zp1Ym^x)tka_e)Xat4Hj0z8CL-LM;G6oAUQJEqhAy;5?6clI>M2+-M53PCjGc)iC$M zm!gd|GPZY#Hr52wZ}tToUc4X2&YpVYk$@fNjEwR1i0V-qL&-;XF3+^a`{3n&#ElZd zKG#^_a0KYGRUg)gQtyHU{`fOFC3g4<68aQ|_aGscYDI|@MG4-X!SY4Xx~Koe;ZH9? z^)|uNcL2Y4Zw;sqT*1NVu;uzt>eZy}PNe1w>eVh)>k&9=^`zK(ponOI%>S_blxW@4 z|0^N%7oKFdA{L%p55Q>!cMT=KqOJC*Q7@P(G?m8C_`ZL#20UHaw$YshipbEG4urEH zcZ*18-~L7_VTpSzZ|j z`!?6XHcHDokk__|x3sOWO?`a~68O?7@+Wxm9V8ymF+%DrNXQpD?@`1Z65hYU`abb( z9+!JD2Zrp27auR)d8D?QXdMOBYIIYYc5popOOYX(XefwF&(3=kai$>U{UfLOV|=@( z<*7L^Xndt_dD7uZtnVI|E1ZLqgKy|PnyII180T`braZ1R3|%RRAR(YZM{*kI0x+(Z z$Eb&WU!s9N>_KjAk?;_V!_+n+zhY2Nsi0dYP(3wUI3Kq2z02Wy|8*|afxw`86iIs^ zZGEzW+3%A3Jg$F82j(dK)T5qKqQP-Qse=73)cI`Z@VqcN>Nz|LooxmQP3)@_WRQ?+ z1>K`a`aTW$4Ys`_xxJ-z4HjF5#`N+cPnr$bt9L{6j>x2>R%gP7-w#0Sm%AcYk)bQy zRrU4;XxuOwcpcU+jc@B<`2^beMLzUmpU$xQuE-=NZ|`!z>v9l!HF^FHiM5*j-ME{FCl_=BIJ03gZc=7bjEWAbA5waxt!AKb8CpAcjss$q+_-}Nti29Os zeIyUrnuoHhAfXQ}DfKQ$s8M>^qY&_9!Wr~fRgYIgNtXje_gEfC0s`ySY}1pSUIyx< zJuR(^$93TInk;?rx()kI&D!6=_WQuw=DiMYCJrW0#2Lb2ChgijZoVyd&%llZh~IY) z!ySS_p3!Ke`N;}`E4ZV|BpCy_3>+e#8>K-730XbJ9z|Mn(#z1tRDPYd&$bx@H5vFP zfnmd%b$eB9Vgg0HRR|isC(?p zJ|6W&A&1^=VPUw1%FMTH083V^mH`ttodHJ&-QGs6TQB)wSY*Bh1oxW^T7Uw|A z=@IxI1OoLMEIDGp0)-BL?i!qY-`O zE9202l6NN0NJ!a(d_#F@6H`)89X>(UlyJ$kA{#77OpGg-p@j_48`*(;B>6G&kkYvr z^SVL;tU%`s*riA3P2e5?2j6N)-JZM^S#x(hjl2}uN75I)E+cDxkkiShai%|?e@g>m zzyig98Z*z7QSexsGRg`bE0Px>FFN|ya;D?Ef`TTR)x01YoMdU> z3|OETKm!v5o{1UTj`DW=>)`J)U4e4Vw=tCoCjaRYjOlL9fCY-?9JVHbfS{hhp5#}P z*Jw?#TSccL?lAIC2_W~m6>ZXdF<^nh7qboJ5)>9dga&hIOvaNNiVMB^*#OjM5{?WV z=%nJaKoLmG6Bw2N%2&v53ItM@Ff`No7YH0*?h=IQeu4oD6i;x``Vzt6wJ7~6dFVZc zrre%}0KMw{kEVjGemw>(P}JkCRxJX<+*JHJ`JJ@{SS2x_L0EeeG!8a8+GD^1g=ek_ z4&wL#vhFuna?5}wQGOFa;|RB6OSLSaQICu9+=0WPkv109j6XCE0>R zLp~i;*GqPKFXmzLiyX+CcoEj4sObVY;Jj4TH*fy zAzGj)XaWL+Ubs51pqTCMF9UjkZ5;xJO`Vt1h88F?$RR*HgIyPrjiU^X2DbSEg2e^{ zv&oq`b`T_}BtR_5rklw2<*)=d6SDdj0>*PD#MaVg+T+m}RRoEPSiOyGK_bS>ge`7` zA1Hlz!tBm9*LoDtgH!1Ji+ATTWjiO8f%WNO=n{0I(?kaf0>oCd{+}nr12jpDKACq- zO4e)Ly8Hid;(syLmrmqmSznK=&nzm>Pab-@9Rr_Cz|a(d6PYG9P!J^aU5Moe)atrq zI%brQ$EiDc><6z)f#G@N9my{suS6b7+7DhoH56m2*fDW|0!Mx;1bw>-NdcBU4ou&} zX^#yMTPh@Y*LPcAPJSJE=hQ;|*r=iUi^IJp9-f#qF@XX{okgpvarNJ)bPHfVOa2DV zIjEPMXcJx5e2A=9@cVWNqd7lc4Q@+AVE~7GFS#%2L4Z!=jaBSkhJ09G8ft`7_i-%s zodFv2)*d+CKft(o-??^;A5LCJR^SXhecH9{p~)NUr3ap+1Mkex2#?{pfaMp{eVrZK zW{VjN(4Mbn*Z0Yxj&Zq*wp=^|e(yIAa=;Z%r2r9PkkI{x&2cED4al>5??EjY09S{S zXOVSs+pi_HRn#mt>h^3|rBYwY4ys2%L&+XZz8YEp{0jd4fxb9JUvSdi%YgM%vfj%H zDgB)GepN_-nqnDDpulO?hYZaV5lYe%md$V&eWTNoX9j5hFQDS1p4C(le+O-^_l5?M zLOb);A{8e&h>D>E3Eg{87kM!Y61AGMRwcOp7+EL2U1|w%Uug;aQb`|n>V4{ckAjBK zo1Pk0+;utvKi#uy5T<_)1Ng=2EU7oADGR$!ufjKe-Zh9O`gDyY%@B@fqDq>s{*IJqj9pGg$62NNBFbxh+Wa%hzeI*<|_qOFKlq9{#JF+`UV^ z3KWq1UKl>RBbIfUvpmkWGI>z%Ty(@|Cu(WC-;mX-_);eT=9+5}{8*{Wo=r!lx1bhc zr#`YXMREH-_VP~)ZQO+lTqq7%L4O)MOaj&dnV8c4Sy{2qv_e534 zzq%ZQvj`oWdqXEY_)8BO@eh#LMUYsX2JGdHr_h})G<>wPX5iLI^Cul(y9Xa%x&ytH zR0iFnfWY&yX2VJrH7|S$KBF0$EKMK-qk~rObp>XPfggT#RpMqF77Dz%&D+19$fH zhISS-iSMoLs4A}|xE=+Kb0YBD3=*%mAW`07CaENTaWz>d(>5R^HJPGndi$YqzA! z)C`0Hd~|tCxxOuP@X=t7&mejfG=Ls|wiP5aiHrq_w!D2ndhnYYMhCAZNAjLHE`k{W z+yd#jiKBYv7NnQ02h8CfKO-v^q28t zeJrVy)LEc_V7-m$TmNm48~pItPFmiSI%5D|UJGIWb|x@e&P~kXHGY2scj8QvF_6swKD{V=@5(OWY|p~@^?lByl@!$aJqif@AlQ5diN9Eo zDCq%K%n1Yd+uaCi<9NE)3E+xCTJ2E~BvuCB)fF*TEpAiPRb|Y|J7oYr_kHi}dIHmm zPC*w4Ya;^2A@~jwheP0t;tFlq7-*XTe9-p^cm-lnt21=@HfXwyFzg{#e9nY?4DGYq zv_e}j20CV-g`UOJ@cC9gz2SpJ002M$NklXYsoB1@oWk6Kl^Ek}1u+-As zASvA-B_RUR(%lWxUAuI5cSv_gH%JK5-KBJgH2?j4f6w#ozPRU}sWUTY>Vk0sny98P zRg8};IUq`pqS!6GpwXw@(Kcip=DsanZY|fAZL$?p?*C!86$^Maq@?m*${8e1g4FHzfeQi+>*K{E4X$R7Cw^eZlORN?1Z1{4jj}Yp!IDF9=+{@dwrzb zvuSOqy@9azB_6XXQ?2exYy0iojkb*D8i9}r7))L@MN~N08TQ$I5>NLn=pnVBI*{gr zOy=h|CdxpC63!_Qkc=|($VgSGy;Cnx;3KzWzXsM8v&@OTcz=>l#?k^&Z)hL=1g8`YIB=-KaQ(w zej-_X?CrbUxmj{|KZH&z4H>a7>chZqO&mSR1U%~)g08uU(T9s>A2_q6$RUTsHI2Qv zwu9)@H+l7Lx;!AzPq^U;JFw2rAeAxaleH6xnj|2p9pD<|=#rsnHJ6R{9l}Ec>upk!jamF%sxdmspg3^!DM)+2Ds<;x%@VKrXNB zd7OUHU(c5m+l=D90#CkWx0RM;XJ#`nI2*8tl)A@TP^IC4kb_n@ciVz^@?JVAwW&SG z1Y&yfo@npn@^5(d?m_*DPFPtxR3b=#2WQsYnNMJljxos`?D`X~Z%4wl_V{bSx(|NJ zxeA;?9IHN3#5E_ZNQEoydnSu%z8pw^K6?|mcmJYKp2dWOnk+!6h)z9O1>86y0^;`e zGLWs_KMP(l8G2(SkgVg$0v?>;e-eIeUM&d)PpQehGeNp)93f4>kJrBiu}dzr75QTP zm*}hU1Ja;_4JmxlUNJ|r^TU5g+4}=u|D?1f zkoruMxx~gy%7c1ZDfYGqdS{__>%I2A;e(>kWL+=c9v9r(aZ-So|Dcm@6ZP3S<8qYV zejO*&yd5EpfuG(OHr)>o|I3~p={v|wg14lTvkZ_&li zFYb7O*OqdOXyBXt1d>&LQE~T6t*Vt*_$o+hx~b5zWXQjPV{Ce1DG9uKA;Vf_~wK9H_D<^x9^CQx!$ z`5u?d0ka`4DXrCk$f#;9&g>Ea?Juv+=W{$y)khky#7#DX4l?sUU;50;ok&8U@ZwKt zs@m;yXmV*}GU6Zj9>5J}*H+GnUsZgm{&w)0>LP3~v%y>mR$*7KY%>SAqA`c)GtHsD z5@G7L$=GVm^2;@f+FsOYL4q-XLJ4{!E+g(Ya9Q4ES-ZNJH*mJ5;rA&UZ&N;0H8V4g zrDGlA$*VLPu{s|0>jnaVnNVfJnm&9<5jP`6s zD;4CmXJWTUn~vgFPLA|A{oSy}{5Nq;g?Nu>i#tZ;GZq;tTP*#LB!AT!*oIkTTCXPV z{+yKY(ULEB+q95;sH1d#kFCh}D>03Pv8)a@t3hy;^FY__DC8@WCn)E{lIiO zbbY?$J0)-GTr~vqgIb=~LxT4QI4_3$wfWvMArw3|Lo=rlxo$?!r8Jzp33hWIr2gL0 zi`lP1aT1N1(-Zjg0{_d!>N5>NPN)1Tm?c-@gI;Q-C*xM8%mo8YjR>D_@3)ly!1WuR z8~xk)AXRaq1Ae--PpID$QO@U4A0~Z-o+8$%HJYr^s!iItKV@TF zurpzsX{moYl@;g4FiGwXlQ5JcsA}`a{Bmn!H-(aQn>ekoClv^?*;=vKBES>Hr}Y1B z|5N>Td%%GG`Oz?4;>G zWAYi3X1j1JI-vul1;>faHyOF&+!sjCvMv%;;{dk-IM$r$F1(&)%WYyC~GN9Z^e(k*aAa$=ZYDGh{Nbgc_;mrq8p! zo_=zLwVphPw;nLP2-D3p)8C0;aTlxD@LMMz%VFi3=H#6FXH>gxHgnA!g@!-8pe_qgF|YYGq}44O^Y#cjc{eoSEtNs+YI%#k@aTr;i`1;i8e9)sHrfRwK3yxOvCPoq1|o%yx5AMXZk6VBL(W49)o$#zhj8rd{@AYU;mUj$c44H#?` zBi_%vN%o9sr?vA~?zrtLspdqKNf%h%?nPJ@_aF#^ZoI5jE&pX?DvQ@CJ50~_=Fuxx zeUk(wLf;`H*;>th*XT(dQd{J1{nR@}qqRQ#UxN4Va1RCQorOh!mp%T&d;tih9c!(Stz$ljeF#q6#4fU7sb-6?uSUA06ofekH(?|Om7t+vy$yl} zJps5$>H17MPP&>I)IdC=QK1^PCvC;O#9LHZBvga~;}V|tYXo?LMRoc3$bo=|9Qcs+ z7>vRXsNx7hbro1%UjWw~cwhV1c{b-_A{{S@8;F3JMiw%Mbdp>aTg_GGB9XaGb>0CY zP#uzzTc$6n^KN}$ zktZ5T{TRzgsXVZ+Jh5E;YUXVN3%?Z-*q>^yRQRQwTJOD%)t_2(EASH4iKzrNu~h`$ zJEgOEa^$RYT!f3<9)#Zi()nY<2}snp)rv6qiPdw)muFijpUVwmn}<~DV)5UQ znokg+$xN+9_mPZ)kM6g>I{Mg(J(DCe5NWB2M2_WZwG>luUdY7Nr9#`yG9)xg{6GTK z>qTP5leMe+8zGpBZUNIObfB*UWNA{~D z^!IWzsTcbd*XRrJ@ub)S9q|*BJs)M&C(W!7kCK=GQp8A?=}xDt6@^7Aq9qgt8{s$v zaTDND-SCZZ`(R+xC2+cUSZQF;stn$8OI-SXigwr@AF!4?umK~Tz+5B z!p{V@Z#MKIkT=!hr6J?0PD1Z)gGD^g>D8tH>W|em zV5D1vaCC+*6RwiL6RiagC#ueh@Gii0R|Tv}+;o`WM2N<=$KGQY?v(HJqg(Nefus*l z0De=IL0VjsxAKi|35*6kxyc`f)v{ zrSDndilM~&Oqq2#O}pvmYP>yBHLmK>bYq6d_{V81$5lkn58b7$qVD=c0L44TyEu2x z`$gp`ji6vVvHjv_^20s~+~sI!JOyx}`Fj)w%14J;t#<)}GV+JBO3C40yT8GI z3*0GRRHxCme>2SrR4ZyUT1^Ko{3BnvwpX~ArjYbpsTUAln-2~var3(j*Eb#hr4<+G zhsleW`}GZTDK9O#qaVEmwtz+siKbn-iL(3%;xgiMx(5l>11G<*0#&XJ-_~f z@zZ*TllKQ&aVFmnfEf7x^95Byg&eQ=F(K)Y7M=pQ(r-ME%@Nn!=r#S{UyR z$gXKaP4H1C6bWkTVeTDHV1MD=+O|9#Y3%^UeMI)c^IMLyr@DYH^`gE&$TH5*oV> z%hA!3FHVr!FLZ8`qzp0>bF*5Wl7OWLPf2Xa+8TbR{aRbv8w&Y#ei&>rU94MMRbq9~ zeUQz!;ZV#N`>M7?kLu3maxGB^$vyIACS(M6IN@sVr> z))2yPI@fT_{4EB3N^QTvVuWjNe~xdZ19*lJNXVx@esO$Z`DB;N!As0skUOXxIQVj3 zj4^10+g-kE;Uo>GG_5#PjjRAE0)Kl|JwCqiaLA=xO;A~EXQP-lmAQ#3!KvC=s^fh~SEWZ$8*lZnNf8^d z4c&@^Ez^cprE_|Uo`JzrgJZK~UnazI=y*^2N)9P90TN(_Qc?e6$a~bJFEv>amhS#j z)QA&|d_u3nPlrBu74TXj^_~|I zM=@!8b;G==J1TH|0hE^xcV&eN)BlR(B@=lIYc&GnxXW9;s((RYPhW<`2`zd%#(aX? z$1BWSiYX8qCW<|+(^EGnE_=5PG06IumWD39+sR&z+WGrxi6xi9R<%@8zoqw_OJUFW&80lR z8Udonys_m&4!?hrxYO@GtXvQ8--D zv2*HtrDF;~VDgH`wmy_GF=!o0`7{5ugn~m7O}q^f%F4E^naCZPP5e|$=T^|*NMAMx z#q3Od(a9DuGJ$Jxmnyc#_EXlaV*~4SX(gb2HhQGD^>2bVRhywT!LhtJ$K{n5_u36BGPMl*)gJIL%m?jPuz7--8#?;7E3g2LjudLu z)}}4q{?tw*uO#y^ifn%RvRz7wD=Ev~4m zsz#9(Yn!E!h+d)QCT<@k1|;-fdujjX<@U`C4Oe#Ptk6wB)Pnx2WJB#)rd+yd!M~K%ktfTLtfv)=I^y#v#4+Pw#qqadp}4qImZGY>DfoxnxN@Fgh%g~2n=qxG7Oj+ z)p7t`fR&C7V*45=91^uZG$LSzMqlJuGw)*+8NilQbfaY(_QCX9W_$o_A``pDwmASo zv4U1-44p$tej=iE{d$2pf-&nfqo=2?2mMz8|K@`uqsWj_|-_6`v=6x zJ1Z&ew`3N%)s3}}ORDD%2cJ%^MSsybUPtq_UTze{V-wLdG|xAb-h9DmHiRXd^jV%e z;ps@`ALBjDUsNunJXMZt1uetA{#0>t#prIPD!8N%^40!3h4W(63sjdBuLO4^Ta->s zry{@pv6003dT4j8DyxcLPzEtIL^bP%bNwSov26{|^?hy%hQ)*BZ;G`@YVi3?Yo~n(y5Q&>phq*V@MUxnClYcu^WM%YU6`zwl&E3jJoQ zFZl(l@roT8Q}w`b+=UAqWaAn8lbiLqv8IKB)=ZTF3UBHl)&lb#8|?i9L%uR}(F3e9 zw+=^2xV*o<`H1vopyE=l#*q(~oVm7Q2UtB@hqgNkqTs*;7BlR~gnKg0d&>XW=)j@g4V` zawnQtO(Yd=6=g%q=7cW+c9toi?79~v9PwUoyyfd9WFQ3qT56+A@3TR+IlBlP_E0{ z9iO}cVq>@^s7kNp;sj8N7|A#HTpqM}`Zs-<9O*jD4fOihm@Q%UWTGLYgGE{>JL)w? zx8ISY^JG4;MuJ!ThS7v^wbR&z5B=>a{TnRH_m#L;DU}TIxH)jJRuUEG9bK6i-~)+J zz6Zt1m(?+VjQx?_SabKmGLKpQeJF)r^M|5GN&yUaOxSo&_>d7OEqb!elh>u6z~Hc? zZ8l2Z^@;N7AcL#y+)&YEc%aM08+l<${A*CVG&V!%=c`-ez3JAM?&wmA+fXcQgW84klg^R$avb>oh9oJ3_37 z%te3G%u#P!qZi+=Ra{7POujp=o@@>p%(#Ezt}wFiu&aYgd=krT_qP|WRJ`iu$0)+< z51%mV_$xbeR5Nhh?RMN=ffQOxEhk=h+FM+kWqn5C3p2h|zK5TbYN3T0E zRIfZD$yFm4c7y0eb6ksH@2~$>;(nX{?32D8wS6r9kFjtUo{KleKvPR|I3u~6 zV%vI`($5=@A6s0)*W`TJ{(|ICERT(Q&h(T?=43UEih4pYVn@Yv{-MW=*{IG{%@D&q+~iMu@6UM2P0NbA zJ<=$gn601uwBBH&N2SNw$#e)A%I0VLVqePNUSsRRDl|;B34&DD^D0udZgbRx%QVbe zQqG2B*>X2NG!~|bM2>imyfKa0em*9DJ$61oB~vZG84>*DZ-8HBD{f-3YpwM%Fm)Z3 z(Q(zHyl+cmAc>4aLNk3#McwQJbDTQRVhgzAK=L7p8<9cZC$JqS+p)e!pyBM8zk}5rhvj<|cu3t$gwvT)#Q=Wy zc98)J?}QkvC1AtAc7RfIMhMYz+6D|dEdi!*pj<^ryrH~r=7?Nelg2Q$>-z>4?M;Gu zo@H<+Zh&$F73UQY4X+*uKiry8ML5Ru+CQ_$d7&zWG{es@dE*;(Iztmi$tLY?`7hyv zl-(i+(GZvV-3mfLRuHl(e+MLBWWpg} zSL~fSJ|T?PjB;rClTS3IT6KzyRf-f+VQF+iAr%A~csQf0Rn+Kx(E_Sy%!>dsO^p0A zEhrigBSN2HJ5xhPk8ZelI;QhRZ5jS8w|jtiyq)>sgZ@r5?ZpF*RRm~N3mw14{L~7o zqN*ab$aLRGGz4K_ZPNPj4+I7y)xa7hp>sS5H#`QDcjrm_a;pxjOx*bnecf@r`La>0 zUKYLHc)2LCgS%7z)xzOt|D#emvINq6sd#0k@`Vbw2+($=*@+i2Me&a5#ud^#)l^K+ zYLRI_#!qMIjgrNatskq133!O{-Ok{l;X!#xp{62Ke(BGdz4<=?`|`;rN=5<|=;kFw z!Z2$5a+#Nvg&%&$=ui3Jw#O?3*p@y7hKnRu^*Xju;?vLL!`{*3Ty7wPA7Lv~t2O0s z==LLV7DRNEjt@{&Ze=&i4`t1Pm4_a7-ncUZ%nW)R6gFZz0ovDgRZ@5J3;fhiu+n2` zffQeozAcPbR`hUy;RH8TKsvLYrET70jwQ(hT_ei|yN-7(% z|3n?QE{#bg9b;N}0e}kyj8r4;n0Wv}uy>F*?v-NEv)${hJ)zu?7zJ>#{`%9E!)WQ$ zaw~If-6=OHbOPeW7`oAKv55yPQVcp{>x{389pE1Q`xb9BiUuU$U+7hJ>fv22cV-+rg|6=-l@bYSa9ZozD1!!b+FE1&sq{zvVu@@Z1Ih71J zR^~CEI`Zi6E!(a8@N3>ld4V}OH5%H@m2drcd+>=oX7|8q32wT(c@JT?8RI7czrUe; z>2>}k*jw$=;wow+GkG|XlLH0(j7Ae6CYr1`^gGF@Zh6TNR3$kLt1X~)7Q}qyc$OPE z5$2k3E25D3ta-?Y$z@0?fi|yJ;(km zrU0@~J%_vMbLBcKe?L$`42&VFgWCuft<(zv2x3O5zOwFlBxzQBUHnA?V>um&qVNWL zuXd`hweG6|vmJQOtXB|^H=@zzCwK}v<%{tYZ}_>{i#+muBhC;+2{a*n|7zw}e2$$L zDSv17A0J2UJlHj0P=NdLsBPhjVa>%v$XNhCi2cW_xT+v*cgb7C95=?tnXiDI@4x~~ z-BY;*sxQ}cGIeI)n{=pLUpM;$p(}@7pxW<;YgzmpBpfcNn%1@4t;DBI#S;$iuzr{T;3>N92^)a4p(6IWEBmu|Es;;%53< zopzQv;J*^XM3jj&sUtygaJKH1c`t_{4Y6^Jhy$jTr_!`GmG*b|5&zizL*Rsc62<0( zM^)N`dSj^DZ&a>0rQUuB!f6EFXv)OBahZ~`L$dF<%Ycr<#){Va(zc&`t+8t z`Gt>ChUWdaeH`Gp$Lx2kr=JFW*=Aq20j;l!OA?EmfyK=m-m9jPSxWsJC1?V4WN=^b zJ77AG&n0k9kzUaXY={iiHC%rNJrr*jxto|8}co0I@6g0kHx4vn~(0+rvzdePIxxZh}1+^NgNc=K}JoCcSiR;sEP+B1u&f zfma_8)Z8do+(zJr2Xx97>+_$HJDc%t0qcHW`kaN64AS zMZ1m-udENoVupUg_Q^_r-rfa%?`pxs_ERJix(+f-Y81(<8eQh2){PEEz&zA2>yFy} zTS{S;H4;ly7gS8MqhCRXb>uV@H!|t+-lN~#x~d;#Z+CjKJj)`Vjt(|oI|nHhy$3CS9X>0$DK!Ll`0FMdWccj(^_wv2n?bb>7mX) zOs#@tC~<&fQ6xO=q_B*?+mU4g>%6I$DeGKYx_)i@{88e69~kwQT1Q}0;JJ-ZX|61? zc|PoV$V-T$($ZI}u1MhnRlp`Yv?KiBVSTY3SxsWykdO%ZF5Tj=@7Yx;LC(BF4g9+W zOLS`RLan8L9ck|-jV)wcI0p>Ao+re;BRb@sfSq_MqAjh31pPFP^`lfKcWb?$2^)g1jZKIffUWt1Tm#`_NlXIS8@4(Wan8y7dd7k zeD#W--CguYYSNsm40H7d?_7Vvv{<`|s3beoT*>_qp-uU7g6xJbaL9IT!~=z~E2Gmo zk#yXyb{Nh{Z20YX^qjg@Rq0p0?O}DrWc)`tmZ^qfxc{^>T#VR-7J#US)&UzXJDw^V zKK%uSs0R%t*_ad5ZUhl1(Cph(T967GQq|5JfShR@)P$TFXdV3@3q%1Xm~+SVp}&v# z7xmhI-6KA5BY=L_SdPMuk24XKf7QfUT#})5GsX~Eji|!&{YkdelYJHp?WS=7aWSOV zmQjaq+HT=Tv4CXw-UsSHZuudxJR+**D%6d*giW#B8z-Xnjt6Ixv7BdJn~49`ed0lS zVk(lr({)7e%yoOKf<{xT`lw?bf(c|9$Q<5n(n6 zg0|Vt)idD}ZRPvFe=w*Rr&rRklyDD-?8HK9nrR$e$bewU4M7}00t+|j8TKRXj&tNu z9tjMm11@8x*It8L(j#wU4RmqfC2~}yy`9cH@g~KRq*TS9M(ZJU%z?7DUX3mMV5~e1 z#FNF*q5ShSIP z&-C4W!)T|(Tvu+Kgl+woLo9lh23w)2Wevg68NeqRN8~Y!uypkE)3NegeoBx$(xUZV z!K9G~C7*xzGb;vHRt&~F7Ghx1FF2=j^`%#ZtEqE6y^t6otm_+xa(I{>E)yd_n%lv9 z1A6VE&Od70P{W0!c1s!fg*F^iMB1iRjroGm@=N!U55F z-Rw5~sV!Pah3CJm?qi^@++xw|0OlL1ZR#$%!j2^&Y*SvXfSuVv4@O7l+rr6rwR}_# z0=T;F!=v`DR}hkUc}`GhFC3?)LnxWzh8yx-v|ak|o^JJ`*U zcLg2Ib3EI?itf^7qI^q_x1$c~&`p^9MFTj+q8C^O8REk@yz)gg>)vzf;F>9X%1oE0 z5U2nF^*^8aSnlZAd2%VXXS&hT?-23Q#6V$AVY)l67cO{Vm0J2{%`wN8ZFh~E(_tR{ z6$3G*JmIIexpQu=Q0Zsv*;ySG%}~C5)3e$JmvwVLmen$~kgW z5^G}?k+@FxlAqh>Q@g|>D|HV$0}jlRRxtR;ImJ2`)nx2vp%(c?e2CD{aW4H3=AUsPyeSEufj z=-DBwllH8upgwX7gJ1qoNqbR%gLA7R z-pO?UZH5EUVkv+R;y$0quS4^rb#l}Z16Wa0dVZX069uI4d{$10bLxM9-b4c?2ptfw zT6{pdj=U&EXBumZ3@2Sj%3EaY!FnPL$GYuUy}DauBs@0%aRIhZJ{?HF;XtwT@3oh# z9Fuv`U+TM8$!ei=e77WCn;_=fh6Q6j5Rvuwy`}7z6|HKiR0mky7r0Gc(QKB>C zZv0fI%hPe~mHp)HqA7GQgcn~v-LapPM_|`j3KT+S@b`FRTebO5xFDQUh`?;sjqr`2 zj;VFA{fKNO*D%ooJlC+m(8XR7KXTXZd~Gr$57x@b@0Skbn|8MULyHJV&C%OtP9UJj zaIDbR{rwI8<}h0~Fvo;yNt%M^-iPX(a!=HaenZZ*)-ETan=CJM_CFa*0GQlJ?)|R! z^KmxpuB>O#a`>~xIG*~83(k0x`rrE((z>XWACtfSr!$Sf!2@uYPnv#$+mPF!?Ye&m ziCYw2VsqBL$Fo&wKGUZ?n_+!J&^K8+E&idr`K-x}BuERJ3;nH-du>ZJxu&puDo{rvrqK;Cdp zJf58|Sk7o|>^Twav*FCzmhbTR`N;l~+)qFHVg_<(2Y#oK_&4PTD4QPnpfqWTmeYhLF z&aJen#eXs*77uo0n<|~ogBS3#V%hsnin#Amv)*bSU+vDwaq&WQAJZIDRd8-ZCS4mW zs#a8^{(t9(h=>uGO=u8neSQq}+IOB2lpL&!OL~fTMf#ZtJJ$ab$oNq>hQ`w; zM+sn236TTc53W%7Af7DE0~+(&wZjiLqLWr3UaBVlpYYm(1X`>y=oCg;mA68Lvs_k} zyE(njmBsGQh_D~IOFMd7`GPn1vK*5fz)hoY!+D?mZLyY6HSzH4$t)aFL#=cuJwn?ilm*uqEMN{Xl_3XoftvZeZa*0$-cpx5aU5+H zJ=flU94;56hk4jrFc14hB)=IGV+j}Hy4_hgso2$mfw)%#yq6oaDNmQ0IZy1(xLU{;IrmfQ1sQOhUPs*z@%0x%Y^JMPc{W9hkP=br({Mi55e5{8G6PM=3@4vggIVc?4uy6*6 zS<|jIFwG@D4kM)dcLAnBb2T3#Sx#+J-c|3rHT_V(WIlu4E zFH0=R6Heq+e7uYep{OLEk3 zRWZ>u6sC_7{^(BaD@`!$w~E@w>h>8wno3x6G_D$N+02oBdBt|xuW(n(OvNImIy=Fv z`4<+BE>Du(hALWNj2e@agn<}*7=xj3hHW!*tt@ig%tH;{N;)<<(jBR#3lq+@l+YO* z4~BM(eq^AO5N<%Zp&y|Om)`7K>jLs>lN)qBTzabd#=xYD7Y*xZ{lM=5Yc>Syhktl4 zIEfT=(f1?%M)8VtB(rHWk#mX=8#8b~PIWuz&?(Jiu#_W#>sfQYSM; z%5p$s$h{j*i7>me%SKEO`5c075llP}D(bKy^jm008)L62R3ip2OjJyJ>-XstrPj0! z-goV!7NbPzpFpqBX{5wBsuB^72n2AS#ZJZsMMrk0PX3)R?weo_Tk{Hx(AwC=i}AK& zWoYeYT?$lxI}^>TwWz>bnv+Psq(@c};YW>NW`@g=F#o3SCotTFKLmM-qZsB=&SsgB z(AODxM<})!gnq2nCxm*-xg~83WBlN*PjjO`;Cq4Z?A%8g^k^s>~B!#KdV96wlCLf-xV| zyF{wFRf-SSlYcU#QU}C5Q)%NC>4`N@1e1CzL~?FL0e-%|Q5#n5rruyZ=Oz2|Am z03Yyv{Vk27GgB0YUIAh93xn??NvNoN!;&s}jh`6IswDbme#{A>JedF8k}&V0Uy_Sg zX$}Jk%ANng_XZvH_Yv{VD4XMBMITL#jquOOig}yj8|$XGW^-QkL*?Mds(p*-`63LL z$A)Tyda{WciksKHFJ1GIHdU=K$^?(~QbO;2B~JLccB%~MJxw7Rox$!O+rc$o z$x*@ju+CIAnz|sa4wDln@&od!FDpJDqMuk`1-!yRymMe~m?;$m3(L^y8~MjB`B;(z zG%V?XgX<5=6=-`>mS?A~W9m)UN9I_`c!%hE&6<{=)m5HUcuH+u3j z(y^I49JNd2@?g9ht6D$B_)xX}jd>X)a2RM7v(gn+)qzEr0Apg}N9O;`aWT=9zQX!? zw8cfXLaP^V+r`e0qL%75QmSWoR|htc#bwyq&^+&rPmA9}30# zf&))0E{H(Ob0{(g2SE4~{|-KtD!6dx4Pq4kOKPN0laU)u*bm-96IX}TEP0XLcz2Ne)qVeh`iFiK} zVYs<13rHS318#8)GU+!E>HtJEt9mp?bm{?p+UuL<)WuK>N9rPHaMYcd#<40P^=KgD z?1e&ddu%`S2#`*Yh`-)`upE=Soos@`{G6}-{vTiyE)R}?+Xyr+rcK;RIH0uk93Z8Q zyhV~P{V4!rd?S<+!*)*6Ny`YNHus@xWE7!~8z&pI0e1wQ@)_L+GT^2lU(^zF0L{&f z?7?qA6EW+~ls!*@50PJx7lqJG{5UwCKKFU8FY5T*D%TY)bfJcVEQ05>aRT$ulxtJf z1NYrN9E=&U*Exi3# zbx=OxepO>SRFQa!>b-&(KenE0AP=k?}NLNc>6cpss zoh(%>yCA+g%`2%&7wo=U?qFrD@rUBj%}LVB+_U5M1bd?2GdT}0R*=#L-jHNJe<)?{Eylg$P0XQ4mkr=4eRWm>xeos{ z2hb5mJ_YivD47&#x`Cz7O=bJ!$IPd{jvR(Jpk>Gsv9eGH<(g(l!0aneGb`?4H^HH4 zOl8m%eMTo5o5itxl>#G%*r5xT@voG00QVFn@W|_)Kp-r%GPqE!f7BHXEDE%;3;hXB zhh7kACAiEsMe6(z!Op9-`yaR4I4^{33?QNHSOOi zDk9L$SMj);8)Zj+j^G~-H+GkSFe%aI%HIh0YjqF3oA62{yU``wf3NW7BP>8Nw}Ex* z)9JwhTd4xNL6#YSZ~xvd{!L%|&=4k@T&7#^ZFF)!mv105;J!>@NH;>dd8!6Ygf84a zhIux^K77boha>AhS;|p?8(BS5IZKxX;8q@h7ywCshB#?oc>d;lTSWj~xT8;rUEM1I|~SL9#KjxdZeA|dUEy|#K?&N^xU(= zn&3dTD5-mgA7^f_|Di|@IxAlCYP)}N5d4|eq2}3zX~nYS^v9xqAqy%`oGwz3Zxfd{ zk{qC^Apzn+85a~Y4FBOh zm9{9Q+m6aGLjQ$w>Vuq<`FHoX7&5quk?v+>pbM9}bwCg=0y^93>6KUkClYDML%eVb zsIW*G7aIqIi(Ph16&X$33*0ahprtBb49A*acGgPm$+GoGo0}Vp4#+H65I*CeA!r1O z-DcC;Wnh7FO`THu_1!#(sW<6ZP<;lq<3yU9%&iG#LE(r!bED?jfpcR_^Bj=84a*dY z0ImN34TY*46-*siM!^ut;dZp%mud~JBBCmv(xnVDSI;}<1R`1*Au`}0{;T^vmJEHL zvGDhopatan&M+R=kKI5$2yC5Xjl<`)<*1xl^R7aeJu_X{j6wdA67NG{#oEgjO`DIwjk zv?z^qEGZ=+ARx8yS-M+7zy+j1B&3Az`upvF_j&fY^WK^B-kJNJGiQMD6Qf<_yz((J zf89|?fe8XHS@a?w>I4aW#q%#1`Ic2bW$ny6O)nD17z+(=Y_^3*!4OvA_Vdp`uKw&A)=f2lwN6+~Ay(2Wo%!~zz zi2+_>r8pzhMl2z~=R?uwv*vo9fOSPZ&!@G!Ys#SSxXSlCw=V^CQ=ysrmAPFTz()KM zbh^;)xa>%L>sRhBz-W6|U4jC^h#jgu0Z?@g^1VZn54$-3RxBeM($ZrA)RDmG_Q&*A zm+}U$hwMJKw(#mO2O4?VmGCdyVcF0Ix}=Y8%Xg8eJeP3VQpia1m*g45+Ubu1CrOzE z7BvgbEGqJI2XNN+QQ~AlyIyiUygimHnolsxm;UyzQFl;xg?yei#EfY&v;b;E(UDYv z)c8cR74GZ2^gKo8D{a-wun-=^dR~-B9nrAK0Ml<^i5CYll0rt zlc-rd6Fpq&xX+>~#q}bHKAQj#^SNfIEf+e#_lvF*k@>+2SN0n6-rD0OCMYbY0_nKb zE;rzp-A6@TWnFLB0g_@~%Dv(D-Y+et+wT!kP`x}ztG~8CTnkguo9{@*Avv0 z0{$GTuueC4S&U&$K8jCZ&tc@w!mT@1tDIS2D>y6E1U)WYqY72kkrA=0$zOIT`5TU5~ALC3pIn!wE(X zm^RG7^{DCI)mu3#8;g!a0fP^~E=as;EZtZ9xrb*1M3xMFS4WV~UCJ=uk)QlHXCZTbS4-kcTQVptv^;Wep!+8 zQ!Q0xoiF!}vrjJFH(&B@xp{N$Olq$A+-#;xXrtk|y`zM100QTWqZ8k(u4BHGsi{^X zU*PFU38TwZqLD88l8i|7#FPbGqnXDPpC@qT7_!3u64fQ2eb9Ab+F>s@{~9t(%Ec)+ zjlQRl5kl!h{=kRB(u@6wJ#ihx5x85ALgahsysL9UfRWOk>ip1U{P?(y&0b|^EE%P4 z>aV=5F2rOV`_jDMEFxuUv@5#2-%N|%q>wfTL4LS$l&(U~ZfWw4=kWSYoPv-&qcRFr zU3E~{DIZ_k;^T{oBnPy+^bCT?qR_AI;ut={Vo_+6(z8y`Fzq4UgG0Bd8BqVOEgQ$) z5@-^cne1%%n1H6$r|Z{Am+7p*>fl{Yhu0%f`KQ_c1!o3iTpFVgoigM}M&bo$_Hk5(^Rp?bjMRC`IV|&&Swk%HkCZh5v(~{8jLKH!aD!wg2a>nXZDnfg}lrj z?cX_jH8DpG<8XAu5E`++z>D!F`PAuz&mGJiI!AbnIyT0Q4hmluPfBNiRO>Gzgw#cx z@)CcHk>YdSxZ1uiz%$~gPZz0w3393Ui?iz3V7c5{P%vxX!bn2h$=%1u+Dp+%5MHY@ zQ8R1}Q0rUROZnj?MPcpQA;*h~wX{cU3pXO7ZWm{FdS8l2giInY&ALg?I>bD0@ceGm z4v5-;YJwC#b3g`(`3R7xz^X;V4DHHhMq{gohD>cxQUiT&$wa+{0P1Tx;p5V@N(Y1T z+fKvr^pU<<-|)g~73MqETBks-!M|i*{mQVq_yp5Hfay7r9QCT|YxUA(NV@J>EK4Mi z6-;#hvr$Ecium35tCo-)VR{uVA2OMHc_v5dYu$Y`!mQ><4?l04qbu#>F<91UY#8+9 z@RLdWU_7ORjZBNguAR-9)Z{K^gY(MrE~+H1O@C_oaMc}6csGYrU(g%dZ>Ldfn1J_0o+Tnd}6mB;-EY>1s`plWx8O5Uc=;b zbz-nC=K8M!_a6w#M3R zJyAZi1Tt-o*F3`N2E7igmh55j@|v1u_C)rUdj@hdnJj!*CCS9{%RE zBWju3yv@K#L`}wqbJPY1S8L&-QM}-;ko)VjDxKkTTBA0aIplJorceO(Iz&tr?R%c- zgd82HTcNW2qT0mYCu6C?kO-X(%*ZTz%d%HK3m;Vi(8H5?R!e1oa}{>stYCq^13@kXn2Ts4JbD!jKPbe1@YS~q*- z(wyBkz&S^`z_KIaz|@cCT7T!%SmT?Ow`+wQdst+F*9<`IiN?EqH>34<)&!wC-FaLr z`BIYNPJ&uDo0(aHrBHub;IAKIMg=Vr>p_NPAV}WKAA(Cf-=7Ks%^V+UjTZrYg3f&( z6|S_|OS|ixlgaaKw_=?F#=J{5fBZ*X@TsvzK5sE@)W=g%?5;$`WZGi`{0 z*bsfc&dV4f=hA5(inDgg9T+Q?tXupSSGc`i{?0^~u!G#_0kBox-`|-7aZb#!u>E0I z@YA;si>Pli_r6iRadp`zaNl_II1@ufL03)dZt}fe&+^YNAQ+<~ci=S#ci%HW^&Jn5 zpiTq_!dNgOjN}tJIv&b2(Ip2xyu@BQO;w z%LFX8wSIDcleyUXwP5x9^b=jhUrBzu=>QJRbBgaCo4Izkaa{ReIEW8#`(dOyjZS+J zLa?yJ)wZe8mMszI%UBH7w9OpGSp31ZZOBFn2z9n_)~mhej0X`-P)wd(T1ZN?73u1h z4(VySe4HaorJPjznL#$r`+D}qmuslV(gfgPG6%9yn3%w))BL*iI98tQH7cX-MAniW zM)@s=LX6e=8M3}e?2$Xakv#YM)i39@W$2e7T>~&0`|?E}RnSWTT>YVh3SF+RThnj$ z5A}XGi*bcYZ#V3xjuM zwHU5uf6;p^6+4X;N#Xqa;^tECr3u=)d5C~!6h+7L2}O&-LSfq0AIZ?4!Z&(L{$0Ia zL4}GmVHo@AnU%`G#9grXPTF&#al1cf$azkQPu1J83V5(Y9x3Y+gFLbnSvu^)si8SW zz>VK?lZ5{+RZ=SpK^8G9hw0yd)sjMjrQdl7imMc)krY{`gALWZKp71hnuTS;jip?4 zWH5$#s#~|Jr+LFb<1mX}=&(Jc_Cr(?{%vH*p+A(19@BOYvrNO!ZOfP-qJXprY1Cl} zd_+JG9~XRoYsQ&SYsMXttU%_IEKRLJ-J?T>Z?Rc|vPCEu8vOqYH~QBXiB;9sRGYme zO3G?%WE@^pH$kLhEEYqUFY#Rk8e%6k+Qq04d~P@7Ge@1-b^^a7C+=uYnCCZe^wh$* z5z~e?ihsRuwlGEIM2{==eLYo|GI2$j6tAlxC&r8srqm=>2rHJq zGYK-PH}lOg5y#g%l#Ac56Tc>is^!9J`i3M1P+MUb{U%T}%~e3YfCl}vJc0n|D?nn@ z6!sy=gkCJqWu6!Dg^n^IS963>dO)2kPZ#?3TDMvbm$_jgRR!ate(&MFoKW@1G`b`M z@l(prUj_Z^v}D_g7mi!DwND@q`4b`E7x6}AbA3^}f{p9Xu7~0H$1tMqo`ubnjSZC8 zDU8(ok9)UjgL%qO-=>aPj8Z6sW2|&vk<07Vt!&dK;LT+v^nmPx#7!Uv-ZXxefeF%9 zPCAh-s`FQ=%vM&gfc)ATHmVvlMWW5h@Pbb~ro#jzmbVY*M|9B9$LDK~48LUqmvJuA zVZQuJ>aS^}j6T+uM&&jKX0W_692o9u9-OCN{>YZq7DCu7dfsrZm50wSkfuJ3wJm^( zR%9IBbzD769qDzAc4l0Hj{FP!^1h}|_)pu@yVO7G8t)9ic|C>t3 zky#mZu#^@2B-j3_fUmOLQeOvBL5m*BCrchs;TnQ{bdQz_CSLn!tSqiRG@XBH(fD+5 z+rbhJyga=Tw;}1sImRqj>swuMhn-AdYh$&1D|0@J$P$xOe)0GRJ8P~$I+9SYGuMyt zR5q?R-_k^y?8TTbq>ZrG2qUl7AwzcrK z@ZYnT0vjqjuC`1Bh+XEsJh7T9KUK~e{X}QOU=a?{df-c2xvhvK=urg#{m7-0a#ye_ zBA~7?MO!2A)3EIXJwRkX*v}l@dU`}*cwty~feH$ka{k`ib_BS43QTK+#%E(vz&FWt zCps{bINV97UIv41v^L1m!owbAaL_pifA$pHyq#g9XkJ{_xbbPMAb2j0Sk+iHI1 z{B;frQVzws)%rC2Z%cHoYtoaR(5dRhEuTzKE})UTD!75sl@gpaWU5EZFypVR&cTc> z2(I4wW$9@QYSGo?3^+*$XQfQ zQ{%vbEuXKF$RNC6G0FCb>eOmSw8$rHuF1O|_x9T-@r9Ex2@{GGW~Tm5hD@F@v&Xl$ z{aY_#{bO?{bXyK(+0|l?#vl&`t^#{rhP_EmkEj9%-^# zlW5p@+ArgboT3 zY-5I_MbK;VFGqde_}ic&b)e1o3L2OkLqXI_m_6F+W1Niz=&Q=$B{rw?&LduHrR=$@ z|8mzHo1|HnYyRuL%JtcXW@jfG>Rix-8tknBC$g#F63aK=&U}|jbr-ioh35+7^H>K% zlElnJ@Kp!SR2Irb`2w&2pR4EncLw0e3ty$*?5a}Z>B*6d@xrZPHzzRq`7jx=t8I zzl0#rQm7}VKXrbdwb*TMLY?oKb9+(qbK#vY??WF({?oJAht~q^KGqBoq;25Gh3s|= zi5f`o%mYU@QV^C$Dauy79-0qpbkzxYcc9Xw7Cl&HxR8GHw9|^`Rk?0MipQP|_Fujx z#_^9Pu3^^;EIS1XfnhB2z(nX3`>8~eT=ZbP$pR9Qy20vZy5%BHIJd>eLMZVAYcXYZ zI70@IZ*B9+Zom1mj>DLsweh6sMx9u(Yc-FegOQ8~OO;}Z219&at}M`-og@Oh>zS{nxl**LS>hL)zn7fnLu99Rzg)vDQc>19OucC}EQa z=`c^HFE79B7^uG@y3I#GL#m_Gw@C5$W9+Y3qg48iJca#k(XiV4o0k(BT;AW2;8Vl? zl*psbyXU7YhyV^narZmPjkXSg7VPDuNz|F?KDEytN!UkSOe|%=_7D?6tsi@(QB8_xo`#L zxTNrn%D>5P>EM!|At&TqK$W6&mER=aln@l)rr^`KsaLHnRLBgu{pw=P;kj{8l#FS~_zLDyJ)F zqHh<~aU-RygK<%15cf_P;41KoHSTOOm~p4ksLC~x)zP54 zHfBIx_IEW4v3|Sl_jb2s?1w(O!oYcncAFuM64@O;Ki#WwV zt;3S6_Gr542ahHbb2HvvynUA%1IfVc)<1cORC4-gAz2KN$`mYNXja{x1h_Ldc#WgECcts z)_(J=-KUokC8|0E^}$l4;pIk|6tli_7f{yd&$-ZUijLeQqKfZ*={XpVwK)NOpzFh* z9yKG!OC4SQiJ9$;^IaO>tLcIlNI?fBPTx_5R_wo;kWxr!mHX)^7N0dj3&;aRlM)S5 zjSZ2zc(5~9NX-VIo2*fINy-^$RS^;X*5os@w?KNjqL}j(E~|bK&|)Z8^Pw<^61_}^ zb?3LjrS3>t60rrWmCvu+f2_a*l@_AzX8^9zB&w#qPdvOL;XX@g$bWNz z$ETwdLatzFx2Fy>Zp(UIw|sP`K;gucVY9`GXKL6CE z->M;|!eF|ivFj!sba<48Bp5m+@Flb&ieV#ziJ2XfF5<8=1EU+!P+%epK~)dh>zweD z27XoGY5D1Qm&kmZkqj`PwJ*5luH9z1(BNg6nKYGoj!6jX+W`fxa&Kv}Mds}e(Wp~_ zKebl$E5E<&--{3&M!<%}vuP+8Qi`!lFx3Zy`{F9Uf%a7#h)=DkQA?T8<-!Y3z;X@PP1el~+2fS5C> zT`*V9?x38(f)V?oBYpy>EU8??DIe&+x_eUe^pms{P6gYdb#OQ_tKtg z^(WEu(@@B3WttBGXyFGTkXl8u;XWcEw@6diyEn&W%Z^VfiXSvFPuoV|<%pSi13~_n zS_@?f(0U9}k!HnzC$B4gw5iav(GQbnZlW2P!TAS1%62Y75D$SDsyPy+#OS2aTkNo9 zj6kfzJFe*CRFbnf&l2orBBkVhdh%gdg@64xT<5UiY79ZKMbj!06pbM)gZzcSn`&oZ zQ4aM!nbFLd|82wE+=(Hv95gf6Wns{4Ufe**|HExJ+sd-5uH>z zx9?{cN-Vn^**V0wQ*O!c&8Z`8=(Yp`=Lr4wUaLi+uMR|zm3Nv6-SoKlkO0H`_a^T= z{T1{|a*Er82np67q;CwS$LzTGZ%cp`e@jiA9Nh`td}b7Wlw32jG*qj%_S zQ0DVEa(kZuGyNQ`!|;$3TBFl)F=H;GDh%nl4qP(+ycud=#SY*xYK`|46sRyOt7;ia ztmze#|=_8fc<%C?{D{-|IpU!ft~<$Mmm7~(XmmM;UC+PVXj<_c#B@||`h}1TEnOe`iD}eHXpD1I2xC>W01B(JDqgqm{RL*N)(z-)W6SbU z8%uD9C~e4-X3Sso?Zc{b2^ZaMH?i~OG|HUos1o#o`ltTm(;tluy-nIaDa|dbuv~E z9M9FXi2081b85LhimBgWA(vg-3=T@9Qq8ti&Ay{m@NYnpNw ziFQ5lifEaZ3-D^@m;rg&Of1BVvR(^&risR+FvIRlo25kiHZmf&g|4!G16O&R?Jm&Ry%H{+G3NIw>vvBoYxj> zvk-r!e1maLa?aaSy(}YmF{o-7S~GwmYVpA0Pd;T7v3PsX>D_wu>c!1uJGPijpSc;P z#4nh|SCh&A^^^B^dptwNOvrfwFRS2KTWg5DmLAde_V}PhgPToE3Er&pX5~mk(I8<$ ze`km|x40mRLUzVps4LDK$*%9iBE%IAyf_o(0DbYC{HoDfXGAS=0||Q@J;*_eq9gqgd(* zIev=VB+AeXB`HggZ<0qGI0@&khEFM_I2&|M8%$HWR{!}QQOy4f(iL9JjQsL5;Ez=) z-&Qb0;amwnWM+m3o9YMmlPf$Mo4E~M5{NoZgFy^vrNWf_F0CG|P!n^n?D3fok@6Fb zax-?%^B6q?UvnjXbRDt^Gc{E6a}HaUcu&v8Vlc}#2K|m97>GV-&nMy7z`V7EAU9yq9E6o?3xg}Sd=n2v2SJ&qf|Mx&ipl+2F z)o9;!a602SI@w7qBO04SCB|qR>(DG&Psm^Ov+jTT4?ch^A8fRzR|VruFjZXF1Rtfh z0!fv%{&LceLho|WJ1~@OM!o2bu?-M!8ZO)P3oRqj9N(*kpne>Mk*}>;UM#pn>L!2f zo5FAF+XqqVmDc{KD(dCeZER^unqJ#M^!j}Nf}AK-%T@F#Wv?SbABJLOLgpP&q`WQ; z@bT@lyMUp^xTYZ$<}uVAl@7R^Y?&$C?N@4S#_h~p>QEuNz@vV4+_K+@s3GbIuFu^B zX9lCdc-RW#pfsD~5%~~b1pT^Oo;1A;FdD^o%Ub|1DHMB1o(s+h0kk3cRb!G%_E9?u zE&hk|V{B1+@P7gW3(y0Je<~ZaLzJiOlZOikrI(mwNjHlaOwqLx|z!*9S4Jtb?oc_ zna-Sr^Wc1~=w^zmBkqit{(;~_qRX<*Uzx?O>ra zLtkFYq8(!jm4Eyv(dwlP%A4%NkYx(aUHa3o;f50Tpb&9K(-n^@iH_>N_9PgJv5XpW zLg~^>DT9FjvBg|G?3dNQAnyH+!uX$b;d;9$C42nG#jGFd0`UeOzso2gcmN{%#3AX2 z=$#*NWfYE*Nzb=R_hp8yO|ZiQ9l( zl!HCD&|JbyEQ)#pGMlVAZLy>*JP;ZmcpUrLWk0!SX~hvfSKA||BkKy zr;U9RF{(&D4BL``Rs4|1h+o!xi^3^AN`Hc6;^}q(=G#TZ+T#YSlf9n%TZid@)`S?3 z3L*3SG+@aLIvaFP5f%lk{Cm@cPFdRHQZO7)yw9tH3P+I={%s&!Uqi>G97S!#w2H%a z|AjL;Q2*Y~Ti6LEgu(zMxz59-8k81RP3v|&vrA>ezLXRGK7o!`YBrgzF1u?fouPX` z;-6wf{9kvd{0b6!6hmIBL#pDS;Eqg9M-KE4j r`I1!`bN{JlA_*$G`j^RgaQG7dE8=}p@tS!J8tSK}tgY0bU=#g6+Bz_& literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_openpilot_mirrored.png b/selfdrive/assets/offroad/icon_openpilot_mirrored.png new file mode 100644 index 0000000000000000000000000000000000000000..23a7d5a5528b7811887b68448dad93be1705e48d GIT binary patch literal 18150 zcmW(+1zgi_6Cd3@y1PdA=k@iC{mJ2OGrrb?*D#1 ztLORMbI(0@Pu+cQNhU_xB!mov004kQS4ZOs0DuYn?~RX*uGxJV=868oc2PA{1ppc{ zi0)uG=rWt5&J#lbAeaXLh>QgQZqQYcy8yr|Q2<~c3IKo$003I=k`9Oh`T?eczP1M7 zF(G537hNLo*0Fwx{zg*)>;dmvT+h%y@ceWQHSvC7;~x zxe2|q2_|=DJZ1Ys?_+P_LQHp%(q%+9RWX8M4^MeQdT#-!EQ-PeE{o!fRPa1UznDbh zlXZOj+K4^Wz^Dd_+6IN&0gu;HQ4Wk!$usIPj=rfC7U_yW+PrhxJjccGd1X`wU#UOA}oiLkD&!|2CSy zft02=4CR|+1*yVU0HwiQT160DlH08R}+yDHlxh>P5BTp&Smilup7VLvu}KuSO-;DQ=0l_ znHH3QJQye*_I8m&NMlSZO^qpU0B1MyQr5^ucYPsYj4mEl;Mw@LnoIsUF#5#LPbH)| z`Hn8uQrZDK9@b_pBE%I0sUnZ0o}u|O%VJ)g8%yZG6A$C#dH&cR@r^Guj@pO5V?Feb zdLWefrizv4z1>w3L!2=}L0FTvnY!#5GxdC>a?dcfx*Pjg6hqw0Kx|=ETH8cQlpe<@ z!@0Jy!IMt!G=?~JD+bysB5-+5^XtSW2Kz1dyGs8JQYk|16Q-5;aT6^YZOR5Z)~bA? z@4hh%ajycoJT)x8WzA>hI5~(a^_$pv!WpFqQ)bpNSK{@vcL0_PMIME#hVcG4Ti7kmyRK;8tB|JW~g z9<_@5GBf9qn@6Gbjc+sl#R>V6eys`RFOkqxnMq$adYF0|2dNdY-3d8^-hqiiBN^67 zMB8*{Rh)&{?Xu8oG3NmU{S&46JbrPSM3eDn0lHIrs;6fl*v zO8kQ4gA<@p&U}TeBl#O?iE2%3W~pSga^&~jC{r|TIy-J{mpq)L`p8p-I&U9U#Lfpxq||1;v= zG?69;fQo0Z zj=66WHJ>ozn0k}F(S4mv8G^t#Xi(beU2dT2B)!d#GJDHG&7W}B3;Mcq1|j%vVgm-1 z6=W<=V!Khi=4yZ-l$5k2+^EwRlB?xd4;m+thSazgDlH1E=00W`UM@-hP74-!gw&I{ zqzLo+wgN#!FWoQuOfPB9!1ymQZm{3)1rk=DU5P0U{OD> zsGG#_n#6buOk=IMM@084#nN*v9OJxB$(k%|VjsCmAqdd3!JifBx5fq|9uvb%AmTYK z83h`{8M-ueFZ!pabV@p{e~1R|;&lQ3gCXofO6s7#>4HcCcvdrTy5jIlsszN^MnBr1 z@5Q!^8%6kQ4J{<+DbJ@Y3ksPKQNdQ9roo6wYTvir<5!w7!LqdVvkcmL?nx=_ZBrAuG#g~PFd!)5aWmMBTC53! zQxwQKf$PTpFc9n-lQIjIWMn@?ItEJ64-3BT;|t^oPH-@u2`fm2(Z#!sd2dkTj#n}Z z4{OTm+2|Ui4jRrzkW%_oK?UCQWk;2jchhp7Na5m~QPcnpR3&UvjbsgNbhAAA|G*=g z@xN#+@mW!I&pxrytT-IfIUfk<2r)+@z~C*L=FE8rcG;#P8GE%8lY*eHzQ^M=(PRT$k`Lzf>sClsdbnb!mUn>j^mWe64=!#p@qUf~J*dWJ|; z4cE#pnK^NT>)O+|UzG-kS$`eG!L?YgvgHihf7uZ8Lw84G3`fvA^IR$`1#FA2R@-};FUUS^$t&s4_^aSM>ZKT%81>7gSPg?Oo80Xn@q&vR8?PptEP zD^=kp}t3heN8whFZHWJus~ zB>B9fH+$g1T&(B9PO$!G0;n*?ctzGdO)L)@;?-pRc)ae6l1r47427JWA8q$ukV*)g zScP-Qjytd(=TE6P!NkIaU8&agW}Lr4IcLplrgcVGbqj_u9BTYd_`I36+~f+wq~rvReCT;o1nPM&sFr&N zb6X=4PIuW!Hfm^Ji*%iMig$gRpL#YcorR z-$ZMtr(Ab~A5o_Q8!a;2Ruf-95!OMxULA=CC&?oFa!7e zsvvVcCA{FPWmu<8(}E^=6@WZz|4}no)0F1dtar6>vGRM4y0h3tUz?FUP(bE3=R8OO z0=D61K=51M`h9=bl$p^u^)=>aBhB)RViR8mHd!>1ygu z1a|M=z5UV&6lzwFXX#23DG(#0JMvM3f}v+K+dMRXFk<(rQG|bWiWHS4FdO&px_N71 z8I`5SedTYD>U{Pk)_kRZJS-R&We0we^sCh|p6r8N|I&Z73H1d>1K&%A(otDAr3=}i zA6_Zg)shQ5^nrU6x|jR2-*R3^e5elN?^jl1O%QlMI)=7?+~JwU&A;nUh`pS@U`p=2 zYPL34-jlu8+ffeHfg9UZ)?Sf~pSiGpI!dVCI_J!Fxj}r|vTGsG#I=|HHkEpp%+2z9 zfcRRby2|V|ecmtV&W|hH`ONe=XF^lC;UGf$-1H~9{#Gjq^doZ|U3eX25@Pl_=@1Cu z-Hj-8O&_dhIo7!nwErdxUDpT`xCQsF9%rSaG&lFXi?^B;*_o>)FK?iXzx>hQNq5dCHl451*QwCXnF^IF#23(e4-f z>~;3OADatzMsB(Z#363yWyV0jz$Uq+{YEw^RZ|+t+bz?a!1c8frTbe0aF50uY650H zVbGeNZVcIs`^n6J6V&1tn)LQ<^Bl?MaSpnc61n$n;Gz!1Y=1}K(=PVa9W~3Z=P)B{ zhw-=FFZA?X6@^48_trALf|SK;8WvXoqBo#o)J&%W-amuC}GwN$yom)l3Ae$j>j?fy!cAPy0Bp zTfq?A(Xama4YGa^RO086?7-OSE&X0D_XBE{n(6X7J$mX_5UPPcnP_2hHYEO#hxw^0 zdyQOib189%kbrJ-Q@>HMwI;ar4l8^C(sy6YX$lNLlr$+LRGA)jvQ{>^7Jh?7n2Rgh zVrzVAvj0sfy%Ax+XYb1h1P*c3^_d&3sta1_fm>r#{e3AnE#`C54Ip>XJ8}X!|8o4CZm~d9 zI7XOV7GQDBQ>vcBUt!IhY>e2a;k+Ah^%fbGfw68Sd%wERbN!qER)xh(v8}Pc-=anC zh1nhXI#9dlYUB3&VXFhZ;bhLQ)aeT;r5iHaLm2rydHra&H&@LkKI5HARoiADUDrdZ zW<#;5m;oH(RG1x8m~4;c{$RZ}hQ<7INn7{%Re4N6?k`h~%K&mCD;X_QpuT8sHgi`K z4WXg^uRYQmssq0WUrksTFU||kEQ0N)conwnVaY&ld_+P_zz^Rj-`5HQs%$nvY7hXx z;ALakg5m?7_-HWsQ@@w2nu}ylW!qZp56&pXq+hN3|I;sH&?KO|TR?Umsz#{OIVeWj zTN~UA^66!+XRUbLhqWR{x^)-(qvlFQ!fb%tt|u&b$IT=6*~%*&SK+7{4M;SeDRUjK z-Sq2+L@&5qu!+Tlpk5zTA5Xm~;D+;O_$%c{uzE73_`>+j?F-o5fs(;WqdSz~kW^k+ zRk3LV_Ab{J0TQTE_*&H;6`{>WGW7CZFy6q4gLB88M;yWYw1H%q^e%w&L9!5)#YLpR zKm_Xqk5g|KUxl+jdRJ+giGW2!)=FkKlTyyM87=TNu^ zV)l|0i}<@1xawO)#%@%V*rbhYw0g1lbGSe{FFW%aLcvI@v?PMJsyQQJH5GklCpxWN zBt}p#+9_K$r~$srUVFrdz0ZIQPuTD)6(;ltXSR(p{31G4Ij&YLRSP^ zqF*PnXedJ$=uEfDrcC%A#f^t=P=TqH%7=NmK|=}-E!~O8WY?HhSK2EIe8xJYDDe<#lWFnz& zqa(WER^Z%j>=V<_%~^I4M)5e^i=BY;?gaFZAXsm_NWwUN4W6b1iLhG9_W8bxNWK^q zyP-;P%>B-LUhLC#J-!3NqkFf>WE(Z^Q`h_&&_IfHN;16fbQ&YOYx+&9cM%v^=*$~3 zyoQZOOXK)7yze6XzJZjv_=9%`GQ zU%?0jPO@GR+7}d}#D8t<6}Yt+HxQURTDw!vv0IY}LSLR`{+Ljwc}m1y7gy|E_1pT> ztcy}`)fa1aA$6K?tj^oSXD&UU8_fp#A*#TsN`#^;vaW^Uc_P%!HtOlj(%(|}UzNMW zH+19&j@`RRtpZpJ@^pKp(jGYQTQ7$Dy)$G1Z@7$5J}O4YN1{XJ3-oe|Cp7&H{7o}4 zy)2=>rES@hbG2lv)JhU9YhVi*Z*jH705OIFjm$b69g(0AwQ2;D3# zq@Gm@OM{Qe(5Q+kE6+`X;~Y++PY+;vLSbv;T%Yu zTb;{AU9)Ldw=LLgCn+3R(4DuYyVH;u^h0wc7{TsgVKaGt!DJ$= z$c)L4e={)dv49A&T$E$?p62`OBLxPsb>V|f5x!Nrl>7;NH;PZ|^aY+xa^LvsQq3w9 z38kA|sZ@?#m$2Rc_FAQDf9Js*38I_&(A=)auTnr?@VrUR)@~t#sP_U9vUQsNk0%=U z;PfS^|L2LzvL$zT5mc17sk@n&x67-gMa@fzu=@fLymgu_H}c$S6M^%PWYhuY;=a!lc3tzeX~UY7#ikcRHw6I)C;Ah^zrj2d^fr!|y;VQ&6}Wd(h*Rnb7>8VF zmj5!(JBUmSNa=nV*E(;D&&5lP(DIwzI9GJ56kDk~VWB{RSv6 zp;r1p(&))FI{9CZf1*?Sw+&jKq5CFy*C%%SbS%+;f7e1~Z!cX3%3FE@$vb_B1Of9x9&;HcnDY~yL>CJ>RY z*?1giY@ZEEuvS4|q%7YPCpp`zyIH0FgNm^<+Gtr3$b4vHPPxX`*C$F!f-HD8w1j#p z{XKx7?LiUENcJpNE)dTg9eRt}!dIY8-!N=i-fyn`k3>JJn0E~@g1Ago#r@)B0KZa0@^2;iWly{9D#e2k=m`SGb+=V)6uDCO4+a6qj%fQYny` z&N5a!6MLTsp_z7Mf1F}d()i*AtYPl>`WA*vFR4zO4i zA(J8uNkPs#wlK6;0W1 zK0WCnZyB1ivZ%stw>iF|CaWWnGddho(ryWY#9izP812M>JpQ4&5che`0Fl*1Cw=5! zEjUh|m3tjA!|w-iuZ+r1LtzQAY0>eP4#GF(^B*aby-Fgd#ZvO|YY}e1AT54d`Z#Drbg38>7D#E^JZHf* z@>n*DmSCz8(axMHq9xYv1}2Qn_r~oR+7s8d1ePQr3&xA%K6*VQ_tv$%k~9WiX$n_C zsolA6n(C(HGbo--xLpY!lc!eVn~;@3_8dT6jf zW5serF@96klyvDsDON*2tmk&NmYAwt{ZHmrruF{N$4$ytb3mn5;^dnTQ+ZKhj70yqUDBQv%!@3x^xplozG{vCx_Y9mU^~KgCy| z`nT~_L5!~zaG8wI@7UDbDw!q>&!c7c0Tg2)uW_( z2KUQ`!_OW$(nS6%mbJp5DN<4CN1;&4%BHc!o`ZG%R+-~ z7jL+dbTv3Mxfmq1I%QRuKeq3h2zQNvcPOl2xzAwPUx{r`nXSa;pI@7*p?Al-RDuF0 z1==#$%an+Zw8bUu=6Goi0!3EOyO_5(rw2WituSBBkdw@k*F0rjnwy2KC-L;`u}6 z{h{bj-sB3WPZ^Exleb7i&1Pru+|Ne_;O&nI&Zb>8rfYQwq7(!vV*>^w*3#$8ysBN|r+-7B3hN7G7GVG>x8%X2Yn5pTt%*=@f7!idHBOWb&(RAQYb| zbicw~s0!;;yl8Y08`?M#;)>})2B2mgqn}#w0$x;K@Z~Kerf);C`Gp2RS}E(Efa<{s zb}jVY;d;W!z)-yWJ-E+fBsY-K8hsiX|2iD6)uLc-JYky3uLJq>#c$iUVLz>Y#mDl# zpEI%qY48qKGi8o17ji0dR^Oa>2W3vxc;!Z|*I(kfeRvG{W>SnVCqK(yAdOLgO> z63B`DfO9C5T!gX#8hZ@HX}!OKf(o2n)2Pvpupw26_=mkg+d) zobWb*NJM#y2o6NSfu>60QU{IgsDuD1pm@T*mWzGD+b-_oq}0l2L{D)r4W8GWxF8mG zlGlvO?Rh@Wd9LsRS4TfFJ3-9UCYqAhIgl$86CwLi*BwGxUKV6zqt;c>y^G13-z{h% z%igICu{*$v&D`7Q+LB2*$wBildhW~^w;C9mF}dsEubZNiDN~=9W4V&;2$VwW!RJh; zC&VWfvxzKV_ep~Z1PwHmqz;UrD7&EV%0HuMqm+006V7UCVLKK|3#Y3E`-E| zQ^f1Ln>f5}WYAoogYoF*PYhxm0)%ZupfGKr z7Mo<~9*A?$R={hTuyrFyzcNQR!Qy^m0znTBE9=l00NB>g#)t z(zs#h5u+PNs-iGUDqAE5A{jLC={SY@_-)#hiQj&JV3&qn>Dok_e&g$pyyU~2HfS-4-rePUn}k-vRalR2~nHRfvPS=&43XmZXuPVC}OE(Xw#HN z7`^|C|GGOgL?dgs)#PwJBJZiO|8&1l9Nmp#$Wbd`7wVIH^`A-*GB_b<)y0YG+eAKf zozeMk?9YK1E>UQv-@cDjp~u0o4$7rjFR(x}D3}pTR%x0#%*i=vO+ht zBBs?vTU#xSV+NFkrhfS77X1qQA1-^P!{>(%M9Mh9V^h_2;gWHqBZW!rT@VIkEdDyd`@Q(K$JumvVXv@U$AzOY2`_-Y})UV(!lnr}cJ zx~d(`gw-k>mwA;)+TdjhHR<9yV3S>qElyq{Jr0X@h#P?(rU&K|K=(C1C~GM{`^8Br zS_Jn0exAB%VF1dMyeMj=%E`Pl>hV{@aB>)6&VV zmWuciS#1~V+;p)hlmL*dZd5w?HyTRDl-06{3Sla?HRIWu~o1Razj?;>)0e1^v9wJ$ns_>;N{y-3tYr{G%NjeA=IUjC8 z{R&eWtZ5WdIy~cWd#^kWdGl$dcO;=jXsEE|TvJsAn$~ z@Qy1yr)U}FXsS+QtQ{@Ir~7+nmc9`4A6b*KxqK>F4aLswSS?;4J8*RUbop^zpey5h z$uO^5^(rvsR3LrC_&F7YBMw?XzkO?ugQQRw3CZE6g30R8m>sc=9V(B}od(Q%zkt8^ zjZCtE2Nl>Gd3{ z1T{@-se7dP5ZpWPv^oerM5_usfiP%Sy!CqmWL-=X=W&n7aF8o_L9f@x7ZY6ISY55L zwmM{DEkkAGuw4vda}k|89A-rY=U}?RKa`s7spOdab-#SPT!T$z&sPCeUh4lj%puhv z;C|Wk_yz4<_<2#^E{G>HqoVjKevwxd2-R!zM+P@bxLc&D>Bg#iDx#Nx*^`+mJ#?Cd z-kry)@=!!C0$7uB;${c zD&Z3drIZO#iwR!+KqpWhF5Enuc%9Pu3OAN~(AJ<|FltY&|v-?Jcfv zS}(q7O#SAY!nz~rU$D{5588nPj`pK+?xJ3$`klDsb&hiNq2`!c}9U}CV z{uRX4noOUcJ5WWAiF$2nbfp_0byj9xI}0^8T7gsFvJ*Wb-Bvv?MSBYlAXvsoU$+Wb ztClq$^x17K*i114wDn*pd{~tD+U?L+WOd5Loeqo4$AvTR%K z+aR+JZ4%dyQL7_%mB(A4ytjzWU<9qDEL@zSqU^Y#ZD^Pi#f?(s!l9ZOG-zBbACqL= zbm}4#jL_TK%#SJCmL}|VaY@(0I!jNX{0y(%i{=eY9~LUzz5g)9vB&m0(%8G_dM>;P zp50Dl__Eh047Q0herX>b{`HC|pnxcK;3@W*!V&NUYH2ov^Jdv9SqKHwC<&PPe)#Hp zTVYgQVBZKuTUdebNy>_r7*d9y)+g_J=0bG>uMO8Cxd%I%v0ECN_yMJ=Q6w|jeblM~ z0H~kgF5O7y$u9pYx-1*#n_wvOXD^N09?m}{pCb#nrp#isg>Q_FIPI}t_>ab!s^Vd2R!O*>d zsK3Nx+fs!8WLV28vKNokGx0=?H(n}d?2u2(uwKcjeQ{8A!1yGtG_@+$Iq_|SK>20;qH)C z=wp5N9PRpD@@>m8)0U+QKP+QI{Wtb?%p67AkS`e<=gzBiWgcH(idtXEgQiu!4h(kL zZ;KHQs7H8YX|^p)d9+-K^=dkqoZ$x7=PGG{V@JjMLb+Z-v!evXR;|zC=y6s^Ts~=s za7t)00ia6SBJEXAx3Eioi;*?qSdwaFnYS4pt;1!&u&AnGvO>H4e8`GZ9{9POMF*?} zfyuaX)E=jbV%Nam#BH*E5_wJZ1N_183*OvW_?Agk0U@o#_^QO_zhQWBoJ^sD-EPbF zuqB#0k!(`djQ}2>Jw#|qS_%tJgcSTt04L$lY_Q{145ra1PrsE4d?(uxS?^2t~f5W)Zu z`@~$J#sW0fHrNtj{%t;!Z?I8iTHqvE%O}nIJGG^RV!D8z!s>Q5W=Qcq+$&M(8Kv)~{XjLJu`6LoUiXJ4+ zsXC0$rHx?z8;*PAYLiv){QqeFHT$+&2VBXVi4iv4tZO;Eu|DSDT@`gl-#Brn6~@Hh zgg^eoH-G$FoWzqjopyLZk+Ab`@=j1}sq-3t`@!z>wOQo|^T>L*NUvuetlSTuJ#JO} zm^fry=q&80@R4zGby6Fra}g1<$Q(8DmTYd>LVG$s+{7~eu@FiFtaJTP%6x5EJ+{Wj z11+u|c(cdGO(S}LTGfmWu8lkfeeLu3W6IU%e`ji=hOrR5t1SKax9^$(ttLMGgqB9C zFH}cl_jWg7bq9O@%4U@`SGruI!C!t1(?C=(IDt4B>eOtiKu-sNq8#Sn+Y>OLwiZbx&7!QBea<@r=`D1W0W`(1M1S9by`s0IJa}7!_5{Z zbf3zw^0&=7Jgakv22TsK81+465zmY(F3nL+rFkU$Xb5PVdu<35SAzs*R0>#F7e$w* zZ(+(mBMx`_Gy9s!GML_Viz;g|aF!$mGW}Ed_bQaZ!uq3z*mp_6tAseZC~Nn6&@<<0 zYM||3I!t#5u`~AC;Hy9RqUzvCl`|8Q7nptK^Mv!Eb_--g$6{zJ;h#kEpdAt^^y2yu zJ53ou{6gF(do>(5y1NeS9>)tgu6u~PN6e(8Xm66a|5Fx? zD*jq$DK*U!xt$qp`o4l)A~p*g@jQLOIf^InQFFFwOPJ3~+_c*Mw%y zyU`CH!;xxV$1~1awk~Z=NYRtc2oy@F4oSEkUW#|-$5<5RwkP(%L%X~u2GpVBPY8C_ zMQr2Na|5$~BiEO(BemCMm{fl20`DODfUZL9*-;JgiU8J?o70)h#DMo;``#1(%utV1!p~g+@auM5v zpehBuITQUGoQa+;%<~=`!;sN}qtPJxo(7%+<8Q=Am|}o+Hd|0VlCXCJ)Wp95${Cc| zWn+#e*M}%ahD0$(x>@0hxQF;QF^&`oY4(CzpC+qX(as$>Z0z=t<^D{It(C`4HWiaS zy&s(Lw2fzdt4_X|&bEvlSzNz}Ey_kyoH)y8@NNjhaNQ@bb)o3hgn$BjJ(5yLw8WWe zYJkNyicKWJS5t&)7ipW37n8$kU6T0H15p+R2xOdl%WYLjt<|Vj+3Rt+ zDUc#lx&c*Gm{32B3#m7>1mre+$PS*t(gRc<~0k-MC7*^CNStpIX16MPH3c8Bh{~b!pG@QaoEHqDF4hWr`%oEaGh-ST_e0(JV zm~1csT_{@8&Hv>llXpQ-9965wbGESrv>D5-|b`wYPC?O!uMmIEJ@Ud3NYx@BEFgq zo4SQROBFGB2F5?|7~bPqU)FCFduMaFHYH866%=Hf(mnCFQs7`ncU^mKlEs!W%Hg3s zD6gzBaI@DlTxD)_LR@b2h3XdqfQWTBNxEYw2gX8yfBWDI&-%g8&%XB~J5D4Vg*DH&rb70xrF+U(;T$pk+GTM~gV*{Or zAo9`wGtl=<`d+ZLS_FOoQ~B3Ed?OqR-<08OlQ-tkq9%4G3w|%|K(nQ=l2op21S;xo z8$QgTfpBH4W2e;r8N8jMo;$IuU2RQ~HeDCkPoMaEmQiAysuMa4H+q)7#kR+$fU>(; zN@gFI5?b5srtOVydwfUNKM-zqZ9?e<9!E$`K(X)WL)4mw4Bq^y#%Nmd>wksst9#o| ze;8;oP3mP;0>^Q>21?Ae4L8;%KtD>7;NARlnbN*ImHND;QP=;kkeyiv^KO`2Vb>XN z91?LHoaRYt(aEx~cVCidy}dzIWF5_Y#FOp593$ zF5L;rb?~iNwqt`1)-zh+A-Eg0kt`0?b=Ma>I6P}F`W^enwQe%I2@W?3u@iEm#-(Ro zTRTO}tB#950~+!&{!(RhGE3awX75P6To_f07had#Q*qeD*mLK9=P|!dS_^SOefk5W zS7FG1s^r7Y-!Y7L-850*I_Z{eYylGePA%i@Ajyi8p8tct1Ct zyCsSJoxX3+i?bSG+zt9DnsRFNDTlOLg{Lw0+#G01BhtVW5Z`BpP1E#Xxs?H>9hD~! z(lxp`NTzX!&MnTAT=nc;bBi%=wu~J6{mLRK!YX}bd;eG#vwi-C|4=B**CDm5=)#mv z^72%Xv2}9u4o^l8FFT>s0~B^YSkNf~((cKZa>mqcP|(gMp8lh)e{{OjLE}Wlsvl~f zY1{s>?-6?!xhIACVU%j!`7QXD@9q9y-veZwqw}6A(DBeNtnK}8>k&`sqn*X9;D2{_IlEZe zf1!AZJs+?@yvu=CbLP7@2Yh+{_$uNBUMzQ46w5dwiSc06Tj2n(uo!%}?B+$)j~#Qf z7;F*|Y&W<2^l%;pob zv|IneZGT6>7$38*7UbrJ{H6^;9W~cJe-NqH?tLw7S;oV(P(x~Tn2Ul8F@@=-zY5F6 zOEtK3Oo{bvQPVj+R?xcvC&_8&%O$R<|GBug;`=e?h#)68F0=#exze4N4w4Sq(^Sox z*~A?iAV+rHTZhjCZSj*XiUhqaTt8Ls7vL<{Y;XOAU>)OF8Yb8$DeON33xog>f8M*!x|@4VjO3{eCJzsyo9p0zgbG$5(u7E#RVD4Aev19B2o9>%QWyLR)TBO z*9orZNAzkliCC#lNN|gs|Z@#c7MN*0N@56;QT;#+1tx^Ym zwvE+rdTMBI9luED4OG%vy3G!Y{NM^}^pJwTI*ASFA3|j-`*aY@uDP+qz|dJ9nv_kH ze9C>jQ;#E35S_nazq9~?E4U_VBb1~m>au(T6gjBo%2uUym0-kNg>oy~}wNkf?K znHI25iVTYpD^-9%0XT9zDZ1Unm-<#e2^2O@+UjB<7 zGk;67t|w>bLjwM?@cse!9}fTC<*w)0yTYK2o!~io=|I(2>i?oYI0F;vW1x+NSK(3_ zR)8yo5h=2T_7`;rU3Q;~S8EPpEyM7iFiYOGwym#3o7 z^5!$Sx}vqQn%=SV1d8)iMaRU?`6M^=yl9R=LE#^(?#Bc-Z$&)>ig{^2uhYcB`>kBr zS;RBYG6+C3sfqy|%U=k16$vA&#eU4%MsMuWy(uh`TilHm@ri9t#&5#2o1{f?Y{q<` zi}p7vVsSncsgBHM!GZd3`t#}nga>QWZT#cuV`;27>Ny(ghT36G1c1--jY)QGb7@d* z^Q1}Fwx!=E;j8=aom~ooT$8g<0vuypl489&DT%cHLt*Jf;q$UL*}s0xV*#u%dgTgr zFrC&NB>HnbEk&tCsydsK6Hh6Q#6r-jAd+_|kNKSq5TzEfQ~c)x2Lj}`o@yH&t1wC| zmik(r1fOf@x=~ZGWBp7$d`3-xw4fu9srC%0%(C9q`!YZRnNVq40=5vxBRK& z&aHMCDN|lI*j~|`gnNa|G6ekmxfnagg3~8n5S7g=)x%Ifp_jk^v#;?Az`pn>jvyWs z+9--DByopDHwn1Lq|R|;8Kq&a(_i7d`BEhqi6gu0;a$5%a+v(3tRfBi6OqJrPVxx{RQPI-u3`V^J2 z?p2n@xPCR-LGK8+94q{eBV4OF2(~;#%z4nMpHYhZ0~R73!nCpZB3-1`BzJw1SGoEM z^B;H$g1-Lk(CzOXfu_7l;e0W|mzV^YhkI9>`^J{pop)bnJ}~XbYHvU#4|K|iGF-&d z*5s#V)lp&{`p*cA{7br`{2*8>YoMQ_lj%)B4^&X;x!g%8slIRG7U<%i3`bcR&55i* z!ZPv$vaSE{R7PO=1e;hz-Hlp}cw}<;*lt>A;0fLCd(p{on(`0V`e36Pgp>qR$RE+X zymZvdJUyTCEf7xjzk$1Rft{7yExHlwC6?iqxl`W1;XC=uB6S?h)jOcvP2f%tA%mBW z%g_Fx+OLaKXXi3|eD`{AubmIJ8p{8s{Ijba+r9?9i5{H6Kj+!^sXkL^|KMYf%^|^H z%|KP^wbhBiJZYA+dx%U~4{b1pTBYH_Q=0L;PMAV>-eW(i@~kUlZ$x--uz31!`nCxx z_;L-OI-tp6@qIfDFI11nx(#j9D5hRGFn`KJ5U4J^xh)AmiSIpM2J|+X<#v|1@Z+bx zo@(BaxBxVjxVYgJ>y7YdEqV6XMo;UG?1|~KUcKgao64SQs(I;j)j=k=G%{YznX7ja z5!#L)5*O6N<9<7H_8Q*dm#0`-L3wzfpI0eQ)iesM@s1SXXBpE&H3W~MyzPCtbY=FK zLS*I5<;L=vxAaSC|&%OmW^6J>M0CtbLCx5ah2eK zzT4Yd;q>-p$dSqW)b4RIzu-V{NV9#@-%Ww0``o`@q3ELWlB*RfE4H8g>XDsh9-5r8 zm`JMgZ$qW}l-i!aagwl!zNuPDmfJ5R0TZB);9Wf%;+e0gYBt2~;{!C|=R?1UBn0CR z?0uT}EFb=wW<7`8D8tydfK6xkt@M~NOsSG{2t~b;)(L{v?Py4b(=_2 zwT5X%(TzeRLXiN(HO%*=gjxPp40J`gaM6V~82?LkGlSXh(K!1nUy{ zibo&3zk>Z<8w0>Y6)|AKN*2fsKV#Z^pTd>gDZ|8d!gzP`Wa9KYPk7&2j5Ae~1YzId z&~Lh}EsR=6P#MuxI@>HdNdJb73tRuxj@Ykl>~bS@$ehO%e56iL0s+8fgpt_xFHf+; zHwjQav}(<1m2a9OqhVME19m+uzT(1S4+hGqDF6oaF|*EbB|rHV2mTkn*GBZVqZv?x z?T5*fa_VCc*L(44r#xm+m^mmM8-=zZ39ZAY&k3LeW7*d&Z#k#)P4ZvyQ$}pd4ihjs zGCagl_OSS2EaALzRfHNV`VLfylGfaW&M*gJdf~XUCH+QVuoto90i-4b+z8rX{O5f! zJ)alusc8$8s~trW(cm(muTI;2%~CE086lc=QSCUb-kG?JP5z!^)FW*%a4?{_AnIj| zJ5`i4VV_4|P{FTTSg|8G1lu(^fY%LUsvTm}7jBh)> zugf=6$et+pNnyOt>GQSP=)&((Ff;({!~Z&TC2V1nDv*{&%f$v|s{BI>aj2plD&oB! zT+kFu}2MERnL4K{@!IF`S64WuEa8E z60ZV}fGLX+9YjuT!rFvdD}t#~w(5W~8ifx}uQPi~HS*Sh$iRCSvgs44Ug|3z3GA&f z?T=)+*e6P}VNEoRRT&LDBk<^U>wzMr-_mgb-Z9X(*5|e7j*b0OE9}8yWX{a?n_aq+ zdi*qV2`z6u#tSPUN88`SZPj&2i%-aA=Sq+nRs%k%^{=1%ambAC`bqIW^(pa=-BTF< z^S$a?Xk);cP{2TO7nj?MXs$1f-Bn%Eo6x=Ww!t!%510UGJHX>-XN*Yu!d-z~ zAwP4GsC8&s-j5f5ftQYXe$bMMz8`1FbRe2UWRFnjSI_n!C3fZ~Dh2xP#gC0NAvpb^ zc#X}E$3UD=ErLYdvR5{xI zal*Pf5j}L}s^UOE8FD2c$Wt;$b!C6_nly^5-Pi$K_?k$12fSCymOv6JFe{X~SkmM8GJUrYPaFA3(z7 z1iV3CoFE=spJHMgIK`>U?dOZ%PFmsT|lg$2zUZt}S#wNZv4`BamJd zZpwrvCO!NAe&3cMsg{7&7B5>~13Zwp@m~LAc3C5e16k=PWrm=2nM@ zS`xAo_0FX7V({a?b9tj*bw_N3k|IKUr-K_4>_>OcYUVA@+v#f}SG{f$?qA*!(vaAW zfl1lPoLskA@&?JPcztxa(xNG1ZGpB=R&$K$Ef1^qfwP6pJ8)`$ z(YyEz+JYgBRQe3875UNXVbx$P20G{Fv_Q#g!Gc#&CAxQB=b~R=VP{akO1{^i9;Mz; zZu1}()eTIf+fcRA@ye@)aAq%O)H|AW$I%_9{#Ja2A`*T^ywdH;X#nu2q?l`q5Km&o zJ)ni_hTN20@-UdkEzNvPy`6p^bwN5lCi6e6Bgz0{#IFnHn#PJXSn+zllX_^WVahSi zU|?|k;hj*V=tZ7Q--v)U@VLtw7NBDnWq9Gj&vxGZGq9?;s?t~)3z{&gFMAxnxDrFZ z82Q(BC_u*F-tWyC)t-07qbxChARdHjz4CQCxd?me^*GZ}Q_i07PROhrb05s{`57mo zaH?sc-Hb2iA`x2bsx-KUq;PmQ zq({|mL1&{rtDkbskFJdQ{4U{pPBXKtLL-D7`;+X0SzUCmEJ@kbsZ>ydo|{*w&AH~S z{?Q`F_BQqHiQq#WtQA}wCWp_Mp(a-t>L6oT2sS#ItN@r9EI{QOH0j2Z4c%IsGH$~| z9b_xtoU;tgf#iyG;cr|=7bp2?JDY42TlJEQY8@wel?NvJ1i;cDsex;3Tb0VTEpUy^ zr7Rq5u{%DHM_DE>)zo*L#8@p7kS@(1W{DlZ7;)%{>EY$5);zuBr~_|sP4z}>XMI%b z)e>Ir%eL*&ir|~ys8}nbpXhg#KXgmUdKRX z&i1$#h~xTxP6ep;zZ_lvkjk)HImiL~ot6^QS<%3!UM_ zKjMvpCR_meHdMbJLY<61m|Q!pP?(*-!)*vhJYzNirvp+2P+Rl8E}nd4(nGtcQD-0+ z_;Rf)LtT!BBGa<8!Kr9)A!;Y@SyIiQ|0>%6J^Ba*}ZXZI>;i7 z!ujj=d~iC-$P^WfQ$B3G^me$-G^8MHZUb#S(Ya{EZ2ZUaL`eZ`dRaOSye}RcD2bDi z#>ot#_A^x~JvMJ=+(f|bcNy_Siz(!$D~W51S3Os5erA__rR zX@)8aHtOG2A_=rqdXxL-b=Ib9rsuYwpYCAt1>4UXFecXxMtN3!IJR=0ZX<5LfP4!-o^%^ouz2M>&svC*$t9TW&)ywSO9 zefXXmC>d7)*cOOU^Ii`h0N?2@1^?HoL`KQqAX$bixfp_kvqDOtJ{Ps&>Bo7&h|sDNABFSdO7cqla+rm)M7V{Zp-5Ex9!s z^S^(!Fry#v@zB(lZs@<7l9J*TYb~(uGMGym$JH0sAnHKCiAY#dRia*@v4nJWuy!lK zp~!R(>%jDL?PF^4#GQnfcik45FbZLR{BbUx|51x^VgLjTa^-k$&xEln-&r>;prN1| z2-taJvZlzK#W!pW&7XS*nDTv{Dh5PZv8{Sz&}kvh`s;{8+?+AgB!fS8Oo?K9V+HN; z+-<~VtP}WO1+9xxl9#n+l@bd2^L4feNfea#;zqA321P9Q)?x>Z=2M8100YRI87>JU zB69eBTt4d~;n#+{3Bft}QL61=NATc4&3XPB9*db2 z_;r`vDvRht5x=T@iWe3)WOP`;r~P&?{jz@;VC zbaJj~IRpLArwK!~#C7ND`8%@+?l2aj4wX|xPL;=2*TsC618 zPxm_Xf4`Mv^?9_z4cKrV2HeIFjVtb~iGkF)Fe06+54$0>cMZ)C#~&QddL1p+ygC3V zI~tiO>pDbO5kxJL+)Z`(Z7JN|n==ywf|s?_{7d$KhZ)X#galA14y}!jCgW9^nwa#Rn;_8=3PfOD=L;<|t4zKem@;{_t+>cplQ&_D$Y@9&N}gkT55QuK%`27zIe{pCI-%MIZ{X{ z;(}!rb#cBy(!BfEAikVz`-@jRCr*NdF=T=1X5Gm;180v!X3(;aw2tDdW?JBl%&;^+ zgr$pGQ>h=KA{6nA;IS8q5Kp~(T);}puY)((0NVx{xu%b)`^%51ewwB6q8tb|Mn`KB z0grGl3pLpJ`Fc*ElA*8@uX3I6JkHpyCH7z86NtP=xT462S+}K4PE4>Ztjw@Iup8>% z_D4c=4>XBPM24>L8y#V;>jZRC5&n!!%A`*Y>Q}Y&rNW%VR%1*^Jd+&~%a;a=w8yj-SNcEnEHzoTdJAtYlw{Vz zD#DEDZd7{GJpDq&dX+^pCw$@U$kSo&j@i${_w)TFrw<~PqBKxh_h!X3ezi-f$7kE` zX|(C4=F>AGeqcz-0d$#5-r>)x42}iPDl1UTKfv1uyX#Q9^<{wc<6-qUS%GKt)qbrZ zQcCcCf|WGq1zGljkoMEF`%PaBAE$QRp&jN~#V_WDd4AoJDiKzV(ClWX7v&Ti8+%LB z^&4r{*=|ZTKy+9QTqoIGHr;3E{EB@l#l^6a%&@t~MxM5@vEeug9PXYhlxD{*_Kr$o z0iQaiuR$mTH=eEwpKoFdwbt_#->nUg@oJ0~$hN|AgQuPTz4&;+iy7Y?YxT7}5H!(G z>^)gg!20~}L3WQf+KS2SBkyS(Btb~j`k;YPNE-bf+Y9t5B1`u1DG2MN7V-?N>R%!ag5^ zHn%baLyuK+gEx-87f}S#rG1iG)e;4RICk5m40_$B6}}j=t*g!Ub+^m(>G{a(ut9#XwiitG^v+(ku-F69CVI*Y&B z^%ly0CcomWs?xin#g2MgA#~FU^q)d3CV!hRHe|$2^OZX+C1c5NQ0qU^(55cF5Nu-zfENuL1mbc?ejBG+K;UeX@?!3MnpDXOd>fFxu`yn0EZ8Re?dUzqA&_=$x#GeCoRgKHZcVZ?lDVmA~Ej$LS zV5wbT!;=ZYCb_`#VG5J0_(ZcS5$e*z5q98sIL+k0@&rpc-xlv|2 z{d&MIvDQkE?4aI8HQu0s zE3(|AfIoSNNWp{g#_)-h>6!rl_*O4gXu@$~e$?Dg@virl-15=%2aS9>i86-_FxPA% zNT?9mjja)8336@b2?vudHoX?$E5Lm zByC^>C1*@!pkQVVW7x&Wx1<+R#fEj&l$H!*`R5n>k1_E3x-^b zI0Q=y0jx|}fZe1BI$T=uQU#d||JVDy z$J!(2?g9dspu0baaI``8qqDbm-t=KWY++6#Lo@PfXeb=!SQI+#h7~RalANmQ1gphF zM(MxbaZ-Lvj~{iuOvMGTOD485$-HqoB&(U`hhRUQwO3E;yyr{+H!JIf4TTLdTi2nO z1_`v)EqxW|+h3o}N`tP4W2tGterEUonw>olCIM5td4Lm82p`so2-WCRrR&*bo$aKt z+6xF}j{R2|7W5$^*XN2G_b9N^zDAVlR3U){@wv@}DZc?fL8$yyiO%ON;bo4iUW{c< zn0{8KEk&B*y#tb)SjReNHoZYofz$=% z)|Z9;Nu!9#iE{tX-NYb}Jf+z&39ii}PDD=$eBq(v#2!DwrY=k{;e03#|GaS*QsDD> zKf+gMsA$IF)3NJ?g67K>*m*SAs-d;v0gbPGDH#`@19-22;X*%56HigTRP=&-U-s@Rxy~;j^PC|NBQb?mfys=5S&0ceobEYNqtuHEs*T zQcp!E_v_8Bc@lTNJP_$+r?C#eJ;@r+`%Qo6UPIVun`7%C2IJL+>vZf0k}978&f;R` z*Eb~H?pYNLUFM!Wvw|ViFv$zwm-}~DM34E}XobEIcgK`!uFtgXz4#JN0(Dj=fX-)_ zXlN^3d$RjpVL?pRsPOA~if*tb^qBpME<|-d)pT;8qIY;!j!b)c;mehZ z{Fx!C7thj#sy>fvEsh5ZCd)n2e;e}XTP-ySPNsAQ33Gyj-LO6z?#1*qb2TvE%G}>H zhD&tFDOu{LDs?BhD)|rH$_0Vuem!-6txA5L2%G0^R;`jIOg07I^vlFq2r_0W3cwjt40R!EBvKw$I${% zLSSLvi)~@r3p3QfI~3#n9M4sm+z%NMBd#ashaWx;ljQyo!B-_=z zdg{*(UqqZ39VoA{(k8Y^{Fq8hVCUl;+5QxUu)PLq`g>qaO088?qWsSoyCB*S+M!!S zyj!bQ-XbOY@HPD=fbt99sDVVaAN3yL%?8~Nby;11!G-E()jiPP=1+x z!WcVTOE%IdW(Mu_H5(pEU9)kqhDLRmyv=+Qz(a<$76Yb?#+t=wGQG=XQu<+qp(Ux| z|Ccn(tXUJf(t$<8Me;Pq8bUV>!M_{yt(TCO_IF zrX4!qL8Tm064gQU;xOqums9IHBtA zJZ-rOxk#D(d=NNC3_Npu8dD&k=le|}^84UGl zSEzz@G|xGoe)SIspaZROi-1XB{Vj6KSI^*9dS#Cs=5xoSQ@CkUzi0W+ZfbMK&Yk?8 zqL@DkJnS@*SSbIEa)VLcrBt!p>xDxiurM-%#Heq5*!;YAByF~ zJcEpMxeJ-Vq7uZo(n5idEBgq*oe(Y?9Z+>;yu+@4<})s17|&O{ddV*_S#P zoMa2$;|x&Q$6u|*$(~qVtrp|@=Dzi?Pz!TM^3mWrI>$bx#11r6Gs=gN%@<5^<9*;^ zUvJxA-q#cDV$Mw41_qOCpifEIN8+pu{!S<3#jd&7gh2@N`8@YMm63j79C4aqC=M@7 zc%GH3?&BW8Of-bZzuBx&XD!)H6x0FTukDCGa9EJ$?hD$wb&vXy1lhVjE*(kFEb;kV zdO%7aW`{QsngrqJv)S2QHwxh8-0s77pMw+UZZ096y2SG02;I9fC?U|*43%;hOAH7e z?rFfzuvvhFP81Y-a|p$zJ20j7Zs$vr7RSVNX+;mU$VtOOhusQy?i#w0P4?@sle^Rj zH>Cv#c%Z3#>~STx<*-~M@5TSLI2C{XB3ZY{>!hDK{;7vzpgy@&;oVfxI|34ZI`bAJ zHF)Bc3ROjc%yhWMHDu^AO3qPD^LfKX0ri_uf&W3Rw-t%;HzBCQZsK22>qMRqGo~7S z1c?n_Yp9$p%|XnfPH_W`q4x6fpFNUmvU7UTrg(1hSsdtidr?-um+0fTk1`@!ZvMK! z7n(hn-Pu$yLQxZx?R={~2kd?0zo=}C*KUUi9ZRg`&G3TW^L-NZ=dq_x)q?;HF+;P% zRSLiMOHeF%M;Px+iJWje0h1W?IwARl(U}8ZH|cv(j3LNijj=&x>x*pq>npJ9Km+(f zHms~1*8(=|=Ty8;ZNX7%6#;p5N6!AWb1+C1oEY54Q=;?Z^pU=Y_A!)#w{d5%oG|?% zt5rQeA*1Iw_3)q+NK)%6{f{Fs_4JA`sPoZgj^KW>^Y1xf~3WiXo$*{pP85Y2${iBCplglrPcy)!oRgRK#w zt#GJ*^SGD)$M!tN_SEg&{mKtowgfmqI zs4VTKQjd?=phD?tgKM1!dnQI#NS+Y7rMC<}el=LtTgpTP_L4bbhJq=llK!G0&HZ;; zk_$<`*v_@$jn=te^Ub{6A3s!aW44F}ejE@@^uB3p3NV#mvZp{DUD381jZuW!fs5Y% z!?hslNKUkl*QXZzc*C(?qT&X-MdJULAbxOnIKGcKU{>QdfFh}t%BWzP3i9-~jKJgH ztR!V&+zs#XC-)`)T9JzyU4xH`eu|*@{pEcji^A#?yA863&4S`c< zDaxd6Kc5*6S0qN%*lB$ijpw`ZH24*D4nLO5-BDYUshmW~Iq670?U^0wgP2D;;_C#3 zs7EJ{VV_XUTQWXY0!)ddT^jxS_0*P|eQO2AlqK=enURfwYxA}tFGkbP zB^WzKu23ZBOXzg-(1kp;fv<^eb>v8VrbF;q?AT>LFkKcH@(V`7qk4IIjPL|B=KHb` zr5<1o=(#gWZ*F_Qki5+OKVK|yj~)nMZOGKVCn0noNhrI!IyvnW6+DaWi{6pnTsI}2 z+A0OSvCQJ*_Or%3eV+xju5mGKeaPWc>gDs@ZN*AxsLa-;qr_j7n zI{7j0D=bjrx z1~4B_qrVLAd1|?AT0i(Vuh_g=wp&Q+^5=EE*^#ifX~S(^-e9q?G*ZMSc(%Hbn@Ad) z`v%W4mv*ndR(yp>^vcgEB!&Mi8G4$*8F}rycSwh~=nW9tZxn_yzg?;@o?$?OJV5I| zofO2cF=hjtd&V%hFWGRWk$2f0_lIKZjX&zQ{okyWydN*D%km`>Y+7#S6$Jsy1I{>< zO0ychMF%kjbdIn8PJiQ_2!8yV=g66VJ_mL?KoPrhNsm5^gs8Oi!0w54eN$FuL6d;m ztxg}G4w6;SrfY@!F~fGxotBiOJ5^9cMHd-GG?jg9ZuI0kXDZ$B-iWV5PBU(S0RhLy zPrc8Z2Rv%F!K7KwvV+Gyx2&+C z%x0#~lL`mG2Ve`jKa`yJ5QiQ@Bv%3@;|bF8o%1MJkhLk#m5&`sw^*T)5yh_HTkB-Z zUEdEktut`p^?Xsdl*)Xw>5Ot>d_tIb{H(g~c#YC_uhP+-Xq}(nt^>8fnh_nw#pb_~ z1S~vy1t)(gbWY4E1hCV>O|hQeD{^GPwc)z%T~C(j>q;zV2?+|h-{c(rkU_0SWP1NS zX_V*n!Zz1=D7{TM(M5rqQ!*5IlLKf?JW?f$c$&k8@}KY-V#7}*^evGOhhHde#YC#* zD{a&yxa%ps6Lz;T+<3ERt7b98-S=T)jK83H9ydWLl*V9m;L)PWD)v0O3G$q10iZ%F zf^f@%Tts0X(xI!_XzlJJ_IiHu=sbQI7gc4T%^Gn~xKBt=r`V=XrZxOE9Lob@7R@k0 zm%9SUOQ6496`m8Kc)~rl+waAdP(o4o3+tVC9teh5BZGmnU27^iesRt^$g4L)<(|z4 zs8eDV4WgCPPf7S9lgs9s&B_lLDzE<*YJP9R?wBf@PX3z?_*4ykT==VEtzx9GUa7hY z%4muXsi$!S4EU(fWOdkx(gFv-po65Mo?y@ypi_Q!r1Dep{)+XzPfLt#iLk17C03?p zAZJOQy{Y(|68ymT6F=BOamRm--v=*%R#Zp(TwKFA^ z&D@~>&^zxVUc3G?wfbf6nOa2xwzKsYg*jRGNV^X)s@L&9>$>Zd*u!r?=N{wBJ8OoEKDHYP-Y!U)|5aj?swRQtWjR$ObU}W<$rF!8XLq*RBe*m{0 zaOzzsSErq{@yn^Q_`L3VV<5?KQ5buJmZPK!upp%Qtig|peNRty4V^@PO&}KCxKKx3 z`mAAzN~WTAGCrLvLSaqHDmFemet~yo#rcz>Sm}gD31#}$A7Rj?N+JLH1*m4rZO5?9 zpr0e^l%jCRq)GpLX7Mmg0&bOgg~KLQ?L=kP^|e*X7fMmehQP5sFjr5eKcz+i_Oc%x3;D%oYo?}{Ay%8S;b1-J|*X3&lo@m`Y zI1ZbSAko~EZ@$0#y6%Qz+N3;qvSk~U40mC&4K*J&=ky6@`$Cx31ojGD_zY0p`>+2k zmUqZHIF~Bgyey2_YQ|#*r6s7DY!cmtMFqQNCw|{b^OSXFB53Uf93&`C_Qu9-qz!qV z)a}4r#y%kH>8g4oLtG|YM?<7~dK$@u*wY4OCar;n{bT#yW2;98p9k_C||v`gw(>Jj;KfwAbGfk?;?Z!_l=7Ttc>vGGe}D$ z?$U%?5;3_DxJZ%&WRZvB*a63zYr14gxk#X^7lpGmvq zJ$12KPwFkK`ln$+>J3AfV-m}A7~fM%*R&xl0?fOK&u?u#FBY0!GMCe(UO;fhjSAu6 zR;KVjn`miNb;jm*iom%UzK!QE=Z2!c9PS_PXWxupKNJ#Z-7R_vob7_LPwu=Mqg_e~ zI#SPVUi}stzG{lK0e=FwxmfRKW#+!AsU5Jjgz)=4X$E@KmKsHK{#4RlLy+=W98F|C zD&0P92RIsy%=8E)401=r1PSB2PV+xu<(P*)sDkb7e-JQ*S&jFuwFjv$P(i8MLV_>% z@MRin-S@a<&_hKR8sM$N)cK3^?b1MGCC0la5#By#$ z$hf|thV@_bhB7DY?S3R=Q2b;5b{2vB6-4wpk3UsrM(% zF=dQS{3{p~V#C8OWQfc;X=0c$ZPr(QG($O?U~FxlRtk9%+uRsODpQ|AQINfdE~fl| zRlrGj2s4@2l~?KBO^Q=L1XdM8p0gf99cq2CBf;AT$7$h&VJNHa_dVuoj)Kq?WF;IP@YnnV59_gl*$ z^_KZ{z7_E^Q7anB8%cDAclZp$(S&Sf$q~8ZVM#ZQO9aiB5@E~n?~^q6A=17Gycz@~ zNg7otlW#Q%o>FzQ%b^UdU}594S4+{uD`VGl9|Nwnatfe%xQOj7mbUZ4XNM=O<$9vy zy9l}`WnUW#^02Nu>65|tm+qiMQq4A_C4!TfJ_Qt@ctzD z0V2SWka6aK9&{t~D7N|l)p<6t(>83nLv#qjfFe>hx&z->o|JR6=wAx8hDPOV~*2)=9ftWT)4 zT2(&-p)@_+^%k`3yPWk}d=JQrT#qJdpKMh8AYzons0|!lFKUM+23nEGV#s(pFutFk zECs;3SeHc6=FANPFw?*w0*{t-W7uN_7;TOI82UY^t6&z?(E*!x8y7o%U_49(q>Yx#|F! zu}3gtI(q8nW%#TKpJuwmUx-qM0AM~-m_#Dy}Jky71l;+1rQb)xi+AMYrF#(@o+8lp4 z$UXV;rU*R?kOZEMcH`(dty`>n_3d(KkF<@i)Z+1ZIc_#?;=&VeVnyH=XdrD8nD#^! z+Z*Fk8X=9<;%4W>-^=piI~EJ{@9F0{`+-TBL2nhp#PhUC^DJ{@l$5$-X~5*sk55X$ z4gs|#dR_I371_pHg+DwnZvVh7<1bI+)XuO4d|NjBo;E!sc~kFAs^cuHZCI zY5EcCYv3CY^ubU_3N3I84qBbwjqE4PZYN5B@6d|b_lDeg{JwCOb(-&I;_TLW7*d@QsMj@gpY6IZ7FikR+X}SjyVXTzRa8IJ^B90heRsKVy&Sk%)_UUop;`!nyF2Wl1vGjIJNM ztBE_iG%gH9Jq`rxsD@(gJtQl6cZ&DgZo1^Yv=FW&$Gd!HmJMG4t5w>#1r>gQ$XHBq zgxR8>u`191A0L#-Y3QmgpOL7=P%-43kFV_Lwt2GNtV1Z<6iup%Q-Za%dD<;mWaHpi z)P?J?sg8{BvMm`Uqpl2R%E-yn@W@U{*jR_OVBH)J1ma2}sicg*zyK7Y5_RTy(U=`J zkGNd|rJ&Qs6ihak6Ww>c2B7LzgPGe>S=;{hNs&5}HJn zaEa#DYD-Dtt=vJT2dO;CaJeH0B6Frw%&IL4+F&YcJh*O}$3+telFUmhW3;8BWef96d3lS!(ZR+(Je>`%vtNI)&StPTuK8;Zpp|Bg0Ua;oYz zxMqU6>Nu!jAu=nOV?Dp$PgkXq5D2@sj>|H%7Ro@Armt@h9Y_!>vfM7HDJv)Hcix~a z7fL6aZSifD>>GEwju5UW&EQNtUtuKBj>&EqC2n7wc z{NLAOF|J6vswDwouDUT^FSLssDmnb&tA;?G04(PBXq^Da7`eL=E ziXw6k5L6uukCBtpzs2BkDty~=+&&t(kS>?AQdPN25f0zhoe!Goe$s=r#^v2OWAn9y zJ*W*5^2p@9z7c$Xlc2H4Wu%K#rC$EXXIT+tSTe*CRDVAxZ>}`@;qzZPzriSU18xG> z!xfwP;#kb#AH$#*o)QCt-Yw_V?FWWmubOHsRa5;VQfj_5C}i?Rn>IhV0$=$URc5eZ zw+4w^$lR8cCRSO(1sPf$GoviBZ!jBc<1Z+i5jR z!pL9{I1qhYmb|I73)LIH;P{nje@g>;HQ+)@g}nnf(sk@q&+*!e%osFsTEdClffT9} z67kq{U)G)?)mW{c7Fb8c>m(r75a7%SS=m$~q7++pwwRm&5tY z)1NR4ymp^tUnY}}koFb)&(ke#>6O4!hkV-d0j5&F-Y1qivq}Ul%hv=j%-lfTRtn`$ zpHrHk(8Wc62QIbo=Cz`tZL5L>Y;cU2p62Zz6q!R$za$j_Gg-+7b zfh72AQGa52S!y=Dvv4|gSVq(-Z4|T>=L<^CmM7(&47Nc=^qh|_J;oHS z8;8^TzgkI9nyaC!wA2-uU`l^GxIptVoZOEWbWj&Df|W0*Qskzg1aXmJP%eap5rn=< zO0p#@>8U#)aw-xQ!)H5@HJOSf7fjIIMZMhg+>Z64Tyr3+-3bGG>yZu_;x;;6XO%-a z7ky|(xz79zo&wP>mI$5>9(*|~f*RncBSb>Ezm{^~<1E5=R$8#fo~VT5ENY6qVD65; zAEAiqg9`1?(9+|D`ZJxX?ew;fPWIQ(_D$omLH&NZjZpRuH^_ab^JFMHQ(r3R{>b24 zz_u)7r<#*}_%d1~^|{+H)=%jL>q;(+2Ajn(mo$He4BB8CvZ$t)-?}ovQ>*&cHh;`+ zK!m2O>S zOTD#9$XlicCZ>!-1^g(l52my&cvN_Nl`jm!Rf5XQDjj-;57W{af?;{FjT1dXKVQlrJnB$b zOnJOQ5ip5unQiRIynys)Ai+H;IS*evovLobzIhWv3awG$A)P^=X0y$`zKKlQ30*5^ zndBz8<8jTFG=k(lAsLY*O2@#Dyvx6@_%!upKzllepR~@oOgdi*@wqTrp-xr~l`oZ5 z!fXi4(T^;#q(IMIH_(O0#rBoA#oZZ|qL+A=+&Id-e3Cv{E~AMxQc*$eHZYkUm=6sa z6{faSc}nK52kL5FxxpVvmJ2|QF%=6Mh<9d4usyzO=gG5xAx$6B6G-ntDQ%R`JLU$b z$>%4*N`*pE`dBr0t^L<}j?4WR&8?DRYW8!b13uW?*&-~3jv*=bOP@@;ik0lxWTHX- zwmePf*N-Hky_3J>X#lRQ&Mv7f0uDt25KAu8-X(IfEO~UQlAmBDqSE(ReQRXW;+Urxb&0rC~a5HIg}t>-6*HmL}$+1Y9G7W2E7b{Yxe zd7Tmv2G>1E350Fk{*R`22cy3mRdP2R%Z08c$X6<%n$f+z9+qVhrLJ55TKz2t;iRS@ zGp!u+_>SW{L{@!nIcy%p04^B=kO-vmN<(mI&~TkL?mgwey;Q=J>C(?&2l&s6GeTVC zSbnnkUx1D~|Ez5LZ-Kan?3BnaNYZ|aq(kqaOCty4Z5!+pmuy@vn*i<}uMabJ;R=~b zC>Rz6w(-n zDVu4>s>wjJ2U`yg=B74-3J$Gl%yYj5igmVn*Vc)4rFRzWD{z%%nZHyz!- z`5x!F)L1z@8~i40pHp_fr_q*&n&sG0A-xOaWzm`g0N8-%_tgZ*iqW2Qt@}srWUzUg_#6>};R-eZ*Pyj$IOF**+Me16Ka|WH$;%vU4!+DLpcRjWp z*j-@*W!1KQd_DcgFXuH13JrT;?;p2Dq@lx<8tV#Sd0Uwy;Nt*GveUfKtvpf0DadUH zvu%DU055^!9}Ir03F!z75tXEAgrXhwmt;aGgIZEE4xF+XwURgsw< zkgN?`?QHRxdK82qnZ?1)yEyU2g-7gPShzNTy58e0gEp+TYIj;}8ayZ@Pt34?J`f~)rBokvK)=IxxaSD-l$00>J z&D8A{sx>nRk2$|lr1k0S zWzOZ!n>x75xLElrA={+(z}T{N!7dHRIhByE=|^eG@p+K4{rO8x|1Vv1yTic>)xTo~ z4sHgAw1ntFp+ z4V8e{Y~ohrF@aJ0LQpmHJqUfi(;klzc~$)|J^1*6#OQ%$vq?wiezBm_f!eO0Z<5?h z_oySx$+Q&11V|&j^>hKOWAUvxJMB(jVJzk@88no!nu?Wd4tfc!bNmiLeySS8YL6COeNiRXN375gXEf-2;aX_Z-)`B4WSw7KVmcEWR7I^tY0wrcMa-2x z{kaBQid%Z@dIE-m>QO>;qNRdZL?DIU$mvxHs~WF+YAr`9)95fY+1sBcMd+c}Ht=BC zKdi!&^1(5!cu`rLIm_Gn*;`Vkf`09`G}o%-T+yYs+U3~sOygN@T|Ab(R2~YkR&GKa zML%BucI54{-LkzeZFO4yDK|eM!9FMweo01+(F0wjk!>uA3NK2g^aJUmH{jw#`9Y266zD^{aNJ#r) z6~V|yT)t_aS2u-1|)=Ie}m5J zrH#`)grk%dI4e@7HFurDlJ~FGyObNph@bBqh-1Wp&SjuhvSC(=s#|GW%dK1hjOg!LYLSj$L~?Uh5Umy7V~ zh!)Ve6gKDfvrnDAeLt0!xtXjnA G*Z%=Krk5uG literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_plus.png b/selfdrive/assets/offroad/icon_plus.png new file mode 100644 index 0000000000000000000000000000000000000000..92b448b0bdcfcb2b1f1abede5f5b751b314353d1 GIT binary patch literal 2833 zcmV+s3-0uZP)WN8vmn!XzrJg`6*c(%5Ay&O9c%;y) z_8(A-iN%{1Vxe9t=wzTMcEYNVPpYHB6@e%5`)+1c6M*|*>B zo}35f%-b{1eCNBfv$Hd^zq4&yM6O-Cc1rFak*sao{X{8U^WzrYF0t?q3sfnSPoCr^ z!dU@gL;`s)h<{4l)evMxqq2K&hyI+3=Ef6W{hHEud3ipJe|hQqES$BzrVUOpFL0z) z0qD&d?elC^%MYzT@8xA&-vqP@d9I-BM^xaTSLks+FB+EeopM*@ei16T{(;3X)8f{? zI(AGq^D|~-aIKK4h*|Q}rFUg}ta_AV>8&~%ea08R&sf-9sAzR{FrM;F*M(bA*Z!jT zRr{31`1W;OScTRom>|bop&;O3TRO%p+`&H}^k=M`Gv3pv*~@&Rr*5n(6d;lpvd&Y= zw*&*qFn6aV4(U??J@%@M?hFlE)57#vTsCf0`hUYbX!&KBNSvBO$~J&nxV1R?=fa%iH!A=!>HCD=@om{K*pz_)3v*li^Edn6eIeXh_Y!qO`Av>9M$P zFqU7Nriz}Bdq?h~+@Iy>9ko)2`eT*!pW0DFRfrweR!V3dl4D$HG)ftCC6}zc`31yM zVE(YjGTZt-dWTp>Pxmnj2%sAnXIKgAme|La?UyK@QQ_BAWz?FPs_P@Jve`Oam7j|~ zr(>4dAg25%h(|RXrNWvWqa>CVyP)C3DJz#N7M^{o?Av52kMY@;-G0QvQN)(%`__sW zI$zJiqh7qbt(GDE(eJ#6o6w5ekL3z`Lf)?0b)1#^iTc+P3@Nb4?N_U~a+61xl zd@ih{NBj-CRam|NTKPOT{}L*7h(F43f^;ZbDgtoHEtcVoDlutJZw2doAFS*qz2Mc^ z^YXqa+aG02%kVSGXfrT-c2*kvH??I<3v{X9^no%W)4)2(GRN=w0Gy!gPnl`FBbO?V zi~&-W-zvvEEJ*;(n|YFq0oZH`z~LkiQsQ;u1-V~Y;W{6qb@`Sza-ZJDt4efb%m8%p zM+W`L4ps2EfL-hYZlW@~vT<6#OFIS=0cxuDsIY$F9^?KcZ7SK6uP%41rxSgJ_VQDM zylMOqW%n4jlB$r^G54Ie^ojl31^6w);Fz`qW%4+0Tnsk-k^Q&n0TKt8`bwZll+pz> z6}*G^1Y%&n8>>4C+7yNRO~4~cd)d-Q^yvmj6l|}0)$e!9os;V;N4fwh-H2U`2ssa^ z2j%XUyGxG6IBsU<(*Kk@A$MF1o|QkH2q?SO$@7-rk}!W?ov89-0f0VHW_IH}*kpX8 z54wi3;hJv$tDp)mHB>rO_CqOXYi~p$*()Q374H3ttuT(e7APb6R6$ckIp9o9c9Y)Vn`|n7 zkL-ScUdFWS@=BC+41z)viCd?(?(w&YfV8RBEsz@M@3kpCm9Bb3HaldohFzvthXgWG zpUxm+8>as-B;ZxpO5VY517=L7h2sa-r`uqfTK9n^GW|*$rau$KY)UqYe<>Q3r6B#^ z_+=Wx-)X~i?JjCVMUB}S#jZ+eXQQG{EVg0#=LrV;sH6bK{^d4IQ-I@>9}=h&UGeM? z5;|hAFxjan*JkbTZ1gl#g<+CmqfG^rX{%3}I{AB>?onrGm3hbM9)nFu4LKu*g=K%J zsi~RV3Ddu~*b;p4@i|O$Ug&>A0v?g+i?Y4O?$#GW0v_4ceb~1f@#x5v4Pssdzve(I zlI~0wZy)@z_KjN4gPLlTY341eLHSE zB~ca4VGYm6NBFV`buYCfIHrjxlh^d;3C~4Bz~Cw{Z9v61n~nP|KA|6-4i}g3_NU{!j9+~abvl_DIc?|ni&I!>pM= zZ4ou%7C8pU)LT@llL;8XI{v_0%UWWlfb!UUNp9&v8+fr8Oll`fDYXa?Kilyf%u1hA z3yif(7ut}0s*<;j0}j2U^TSX8xZ*F$?eB$PIfZ$x_*vH(b8DhSFb9NqiWlCEm%~?Y zq`ZLME5a+^sbV!G6D@){GWLqx_0of5eEDhg@Owmf^sU=hB)lU`h{YMFl+L-lEt0WrT5<5E7FC5qdAwZtQ$I%G59e;SIYna z^Rzp8V3=`a1#x8MhhHV*E8#@azbcT<<2I&ABa} z`qvEPoS2#A_xJ+5wDsuM1^N5d(`@Ll_>UBr%Z8_6TA~k!aOtE#w5|Zlr5rI}X>Uuq zF#vb`L>^o^DG*Jn6!-;|y>c9wnT=>z`*jE=f0LWjHWr-i%{eTdN&=Hb|VL5)l@PHhZU2j60 z`9PK<1j!^rQmY;vvZ@}=?BoTx%|4_sMBFEGlg>hiJP~izqeBB!EXNh*g7MH~XJWGm zZQ&t@RDR|?X=ByX*PZA`Tz# jyzaSk8e2I(Jq!6i3v!liw|v~500000NkvXXu0mjfpO=4A literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_road.png b/selfdrive/assets/offroad/icon_road.png new file mode 100644 index 0000000000000000000000000000000000000000..5868ed1ccc3f733b4c42838cbeea9354d97c2120 GIT binary patch literal 6674 zcmV+t8tvtYP)Py3%t=H+RCodHU2BXLMVn@TbA}lihx;J+VLiuhrviNXg=kl{_%&|Uwd;Ce{8-@%$o0qW@Fq$68#e8^1%!PI9$#?Ptos5 zoj#YooIZW}Qg2eH`*c@TS3U1jZ@*n#UDYrk{?dRdFi`aUJ4fpGo3k#>t-kM6BE1g! zzEiqdpSRaT>Qw9N)+GPIHOV!+OobQ&aY=?j2t3Ap3irbnAqcm(5N=yRj#ny=ULV#) z>LvA%ZKXVdJSXI49qjetb>w`I*ED%KAV3n37#W17ufP6!VJ?@u9i`CU-~V4I+g%7* z1ZkAmEhz={xp?v7i&3fz%R-D%@+JggPVB>Oh`3}hB9<|j+``X=<>y_iapugKyRoGr zA`@=jyh)2V1c7CALlnkg18KZ+u|}bE*NtV4oy67R6Ks~9)^W(9MT@pa5qXRF zw2n^xy%b-FpTXUN=^`ih-+%w3D3llXEpl~Wf#OPhDSPJLd+!}OX3UtiQA8I$K6^um zF$wL)GD^IGw{G2vq;A^U+PaB3>LczBcH<|J1lIvZl7r=@wa*?uethHL!Gl{I($wWN zh<_6o7BYJ&Lj!tI+%yy~c?J@fSOfD7$c*j|bs!Bpko?2SB=*FgJ9qBZu)y+qo!hr> zllYWG^>+jFM^Gn2e5Km(e)1N7`}XZ)MvWTP8Q!J6UCAPTqDW5!h&i#xuCe&uDB(M{ zxDCq9*|%@sBMl7=k$ebb4K<7JyTVaSNX&^n$|hD{^b*D5mMl};T%EkNM{OEAIyxfj z<`8W>pwiW$#h1Xti4b7F1r^a>W>Gh>kvI`wtO~mZGY1YF=)en=xlu+ssTQA@6Z`%9 z_fMrR5Tv^{Hsp^J@rgHqCCJ&GJ9qw(2cj&R#gB3^{g$l(I{14e)`{;ouh7%QiTFZ# z0-c>SY0}2f(eijf^k#B&CM9tXxUAIV$&;xAx;wEWe_V)P;O3k7aj!>2eD zl($coQ}yP2^wCG_GMUUU{Exg~kQ#mb#F1SG9=aG#o#2@G`P3D47HNqK@d+efS~cEx z-+i%gbEtLA;`47}1v=sT6mfTA;pfMN_{!RMcXy8%J$m$txG+ew_=&dq(8)^ZW+e0? zR^M3sDoHBVLp{{K@x~il2M!#_?z32kH9C`J^+E)xb1dq}LQ*FO4;~b&PhCa64pF!G z1dwG^V{+tp&ir} zPS9XcccRClxb;2|RpJvDmQ6j>u358&U-lb`0RqsKeF#G&OC43>i?tto_uY3788>d+ z`beT@3RQ#vboDTFM)#CPORRoTym}vqBJt(+$ljdnr=Nbhy0NiwRK0;R*LQ~ib#>;< znTM!51nN-q=`MqiVnvnsESGX~7A{;En;{Az=`8Y>!K71mcZcMUlth*Is_(wDvvU|G zi+V6ph?&ATB0!x{cZe9-KK-Z>Uv7(v_(zT$*@XUV`in+lgaCC$-J!@j@grsRqey&l za~fyOnic6;6k^21(2EM)MS2#7s1iT3XV0GT!-o%F9JKrw7>eLSTAJ;90F#Lca415Q33E?UNC)kR_ z5C&S;D2P}C^-z2C=+SveAUzsy&+65y4}bH`H@^X7D&1+&78^e?;4qEVPd@qNKVUz$ zLLI*Q?z?lJd+xdaMkQD;)}OjAIZzMBLzAdje3pZaP>sa=@y8$Ez!Y`6@juq`)mLBr zD_-HBL?vkLI9gGkQc$m(=s`7noM^&${FY0XF1?2rLc9aUR-ns2O`ksfRa8JmYzhW- zty7dNzH)V-=pp!Oe?whS3FzYZ^pK+z8K`uU-)Xd>dcHxtq1UfpzkyXz`r=Of2@@u4 zKphUDF04Ow90`lhg4A0G1cS167^1Ke){b8;#a=MR{t7BV|Mnunc`cm7zCG|fk6l2J z#zN~DYk@AuQm3dyr26!uVDU+MW$m$TT)K2AdjgUoeW(a6T`vL~K|cch+fqKRG=AO{ zh({9|PV9+~dJI^yWC@3z{09QvJ=U)r1~?UtM8V>-rnL5h@%2v2*s)_*hg0?1Uj?oX zKgQsipAtxX?sIDo5=XZEAU+=kV=vI@8tN7mp`oR&>n`;szF2#Lkv(?o*ap1rj@3uj zl{5(A%jb6_FuU=%trQq1A1^7y$GTZV-+%x8hfy~fu}R)h_jQw~5MMpi;hWk-4N<@Y z9j&*xHL`V5w!{PPli}*H!m#*scOo+jLu81*YuB!}kt0WTI7=kfANh%aPzTYMEi zDHflVrf#WY?9#}k+T!z8$DpkJ-o1Ob;jJe36C)P!eb)zXdn56d({}~5gw!o{j6-7e zMgLl?@OJBI@mXGHf@xizO;7LcmMk9 zuTRIAjyVEQQnnbYBE)BvbW*#jV$z6@Z*k{P*Qk8m`}FHYd@7#TR=qhpcI@~g4Viy?4h6i<+FT7xBf-Vav}>oH%h~O=?%?OflAm z7N6pl@Os=FW>rg+tHa7+?Xo{$L*i5St@>9+wZ~zMBO})L^*r*tPtO8_2?QU($yglTsMol$F8_LJRGWoO?>g~ zRd3Gm^n#zsVDj);_Kd6I zCz<%v{r>&?`LiG5X*{dUOeiMxsIYDlqk}`y$=I&0di7%vA zy*ZzJ^2utvt{#zSEn1bcEWTIL7sLnelm2k4&;ln$f*TK6#3xtC%bJou4C1o_%FS7@ zU_oL>Vxo=(62Qal01!VFt`32-);g0ueR3xD#8=iHe%$c3wzjSUb|mF=MoDDe@0^*C0@4LQu36>g*kBP*F zy!qyve4DQmzh+jy*2HK2s_%a0%$a;Wof`4!BU|J(h%- zFk-}r`&qfPNPmBSH5Q-l5qYhuJ zk1qg$D>77>+#!c*;_lRf_`0>vU_Gn3SPN;IR4gr9?cvs|rO(Gto2x@^kSkm_3%fOa z$gKtOS$?th*^L`F(#=VoR6B1b0ZXIBXT3LV+QbRQ#NDY0M{AL3-p#?3aZOkQDUp*! zQ9+digRh!!Ua*iY@pcnbd@Q3A>xJJc;Zx}xIm5Nk5T|DDPSC`s!Wh__ll}PPk5{1r zqp_blS-g1h+AIVW=PjFCPl0I{En2iTb-(4*`d<+AS5tzHksl=CgfeqTL1@URwnqjTR{TYHca-2BGh(W*;0_e)^ zTL!`6*ndSrE}+L@-hmN6NLPoANGyK#op;{ZXh;u4jQB!;+yRHU-Z2d+y$EtEFhgAn z;`4zdi#3lDJ&OYBXr#snfI~H#g`pP2&+Oj4dmPq0T2^CRO!f&!fE*&1P|d)HFa$+> z-hvot?K96l`|Kll{mk2w5rcql1jr$B2^o<1(B^3d1X*M}UZXu9k!ndlb90c)M0OrF& zWw&kHmdN$2SV<%GK>(cMuot~|r|NYrbaw)K z$gP(6a@$dE&dHM}J2Ae5PvJ%k0)Zg_PL2Qk^UphxVPNh~5X5I5s_(wDvy*EZ88HY1 zj==Ke%k>Xb$T=Ea-$KGxD~kAY=gw`x+D7ZD%`7SD@yh+?x8HvI7mU~GMYmjz!KrRo z?5zRg(VH#v897eByGy#Uw$1Qxpi#3cmcN`vBS;94LSfBW|B zV=#>N0TjXr5V(5v>P2j*91f`^`8neP735^`h4}2c z&%BHP0esJp0oUYXblw?-ho15AYw>wOHX4$>5f2@Ft!%_Xz#=Oj!mc3nBGBTyadi+) z`LDEQlt!x&-T7yJxo#GT{}BSYM;FrRPKqeSQjNt|zUYAi2RhIT@pr{pr}qeYbVziP z*S_U3r@%B4`q7B!%Nnr|AlI;3Vh8@}efpm9@k4yMy(r@E*s+8Ct2}1JLIA`kS!v-V z&??Ekr>!ey45O$O73q-H%U)Yp?}#P^i0MC2TZ&%1{a8vjl!L3*3I%td}ZysySqnXTuxVEG0ZXbO^>JUj!$ssRe@$XQBvG$CY`QU>O=3}Lgjx>VnrOuZxUlvyK*Mu_j*;)|Q39%?aJ)PtBQZB+3k%@I2SSjNWg>e!>W`L7xcmQyko-vwIa zCOL|zt{!qLS^T`UXJ$*5EHQoe0K$!&J$qJ&?ERbwl)TGw=dY_@Jxvb%__vTJr_nItfIwSY z+Zu8e(dh1wyJe*u@x|IJH|OoQ-{yK&^q-74AOMo;{yk$0ksVSNoGwU%udvK`odS4D z{~<>YA3n_IP;qz2?~=a06Y<${8fVR#WkzC_#=7XJMN$&CfV@Q!-5pT*pfMTZyTfb1 z?Af#Fl1rbyZ{lb6?AbFOuZ5Soyl(2FX~ZWM)sSD(=B!T{Q;)410LWEx7IF1H{i39$ zEWY&S(AsC8e)?&yXH_a*QD)`UcyCoSlgdnb}CDkJu!)^I|7HPw<$s_FK1ZHA58gP`TT&O)cUs zQTbTL)hUln#WNOn#oa05x&1)i&Ea}h6DLkI>seKVxA-K8FWs4P(vQ{G(-?~{NP5^} z-K;;5!$?xn-O-6(;O3k@efj~cJv7$CwMk&b6_tdFV z%aN?4yJIIl|FeZOE?v6RtY_sBY)02y9saGB{LDl0RQu+~Jp#*?Ewhi<%=`H|@tLC{ z{+u~;TE>kVx7Ph7OiV#Qb9I6sy|VgNo^lDZb%_Ah&05Q~*$`daoqS3me%`mone2P- zy|*5(f6aPUd6?YqXvBA)sB%pD_{P<#j8Vz6T$AnS(W4LJr2dertbR%2qm`JEm?fcf zK4?w(m-o+|Q`bb?mNiFg$ zeWm0b<=Sjm!(j|+Chkt&;&X>Vy|lvgAzSd;mywM4Kma7=SbSg0)0DUzt^RE*&l0E2 zAtwaL<(FQ1iK7n+dUxy=f6(;l)6IHTPH0v*Z>@jDRZoQcB(GNyH-~xLG7G?Yg|9IF zv}x1m?$EH4@5^sfSi8uxn1nnj4(}j50!<(D;Z>E@7WKku`^Ji7(HHR1iOS;4+mI zCKA7h{|(SYp;!bv0h-_vJ2nQMWAG}HP8t*&0^J_2c`G_G`Y4a8T_@x;xlN8MY)O0p zS%{BADv|-1NVpT_iz6z@&p?oc_}KL&)C=>Fu|Le0`VwCiyGAM?Amk^8)Q3)dWyNVZ zBnYUo6{{lK3fD>PDFRF(`K1BKKF@LAkH~|VxINrTV17m?l~E=3g1@+%d5bULackd~ z|CO^hXLSSwY}xW0_x*_AFS?PfpS;qXMsy*1Q2zy7J22&r+vA!4#Rv$%#b>HJVsug+ ceg%5@f74bt1<-Lrz5oCK07*qoM6N<$g1SsEG5`Po literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_settings.png b/selfdrive/assets/offroad/icon_settings.png new file mode 100644 index 0000000000000000000000000000000000000000..d0c90a620d780d68bc33098bfa3897bf1066da0c GIT binary patch literal 13369 zcmXAwV_+m*w}q2TY}=XGwr$(V#5N|jZQC|FnAo;4NhY>+`~B{Z?)p=8dRLt~`|Q1* z)sadHk_fQ4upl5H2+~qwD!^ke@Y4nj3H-L8e2056fn3!w_d&fw@f`rh;g@n}9#FQVpjFxOri#3z}8P+q8L{nKGV4{nY zD;HNZ0>(jmDV{9|8w`*KZ*_GSk*z8@O;=XuSi9=>e(p1T;ma3MimbIbN zX{nffy4=j?^Ss#`Ad`$k$LDpgx%oF=-2M1n&g*f7|9)DY|FrC-ytoTEg=Jwc$uKl3uC)4 zNmi)pbUj^&cE4D=H8D2c_aK$ebl&R^d~LRv6_8zB1d)Ow9my6m=k-doSc$=5ok^f~ znPAhRtgywSCNnFY>Jng0K-3!AbT`|VB}Im&kbl%P^lhyL>>rX2ttdsH`NUm;g|F6V zyL7`QlMUbF1|Fyjj7byzO})Qt-`%0XLxkAGnD|c7HuE>x>Tsf@rN06*U^g&3iq?e2 zK8==YHXaP)70>D^Oel$QiHrL1s3i8B^Gw>6f6F5M%xyZi#A!?Q(!#z#!~9lkgW@z` zx+f1saZJwB{Y}4pWk{QhVw^*Kho8gacIG96cZV!E%5z)}Un0H1eGRx*@V|o}9AZ(V zr=s%gF`v%rlp%__m^n%|G%BgeC@&Fl;dI#H>ypD1a~#;|`Q4}V=Cxo;O(1y}o0@=W zwU9qXRu3&lcb`PB+Xg6j2p+G`_mO4?-^yz`e!uP$)N1uFk%JWT9B8px{E`P*PD8yL znmE_Rk!t4f60|5 z@Mdcd{(7Vunp)8TdN(&YDK0%X?5*HvO+Ld^00P)SW*abjWyMO`DX~$L73$S1l?Lcd zexGkxQ`wvj5qG2#ZH|`RKOx`c6yL>;!79-laM|_{y39Gz9=jyc=4iWW*839` zG-43hod1+M%k;igy#`AcrBx_oSQJWdjfURVakrG%SAKz*p3%0AFJzg9DLIG$JE)YA zItV0nxY%=Kh1chK+ry>Sq-VoAX)TakHf^iw!_GFR0iye+;0n?x$?Q#JCKv_12-J77762O}DXsu8* zT*GqX5560zriqk-fI=y)rGehN3wRbh7uhZ#CC`^*Z9ZqG6A4#_|6J%;y zi6`|2Jv{e{KGYC_AQBSZgY_x2D$hz?-XCbzCDO?hIGLH50=J4nN2A}+#XLrjhh(SE zvR$b83f)%2;e_55s-dtL*ar`#=-?rV!Kn&?SYd`bhyf+Mx73EEi;99hlGKlvM9w70 z{jik#6n*D04{P$82dca&wa&RbZdI+;%Vz@*6?HG^U^V^l7bRAc@nYyx_Jx1#tow$G z%%!7UZ*|m1;)(o)foEoT9LPdL2Vi8Js%0C1rZvKP)a2Ff&|hkm5{baX=O2iNX=pjO z_-Gf&oo88V=+}PG_x+G|ILb3w<^YU~qcl+vGPG&we>kXzCb@Tjh zkSEV5@FOaahR%k2`2GGGo^~yITyJ_YZ)X`Z%d;h9bSGT!I+^AR_*Mx#Z@K6{X7ol9 zF0KL>D^c6g$w~d?eDSCz52YtQw;sq;@(rofQxpd6SF?V%y9eaOEvGSYgY(fuxdQi5 z%BbtO!KrX1f=gId)NMpKs@L|JX0Um6$PEaEi}vZK{t zB&?V_ThilrW>8KUjt!IRc$j5VH@?WW*@vOIci^{pF|?hf(Dc-E6W=#yZcS=3f_-Q7fO4dTLI^>g>!Hc>KI;nAA)= zgW3URk-`ug`$0!^Nl}lD!_0MF*L`JOsbsG01VMMsS^MxFYv0cKc(xpU+6Z`oNA?6G zZ0JZufuL72Mg4xK?goQEYo= z`+9f8S&gVE85GOajDAH$5AfF;LsB*+U%9*O#W~6KFp&3(=3H*%Bg=w!g`%3XbF3=6 zWzgyK`%G%JSv{t;-KafnR#)JET7hcTOYx(#QkUUoMeb8|DjT*{%B~Ac)Wg4Dc!PO^?m&iigg=n{RHDTksxNxo)b{pV z+Au5bJ10YS0pH6YOhQp-3WD|^i@Pr-5r8;+o8a8>G*$gx7TCKX&x7t~o<6jy;){7f zvA{yOr5~v;DZM7;=_fIP&sXs(Nw@WYHf^*2I98Q)o>Ys0*reNLtF1XJ zdd6n6B1d93D8VyAr%tqbnCf$ptSGQvyCQ*6vZXw$!{DVtM5{-$Hyrx$fh zVYjepFnKbQ+pV&@rSmz>xqH(PYTUk;I-X&3;0Gp6P@q;uO^Dz_+iJB)adK8&Z@&$! z@7%p*cPsjR9c4ib?BYA#6ovz%(RlZ`Qm=ebI?Vu9I6J+WOKi5Je6np>(@o} z*=@GfX7P6@G0slqGn-2EHW-m&)Ss@W$uPH;$4dAR(4cbO#y%{`o3R%V=n$GEKb^?3 z&hS5Pg#mLD?>TVeyfOf;{5Nsxlwbm`G7}!3Ma(O4IuOE2C1H5_<%E^R!D`iA&%;T0Lwy`Z61Di98lNWe$Qcxr3+`|Ej8ZHAsDbCV8se_aKJijat15ow;J zcbi}x_q6pqBKzY))CV`<@Ua!b0)3!3B!dm4Ez=^;%Y26{p3gaPpfFFpN^ReBBhuXJ ztA66O0~Yd$x8#BL5033%nq`Co#*dew*GJcLyN_i}!`KDag*0Q`q!O$>D}j%j!F6vE z@2DM`4GLCm9=tgc-uL6%=}BF)HTw0-{n(qf<)b(){s#6|&)q8!3BUWVr(>KK);9ef z-}fiCNAXnIS?-gZ-mZIReVvFmMH^oCix=I{v~RV*o2RQ6LZ3m*AAA>ZZlJ3NnHA6m z2veym*9)bxla;FFh^rAp(r<#L;$+ObA6FiIc;)G(n$^S!xhN2A$UA@@6hfrb(kxShcdcox zG(Yp5i#)`i`(6&B5B=}6cc;>B1LXL|F+*=Gnf9j#@fz1RdfmxT2Q#AA%TWscAb{Kz zBNLS}H0ArfoeH#XIZv{yS8J3Sm*iMRy`Ol8x-AKkv-oAFAcuGDF-+#No5X;!;x6@gWq$=7f6-xNJ37VN<0x3_%0^49w{aFd$2 zIAPbs>;BF?nmrz^)O%1Oc zhs$n#F;^(MyYMg83tOlh&1|S0CEI9$vPy2x#-zhEJC)&3?`PTe&Vq9JH|kPm;g>sosr z$G!eHU>oL9t=Gxo@vj7pyWoUUF%KXYmRZiZpi6)~nl$2WUpVvu66H}(X-9v_aO69l znn=fhK5N5fSSG~CxkdTTkouGcY}gZ4QWvCu$>lV5#nrZg#! z$Wk{?;fv4}O$(;ubnUJrb-ZHc(*vos$QEF(6vC6+olj+pj zOZ*|=N@>Xxz~YSD`_ZNgD^cjU5=L3C4&&$a^JKYG+Pz2 zLOP{h7*V+}bEQcI0H)|QDxmJaQX-p_B_?Dtp@KlQ(8Ci~`zlec=E2zjzM9lIe++=3 zoA|ZImX4`k063a#=jM*%RdzT5@1w-_lh)e=@WNsGEuql2nV& zf#bZq1(hse_%kK5iI*z?X6iKaQ@~ zBv}TWT0rNr>i+R*>_fs2dCkVV&T%A2qee8_ek$cqEKclp%AbP*Tt7VKI;8j_jhidlEZ|_k-O{IpJUBtE--D&+6fQ%Vm0fTgGy{i#u94~G^OFSI zx(RtmA>A3GMCx}3#I7`2xc+gO2gE;*#u0R@;T-PM0Z7uoE$>4%=&?+WN-vCzjAt2` zz^cUxkoO?lv=3vdaSV`mVU>i5oGeYgJzJN<;bB`QHf<(mr5uVmCA{bj7R%7V!ED(+GG)K>r6RN!hFv51?z$Bo}Ws;?vJOd zQ=f+y7E9?%J5|cAM~(_37UbCruA9bKcQjW<(|Cb?&pb{FP#rXU@HDeV&7wSfTy~U0_%+U&vCi zm7!)ba{vtM8ybOY7;%8W_tbGZnStggf3cS=Y3g0gG(NpRlD1dE`wj!j421Ekz4k25 z{1wGzbN4PIPjOls#uf5naXod`{;{yuBXM~8Hh?wvfWo()=SI+Omn-IfY5Lwaq&c%6 zP}Vj(qvb`4vp+PsKnd(0w2l%BPIK>)gG655>dBXKtK2_rJeFdE6JucqVr001iZ;lJ z5k&DC@_oG==Kg}pBT^vuIUxSYS@Z+5oit{k<7`0(sJXnw_D1O^K=+TS+B5*jc)ev6 z(@7BztS>QvY5pwY!{pnx?aZT!j2~r|f@f2!WeS zGD^am&vlf*IwY^6W~eTVln`a_c_6EO=8{o7=ujsYW83}UH7vF$gJagUiC?(c+Y3u#?x z8`;Vsr7K&WX)F>D4I@Z*BTvkXupnQsS?Z8%NA$W0^RkhC{cgDaQ+Ep5S@{vRF__B^e8U?(eM^o>(N=lF(kWdA?X8id?nRS0+DAk_trVyG=+En}&uST$qg9MAD&!B;lOMZcTf$n0?Xhf$a^g)yZeApF7WS%0~dBe9!)p^hg^WK zvRP%RF`_m9n4iqA<`$s|F&T%M)qA%4J+tT*v9!+gIHAT|*hR^tgXBIU4|LMw@iYpbOJZIly2 zk!G(FuqcjyVoN6Qj?Yzgnq%`qxeV@5qDko0VSN6%%G;+FtVd&y=Yu1m zR&*?W3o*`8VZ?_w!(Fwk7B5WMl&Wzj4QUM`#i_v>W&bP-H4o$Zpx0Yj zmy-+Lblk$(FI2*OxG!!_i`vm(oP&t3DDIZ-D~++#PE<9cbBW#htBCWSJf(F1WTed< zV3(As)x@o1Zl28b!KAmMjZ9=ecw2(vlQGl%`)aH6{P)8@r|XGSTCDT$6lD4G zI+t1g=a!U4f!pHxM$&^|>NSb{5>D#=_2wC#a|5m#{LEIk@@>LzY;fkn0?G(Jzy1F% zs3ZijUBaS0v!Nf}f=xnGkZJO78CxFd`+BU;pQMA8u?P#hl=XyG8g&dV-`7?Yc>Rl9 zt2M_8_zB?8hN^$lxN2{DG>a9INA_r+00Vq7RQ^_Grd)DLUW+_(MZHhcP6~WR_o51E zO0aZ)zS_Qjuo{b-&gQJIPhDgw)sFf+V+WQKod#fy)IWIGotl7p=xdWz1zo}1*CbV< zI)onaFINK*<&K*!gDnBtrV^9isS;L*=gp0H=o9Et+S+#CZ;$8g*6gij(U|l>7YX=` zNc+l!V;k1%;>A4n2hH&+Mp9Ev@aQ>^{m#x8o3QHm?OItcjH>zJ*N)Tds}I(zb^4=X zI~YqhaII7O++aZ%SRjErd=O9MuHZLMT>Tfoey7drvUOEJEmvh11_b~V?k3Y?i3Goj zu?#$oLjl}k6b9u6>vwtVk9sXbolhiuaq(+AJA-Xs7x5DO!~(ShpF58)~gc2YeJzxNfL-%2h z01{N3uz@=Ov$NxdUtozZhdJr}v~Kaf<2*^fN)3LXqi8mp$8T6I$Rd<^C$H=M5O6r; zzVW8Q1BQ956yNH8z4Mv(CT}O(_wz}Tz3+JLepXOW!N%CHV(E5ksTe`FE0XBqar#}i zm}vkjk9Ddt0v0ds)o?Y7wGd(A-2>I~c2J zmch0`7~q2bo|@d$@1+9FHzo`R6a;E{219xL_ILxS2{lyQ5R3BoM{`NrBS+-dElJCH zL85T4a(91UPVIm3M}P)Z@mTg0S}Ow1T)uy9l820u{=LUyu0Z&^@Ix9%+uNBx%Zzt28PzFCT^$%)u3VycUY5ON9VU_SQJ?Z=&UlGl6Y})$?d~ z{$=627$00m>(t!b&$`|}kG}mJ7muaCz^BId_gEfr@>FMeuK`d1{EE5iSV{ERZ{;6o zh7)0zDt!C~d2uwxalh|cVQq!HUcbN=QHRL^(Sc7jVRWEB$!NIJmFD+IYT$~afK^P<>6 z_#oSfM!re(p{yL}*?miUO&W(~nI0ixMfm5qG+$TKOwjsMz2TN_@2HHxIE>WZXZ^oi z{2T6@>RL$eHMojCe#<&#I6@&Bqvgo(3`~}xf&TzaG**Onpt+>uS2WnYXSAtkoYve4 z_%{j+3LF@eL~Q?*>_YPDf4oxJ>p6V@1K9oSA?pqFX2?vTrMO|5qWmUELd~B4v0Lov zU)q)z1sKcpF7ilaX+1$oS$}@}u7Y^Z?V`~NT<=5t-P|rxl(Po|Yk^(p^cJ}>P?;ga z7ZD$b9c9Axw_Md(D0d6Yjz4`Sm-l%6YIKISwS`_}i4$OA;;1D*+tc9vEO#~M0W zp$0*A00+Mup~jN44VCf0v@{kB=e70WKv<{w1SkZZQ`vtevrrhcC?qL<91c;YfFxT3 z%m0mMy%s(a(>w9mz!rxYR))5r?3Wc2>Y>CmdR`?zc57zw@JKt*{t8K9 zjgh0~J%g7BK)?=l@|9Dxn=gXc>Yp6MIFy&WcceTPAJ!#_v$Cc|B1Wai65{l^`#WAf z33AT1|2SEE((cR~j0~Ixm}+dZ8k}CYR_X&8QoBg;9X2{Xy7pO)H=alIdP%sT`$e5o zya$uv%BJwjm7xzcKQB^2AT>|nhobBMiA`Dm{r$A*u$#tjSKpA1iot5`!EZ@RgZ?@g zrL!8GFP1da)(b>?%$7hoem-3+m+lwf@$k%Wefmg=Wl>q7n?Qt&9O&!td2HM58*d9+ zqYUMx)+T~vArb!%aLLouHAH^MBUualTdgOG9|q;gu>Mq+TVCd}=d zJ@F=lv{gn9$28Df1X2Q<{wi@yWY~6KS;TYQ8#ZMsFyJ?N&)GXi;n{j0wOUMPx#gO_ zlAA@S;_o#*Hl$Tx7k1Lfg_gp5=A?9OPZ*qmW;gcmn9Wy#BdN3whDs@c}Ai-;X*4my7!8Mp00wWCvuw`{x1?8|%g-kU|>$a_I zLh{&4m@rnLIz8)0;HqWSG`PQ21MT?9yF9;9`KWU>zi19XY}dnkly18jy&0V}HFdKc zai369c~v>`=qOJ4%#af5)-`GJaEc zwaKV8q&qeUt+=xmK+oQQfTvzpY@9|i9^1m9Tmj2Vc6M>$ z_cxP&rPO-}n#S_(w%y2Lw<$C9eO!)y{P)=q)8uv3W;Rh9`8$7i>#<+J8lkM{xJomV z$yfx-H?^csBcfXh&OCQS{7C)*r5yr@@d%5YuhZ@{@~3x^@L)Oj_6_8Q_ad8cIqmg4 zfM7$GMx#cGjB2&WxP#vsI^U{oA1kV}Z%LC|V@$Muu_cxtY~(l_D?CxuGgtHQ<9^m* zzCbuwwZ+v?vKGlTD`H1}%~_LrmDJXM4)8gnQ|OQ#utv!ag~q`!k4)q+d&#L=jn)o~ zUGpR)_cwQ!P->g(VDx6IS%gzxip+Z?rfn5zErZGGLi*sjr7YA8u;rd(dF*MizM~=7 zp*>O;2l%atd|+2{5z1g`u56t8nWYAjhCE5@LrRh0+pjf{1jAzPN?vrpXcnQc)N%Q~ zx$Y!94@(kXK~LpyyQH%;ekl&Uif@^uka@s)uX?`oAyoFHXJ(GunD)Lv4?%#^3jlyn z^X!E7wpIlfWHPZKN^%XgcC>wFV;=bA7~pw5zQKqBnUIl3G5@(9>fMZKVN(OvQ zV!!cUY-P|spO35eE#MP9GOp3C-6{KWx=!-l`_gQMi1ahJPa7;XEr$7DIJGb;@T{)~ zWXP=GdrS5HpXZG-2^oZSojrbHuY0Y2pV(yx%K4Mx1WC2Sm@)E{_*msCfFpIK%V)axznLBDRAcY6~SDw(NC0S%75`#rS)`$B2d+ zgv@+2`}9FYFMgjk$z|8a$H!$>Mu+BNXuRctUYWpM?qZdCHHAEo=GL8X%VoyNu$x57Qc zLZejp(8|Bprnp-SM(XWxYA^Ix?gVNHt=GUFuKD3llR*{u&fGJ(1oYUt?eePavB2BE z;``o@J6S-T8^iRW&YEtgPOCLe)pMLC5G1YZ*z`ruAY_|{hK7c>l%0%~=Xpn2i0;b9 zehfWHi~6jqpx-e8q-`j7!av*``aYlXm zRoDmC&a?xvZLx9XIz)H*;TNOqVNWn)%0GX@BC);ipQ2&#UaE@6Fw8YTmf<4uS4dxr zzaO-m!M^LXtc^?}rbEIbFqw-QJu!UO@B8yvu$Y_@>(plePs+iGA3uU-X#O!SWE=N# zpn(2VYoEF$`=eDC$UK#Z;CcbTJ^d5??H8oJ?gL|cE08lE<{Ez8r7yB4qZFJD6@b_i z?ncz-=RjHnu##uBG%I^m*s%9JlU}}~l7M9?@XP00eLCpRNWne^ji0&eUV4nJzHieX(+ z6kgg%7-)ovdqW8m^4IdX|F(kZ1h;=b4xi0+~o7jVxjV6Sxzgu`}}pVzV(&^5r>vwDBJBvSW9 z-as}L^^0)uFpyH@*V0#dUi$I3{Hqd)F$b}sdsWA=e;@_)0YWN#>?f+& z_Sqn?4W6E`y11tZwz(QhYh!5r(nSA&FNuU#ZVo*{ZUKM0CeKcW}yuo?9S z(6(O7MnL})okUv}_ZBbrXJn7RMs(`$E9q+J_H$el{ZxIf$bLC~uvA0d*8g@-r)0FT z+=w+Gmg5U?1qCThK;EwXFel6xQTF@+(uBAFI<3=%XZz_B)NxNn#0O8Jv0bO%o%b+K znGYzL3*Ysn{s9`w5#Hr??%pi1wDNDsPDKQfkJ(K`U(46>SyF^QLuY#thiF>wu_tfbfOh42(v1o}HD6RRaXukDjU()A7~8 zmQVs7*MI6dU|)@g&=rO)N+q+a{+RZAfqzoE8sFyZ8%;(@`j%l}nO&D%T1;TKFT#pJHA}mAWX77IMyP2qJtutVRK1r7~&pMy4SJ4L)CF4Y2q7@~ht`Kam2{b)j;%}CyClXv67Tyz@7xvFrX$@^)e;~2ta9!zp&^>9 z42t??dC1@f;l(Ns>$+FWC-zz%#YJzg;{-<-Bef9i0feYx&{G8;i#55$U)k1Qej>bW zq`!gAEgvS$Vv2l)T%J@XXFggL<$F!sZJ@bgo2|5~92ZnE2aVLo6{u3M&6lv4e7X|6 zNI|z5n8}phrX*CtO}D(QM6j$D#4W;P&2&qmH5e>fj?bD+wl0t?$d>;2F(J^WKgrGG zfxkL5p2Lz1LA$;n2kUN>k%mA_4_7)-v^cXJ(<$8fM!3|hV+KrNziHk)*G+m7ZkzJ( z4}~+sgEmA-@JN6C!w6z7hxuK7?$+(?UB0*b*wPvO^{mDw>TC_9PvJls^v{UV^upa^ z!QNY{EAC8*m(5yAU3=1w^8||V2576buj zjzGxw;-7*e7WPt+m>X%xhtNt5I+GIB?|@&->{zGYu5Tr;l-2y0O-Wjl0hPb9LrA=s z`I4}6tMLYYiVKV9FkkgUm!a?DEdL>frX_b^8p>-)ZlO~vNW0PToEL?4d-4T39UVrRpB@~os}?Bbgm2fb zjAic&-a6G9?;ElmBiN)Sr8N!nGRr=VlZU1)MOM%l^;*Qx)MHM1ec{PPVLDF^C}gA# z1BuN_S9UJ(Y)~!z1Xjh5aK8N}UYQI`LueW`T8%=d2h`nC*)q3tfAQeTP0Wbp7bxQ4 z9uh-BNwPGLt#qL7X=`n#U88zcfPx59v^q{o3ZnsOKYbQu0w17?-i{=c>+><;n5HN0 zrHLo{)r_S$1x@Tt@qD?OQ_Siqp)FA-Jk7@xg;WdY-@g^Ozw@H3JoQUKiutJ~I+@{A z@3M?N4^0gnDyL8BLGp0aTJx3i?~OjG%ytm*(m7e=p(*sGYL14drBx4w|9R;SU5=+R zr!U4?)={|vA<}`Imqoc5r(TKYM2c4mPdYN%^pbk|Jek8QVU=4a#6Ci#X1wW0slr|L zKRW_-_d=%{EGAGRS#kVBhv`8_o}8mX!aW_8sh)x~{6jU<(;pY~r%3aUZ;L4CWxv~K z!xr_L_eBQ%F4u(y178AO;S9+>$Nhm<9niNP99Hw1RpA5g#h#7!m%KGD4KmU-2L$Z* z#_lxqSv}ckvs_o8v}Wiyf@6_WY4!@OtbnY+V*v2HRjHMJJN>W3QrF=e{cOR`2D-BC zwm;F{Bvxj*NP1jfp_CT&W4I&;C1i+^_k*dwi?C5 z5Vis(hZTu=EOU|UNB%r5t`m*?X$YF*)PYSZsTMMBnJO`-&3OGa$>LJbf{R5*>f}epn>A1Sivjy)eoxt8rcG*7 zo!{Q6vnWC|NG8Tm7&bq{(ABy^h2zRszuVXkM0x5?bY?gY=0KGE$ms8r($f8+GPSbS z0y6lKF&*p>ur_N|&jg_GwkO=yY|q-Z?-uqSFlbr zWfGp8POe<`CT-cWdR^YGxtw3+UV@$Q(hSR?)DCHA|4 z49&&`xj^Z$*d}hw~JkL4L*`Bj}N0ga~?lE>jb_NE9WBPhp zw-^|Xkbpl0R%QkU#yQu$QQ!gC^_uZD28Qx@4$5671_l^|zScF1AV&NoTdn8q+XDEI z#q{#T|1u(2V?~|A!@%74%(yJTOrL4|ZCcM2R3wkzG`j&Jxg8a>IF+C$5ObD?`PH?{ zM%T4q>Dq$sW^dl1BfKNtv5^1T)tF9xFfS+ySSivdsoJ*d`{ZM}VjFUdP-Bg#Dq8xX z;os#_0eX?4gZ$l<$fA{QedX0g&}&eqh-N6MyEwR7k;J_j(tfQB{y1m<4{ICS$IHEj zfjZOiDVHv5Oj0P37L4GXGcVwlpMLSe(iMkZnsEv&3*Ko+NlXyvFOanyNDv& zGhFWE_O<>mR_cwrtAz_&=jVMw#u_Cg8csx}Y50%V=Fc53Kvl2&z%$KNcdC65LVG#a zKJMiwd4oo@Wyd?5il=?XZTOE^cKV^coGOfoefCq0P5Eq|y{ea_ylVJqbA*R1u*WXafFdEvWYmVx#(r~Qcks!BSqViHC* z8Ni1Vz-d9mEQb9|hVUMWoI|5N<775CoC#a(t;SfNbcz(7C3hbsSP#j`fH)G<3E&0E zhxR`dgNWt@Sq%2iymwS}*qR}ZJ1viIesTL82=eD{o?H^RLNW=Pd|ILsoC?&tibHD)%1i} zf#+~#qtM04u|CRi5N@m>QX=!bS7Sx?t{3yI>yCcQ&efj@(nRyGTjQBFx0&J7HEb?> z&J`TZEj668)w=ii0CQ7{85d4925hK-Vb#y##Akkz{q@@Y@>~`Gn{(=eZk!;1bS1Pw z7-|b3)wDeJ^-raJ9_-lvdWLAfb$9NXGViImp2E+rNb7}hr~K`q{4*!Qp`k8iaiMp+ zB3OKZ$kE0eXzAoMx}-g(b>!zmv_V1Mf!N?P`?@~^y9Q{Um((8T#1-fyme>B z>=UYMnxLihs)g|E$NKcyr}9ME-1@s~_;7imkd9xp(``C$k#5m9m^qN+uxeSH)Auoc z;Rkp?kFh}_;e^~?CFch>13oI}Fdw5zGLGgMadaWH_ew(GH^y%8Aej*t-!QcsnFqqy2)% zM6)jw7n4NMAJ~m=zb@Rh z>!I|96t&(2)>%+}g?xl5N~SV%$Gw6}YhsO;r%mH4r?`FiDAleuO`*Fno*8MLe3Z+- zy#%{o6n)6{6pH4hq@(mlR1F$1JN5Y@S&gdrJwyFCb}5wA?RO-sc;EO;pI07}X)m(_im7)(?m#Xy&H( zP%Ji)$Np&CiE6=rsdK&rjqS#liPsIL7wT=RH3fThPLJBL13??Y2>~&tG{N z1vkzs!woHzOD*Lka)Z(xzUlGl<99f~m`& zmR|K9mFy>TUSU~Ij|k>pz$-twFMl?eP|mEnH`U&I3EtnSCKQM$ttJ>}zy4C2*iys0 zTuaKP4HG)N)i%mbAA?V<*;v%%!_<%5IsKxVDvT|C>eJzKGXFH^xFl00@)tkpv{>zp zpW|)$kBNZ`m>ZWMZhRE4-Vfh9>_P%QC&vPKD^ClS+xCejdq5c}4VxlCkN@*Dx z(krIQo`+y;td)xk6Sg9(`efX6%|KC!r>n?fwQtm)E|;4~`1tEYFL1;826=`_i@N65 zmdpKPNU6`kSUC~lO?T9Z>BmP#^S;;5X;jy>IDYnl{7`aH7AZ=K28A=B%4go~nS@FH zHz@*K2II_r<8uM7={m>4!6<$MAPNO9#|ul72oAW|t$0<&;XTj21xJy^0B%@!%U^{W z-_sBND(?h`^LQ~=UwfP^uV_PTcvEE(w%R-P`6;Fz4_=T1V&P>sAb8n7D``+==4^)K zG)%A94xIxcAzrZBJ5EFvh=kstT0_}fAhLZlTnK;$Yyy!m0EjkM?r{T=uzF^ErPh-k z31xw>mt{$hgwGxx#3YF0o@2F!V)u056Hp~n`mJ5haNJL}>F}JN1&@Y56PCa>8WeYE z5`rGSvvRb-IP*ZL6l@y^SV$1&L60iQ9^70kpRmdQbnQW}67Wsa27CFm7gg5vBqa`n zX;um_pq>#Zdojj@{n8?`Cx5SFuBYKo2@qYrWM3Eq!>3;y3wddV9i`v|@{fRA9 zb@vu#&}9MQ+dmz6rN!&MLFN7>^xnjO=<&*tSAFliPHfE`bvGLaYYHo0_I&VYyt~@j zXr=1pe9k45UCfy8_}fax^r|b*m#;m=F;T10@)sj#9uJ)%Yv>UJg}YKfSl6w$_B~2h zkqMdD?(c-N#D+>Nn-iytNxU!0DI<71=5fMw!L`c8AD;d8VB~nUD?(r{IMuhtw|Cne z#UIul_W1UQ)1(AWobs`+zEvvatjAdse$JXxBcs-_?jJLuICPgGN@RziQbTxjk?7GkN!YqyNsDls77F&t)Ba=6++^G< zB0-Y9!|QdvUy>BAxl(iL#jFMgE3&WUs(&HEU@5f>uT-wMmE|wioC3*FIc<@J2XjIA9U6^wDuiL^vdMsjaa!iuQ=2<-5 z=}WsL82UG_{nANFHQIF2XaA{>?{^0VxtB)+QK>Bj4y&gqV`f?4OHtIaz+>c+7gV{6x2SHBDoZ5lPLaA*eev3`F_YiI9pV$I-~P~g+pe&mu(R!)^^`i*bj zEuSu6yvk_6>G6o>iZ+$lVS=ta1c^UamES;{im7u^Du>t-c$exgFl)woZ$I_H>80{b zShr*)ftx={XB&oNbY36VORe3l_s8X{pb1#Tr!UItislV5+tz&EzeE;iHE;f52OV1TVRJ*rb1hXDJ`w-c9R>dp%wcsV>_bofT#;3H+j7aGlj_PP3Z&hpS`;@|I z!2w!dyfU*aMD$}ZEI8Tcwy%E$u8l3w>zm=Ibe6)OBkq#U1? z<}>ngpIQ5{zopQiizdDKaD7lTuW;kIgvSY|s=p75q$U}g|e`d)cew3PkZm?Ti zS#vg_Hk={G^&(9fZkT!GN}-E}N$%ITe^*x98irM=pPsmuQ}(F7CY6u5u37ao_SIt}aV3u(5PDQ@9>x(C#g_v8~8f+HIYhudxD zjVDz_!w{H^+;bM*!lj-j?V8JLCw5|=pz!%!Y0e|t0U$)ym!B?_CsUUP23?T2w3;T6 zfH{1817vAR8H1H&QnMNEpZ>sRDOi#wTMemFN^|6 zJRb@q6&9nQ9Mw``>Ccwmv!;B-U0lQ~1LsDV#H3CoHg5%iJNOqa5=^Bi8O3Mh3e6GzUTn8Ibgh8*y zAT7tmd>4KI-;STn{sIXr!Ce!TvUnZ^H~m;v=z30Pum<)DTZ~iw<+OkG-gwYY-w7w| zgw#iamNvM=r_a<=k`xDJT5$NP^!4equvBvAIVEhOWN5u7Qmae?d!=GuBgE_4pPy`9 zB-!h42JS(BEpNVaie8m50I;J_F-}{@Ajqm%-EX`KYa?wv&*1+KA~ADmCN*c&@>N(A zl-~q`JpQGp2sj^W85?}-s`o=fu%yPCF-gMpnSC->+V3{y87W_Hq2GdNedACFvL}7| zKYhB8O%bj0N>tGO(Wte_!fy73`CX_o63KRRP!}Z3kwy{@FN*uWLpGJx=8U73n#KCdo0eE( zB>TtP;<+{4D{s1|F`%nJO^D1?+n&XZ{wns<;tB6zi6Zmb1!WoU3%t3z9CFI^G0ao* zhWi#YrbQ8c5cn5cTOKVsK(|t6a@lbIwsqrgjDD?T{{^mO>d?(4nKy>saHoVQ>_`*G zEZcPOc;L@O@Dl&R#-II02b}!Y{5bjL<-*#~9*Ri~8&~c64$shUfp2GBDDk?^1)M*p zL)Bh0YzTUr-gNBxs!7ODq`F~GW;1I9u06->cGcSF!!ikdZ`9^lx{1+gx~P(~kMFIa zzpv7E7W&kjLVWJ;4+?`eKqHZAfpII@%jPEZ(~LtX270+q9I77r&SP?RTreisPzh35o~2lx=rA0{DIL>KxIkm zr;hH_@9uj;L=#@MoV4!!vG4OsetAacBx(%pjera3xe|BroLAjsj&Xs3xP`R@xT309QgCh7ME!MIU>uNII*kamIu41##&Q(jn2;- z;0SIN9#aOpCesme&gGdQmo#7Z=M3m8AYGKI{JXi3;gs9t{tgIK8jEGa{^&OWIde>W zSeck`o7K&?ZtHTmw7pOXkbQu@ygRpE`BUOUaGo!aQ`HyM+JRYlMTs*ud$>@0=!i*Z zGEz9Jll7kLLti86D@=81=zE_*S7D1Rv3~J~2H$6DK1f&k&vr7xZ6Am2153poj-+)j zc0xJt9B=#)|1|LBtwnw>dsePOn5e_LNZLG0KwI0+eFvt`N?<_U(a9*BAtD)>{ml!s z#o9JO-QFF*catQk>apYCC7!fCa;IXmKHNGXHlhW%sMj!QD{8OTj43ChJV0CQ-z%sC zF(S#-*sbF~yI8qwcvar4x$J45*kSu2lTbk|zk+P~a#;}sKEd?i#2D2#T5VDamg9}i zMRj4;xMI|jR1VDQDaxh4-gfNe%ALHOD3K%jI9tCnFvmw| zk+H^w0Es>1d)itW$<=e@iY|BB2N+IdZR^dNF?lh&R;T$>OGw~{yT(jS_bF+lT+|ic zo>2`gQ4h4{CnV-1j`ksA%RT>*`H2PDx$bRq&C-}A4)m={NPcH)7W8=z$}Me^nC zr9ApLnEZ{5_^_rXP%RDk;*FLz!VSwTup+<0+9l3}Rqp@qAdVFfX!8-o{%Esi^&Oh- zkmf9q_UJOjVP4)aBED#|f!BLBu8mSw&1X$tJ|bg`=lA|9p-sR=wB^RMAFdHUpjAKD zLqJ~bDTEuMy*R|}_r*#@$oC@mQ<*H5^)U}2L3fZgA@p=?=4jh{WB76PEDY zuo#@4e+f(^S<_N(Lqsef*B@Qvu+;f!?yClixG{BSYa(KaZBx$dXB%f}bO^ti|ANxR z-O^o_uwg9}sLGf^&D$QqyU>uFJM0jJwHnT}uh^z6G2IgiYk?eLU$GgOTwNf!34Ecv z8>npYr3JWWl&9U-cgQ%wz#-!*uG(9G9#)NNy^N@Vf!0}XSU05{X9GP#LXxp|W>s5a zX5($NWMrD{&j;%@v$ukdq6LBE<|q8mieUUs8+6(3t<;<04W6{`ZKn8i6Kdd}#|8^MykN;IYv!;^ znH1Od)XPTH^WUpuI#lYSeAZq4w->*;fs!*xk~FvZjEGCzY4|qf-Ah-GJa*zjrq zqf#E3fU7dN|PCX)~TEk?u4#mzdd$!-clGJq63ch3K%uZ>Z z0oV<9%%BL17CD&#pT$<2zS6$N6`3DHI{>+6T#&PD0Mg=d`2Ptx9%M{D&SiPA5RjHw zjXqW^=Zh{kV2h4@Zi7(27k5?spMo?yaf%Bkjmew1r@Kc{-70^PHkq!?#Tdf`zc-tA z*WcZ_vzdE}@g&xzL@{Ht0?|!+Wp$^cPt-{g!F;X%xe2(juI5axKK4wClQxj^3qAXq zhhxxBd<#f9;$iycG1zH2z`)@UrDWu>xEC)0udsgBmj`Eb4&-`D<-?1?!Up=Z^3}ElHdJI}4vV|s|hDC{pO76Gbp7GuSby`DPBN#jKOrfcd z_amIbHSqE)%(>bAHP5pqfHyKKh;#2_4ZP1jO$-+gi zVkDa$Ww*QnC8q?ENSd#B(ZwvVnN9pRBuVIBeSm4GWcl;GW0lSNWMncAoSY4ZG?;hS}#iA7~m@D)K^ zp7LVglOlbHoZQG{eq3gJso$(_3ss?CYVXQ~f5+d@LB1a~9PCRT#UHG8Z$S$nsD;#+ ztFcW#)6;xs{&Q9_9k5m}?j|9w^{_Y(jXP&6WNhE8yN^~WpjOve+?FWnCe;~HE=nTg zoaKS!WO)4IY%Y#ruhNWVbwm%K`%P&!Fk~Oo`oZ}IB8-e}zJ0pGIzOUBQR3CS!oL60{ ze?YI41G)T@n~!K&9+h^SC3JZW5?B|AH|aIns4-cXcuKVhFggiTL^2g^cf9>BgqQe% zdg5B&!$A>YZ8(9!=bFXbnVOhdjK*dQ`K7xh1j>{zUwFIaQP$>-7{q;r_T}=~sgYfL zJ~H}KP|38(01CswSEooIW~S-nL%X)?6lFmA>XGWeX;_*fA5E?M^Fus75b0U7V1Q z?oAnr;{3t2C%IZAMfD_xpw(RhP(52m%*SdQy^Yh~o_<+QaS=50C;xb>su}7klAJl~ zw>*<^y1BgwzQo!0UK=#Y9`qhpTJVe2$kvfZeoIRDZn)G(Ex;R|I`N}_0Z#o(%rg}H z8t^Q@P0pG%ghjzap2fzu@BqP$?WH~V0dRSH#D84lwmAz#zH8;tuod8fS>aaF1Q`Ol z0Ae3^p?ynRnMP}ebqOrgltyY+^_ks~D0TofaHzZPNWUJLF57tBFlq>->&;X}`C}zD zF(O&ig#|xVSXj#~^pqm0YsRO{FXV6 z9NMwuh%XXN_yjA%633U@`fgj|Sbs}%v29#I?39jNp_Xh6lP|H2fZs4h1m&yib;P4H zr_}FAuyP4F4NCpFCW)-v@I4~|b8LbckzGsV2PSjFfg0fPh#@uonFnZ($!QQSwH+Ej zo1(5BQ(YTUFrreQzW=KTzzYZscP`!|ya;}e@-(_pdN=OM0y8>>$w_nKV!iT0p6RJ@ zS4y409kmMD{NL3EeaBm%i;I2Hj2NYkoX$*=d!w$?Iw!Tr`KX&0Pa40#-Yddr^6CP_ zRJ8HY>2@zr6?+~VMh?gt@ljAAn(&9;DrBGFz@g``DfL8Ce5F8h=(HQqn7Yd}sJo;~bI@!$ zda~NRlv`BcHSEn!UCCOfV!s^vJzHiLvw8+8KK<81Y-$TH)7decV(i|isq>RMX!}r0 zT7hJO!{367eTvBX{l(3A4o1*V_B$R*70xH2D+yb!7e284kW%R0cE7iA5;}=`Lhb|# zlX~!9DTLrya||Y+i>&|oIm{ju3xOUR`CTTnpmWI!-L8+hd;)NWXM@(qfokF09Y>&o zyP-m4Ta#md?ZWs?#k5MM z{Rf8!DrLGA7uUU!as19+k*IX-Z42VeI|FqSIzwRA7`cbO7q-iqi}+=%Nr`xjAdCKX z@o)U$$|r1@Nw3Mp^_7=rbaye)N3tuIMEBSZ<*d$RC9!|RXHoaFR0kJQtncmu-vJ|{ zAER1kQ+Kxk*={2*`arZ@4%w%I;4kw~-%2u~eHQngOr*zn9H_&ry5(zm0&RDUE3TC2 zJiq5WU+T(PD|sl8Z~SRZRVaXXg{jQGd@A&U*r6Q3C%|$sd8j44?EWYI)BdT4A}G8e zihvUOJ)dLO3EN8o9#Xj^w;$`6S<68};H?Y;Ivb8s=%7HdQ0`NBlCL3__)) z_hosrhv3{~P)hvEHfn3Ep^P3~IAg3@4h>KI|2CCpWf~VKE_AI8yb$Tl5pfQjK_*Vq z{O~4j7&_$u{>b?a)JxmA{j0W(40=B9DCz2y4apFF8A^QH0@m*-$T~iGc9tz}JOPlM zf;;;C-=@v{rc08%yCJ$s7<=(OHl`^v`XflB_`{(T)>&%a)Viq*<$UN}!n4SgKc5^M z4h6CSN@Ry}@A#--%c{q#q$qP@1A7ScuU^|ZzyM*UphOZ>1Sq)*mUK&%n)2auf8rKb z-qh-CU(p#!1CHOH4Er7H@$UD4`Btu#on0%U0lGrJ6sohBU;#S42t*lx3r(=xxJ)Y39Wp`b9C**)@I|(~jWO zU@G1klY5%(5kN`2JvB?ndAC+{PGbgh*9AKDHP;1DyODm*W**$H6?K0a6>1=rQO*PC zwPgWR5IYqvt7e9GCFNrWeXQ+8S5^5y4^7x@O z2(zY;B%04cntvi#T#JF)8_=@{T8|_W8IBEJX4g^q*w#mcUwN7=d0@INjV-zJgp`L3 zZG6<4PIj89Varclx-Ax3=Tz2g8Qz(}R!t3c0=*Wx*Fiz;r9=c0*B6yzMMrXza(s^K zHFQ5PUYH{Tng=&15~d9~aMBz(MmFq+Ai-k?o?s&_IwS8=o_t`PKO{tFM)*u~4+LIC~P^lL+$Qa|f{`Ctpj_hHYlDeWc)`{>QbFsA~efmx2Wc=ig3cbeIaE-W8B74FN)L z!GmXu@{SvlB(y#B;d7yT$)o%I5}aF2%dZnDeX9-JTM$v0s5Nkg`7To5qvOIalP@56 zH~wV5S1zSiaVPKj*xFnL82fQnbY|z&*Y{GC7}JkCI-cIRM{ENy;~G(Iun7 z5oCyUowhHMUs-v3taGW9dh9=5F_@?idN4b;lz2%4GpiMB{my>8%Fc??z^8Pm)6>f@%sh82VyS--)+Ze3-~`}K;Hta zBu0#1=GW$@dU%#Ef9JxRHfTh>5*yb!hZZ|B(=&xBB~{J(C$|~xg>$2)mPBsYXMkBx zt-o$g&Uu8kS%jY+pD83=%CdGqKDVO$>Fj3(vO!o2JBs1=hm3P8mM$Z6K81ZRv5Z|` zz^wjaX1^Yl_YoVS_HwH5rQ4>bDhK=oKh4TZSp^$}0i!VV1F0f@7O zvk|b)(KU)@A1lE}cQz&v50dHH9c6G7Dyw&(v)2G+3*nE#CK>?#WN;#ZXc*@Z-E2sS zwc$aDB?5++azS(^^;DBAS#C}Ft^Pl1Z-Kp?eyA>dYQsgITT|va4{WRtY^*=9^j{gU zu&52Emj{@D1gjoNLd!i&6JV3(0Lb0WiRg z9>9$sPXh7LOPvTrB1tIx>^~~U0V>CDp3C6`j+G#OC=LO0SgVLRwxt?4e$GD@6(Yi( zK_h~hya3AAQbM%3dy*SXW-{o;Sdq3c$+>a;FR_WVilD)ud(P(p9g2Pg&P;D-C_@rR zBdSfJN!0jK*_mqqas0Vy*?nO~;pVKc8ggp=q_~3s!gEm!2xSRbFn6CtL(*8*^`WJN zHY{{1k%-WBfkuUZEBMaI&V(33$IaaZg*U8dRFzIhm)JJJHy+@45^%-9xx&|R;1UvN zmWcdQljTVBD`3{mb7sHT;jM(VduChPAafJS)G&_P=qrvs!(?Dcni>>Y$M;(aF~S`@ za`P_$DiH+7`2u#*iRi?)*fN$Hgw@E7EWM{@khsJ!= z=kgG5K)t2^*v>W>T1eBv%J-%M=>}9Ae?1Jw2+EfT^;zV9cb%QV%4KO=ehh>fEKpAJ57IvyL7kK?a zN_2+P)!x#Oj%aX**g^!%iTGE$<{W^C`G*(-AjZ4GExPH5`u`9~03zvPS3L^=BiF({ss*lM z-T9|lSnByRCdm)r0y=n_iVn?wnMvIs#~PjN{L+5VgM-P!!Is)+%lNKdMT$#mG-TUE z5gM*Guh@{zgQ)+$I^r+vi)wekOYFS?+5NR?PU&s0C7rgpwgxG={*({095C>6hj(!D zbHi7os}snRO7Tx0xBSx+x!>2( zBEBb`Ye&erHCPtt|0n)CZpKycOPcce_x6eIJIsV(-Xw~8kyP)KV>KL*AnWfVYA1&0 zOY7}^sc*feTHQVUI|p?-@6~sqblbP4Gm%n>*go|O^}3E(EyBYZ3*~Fz#(Zct!n|AA zTiR@6?)*T3VUP2jOV#=%alX;H_nfC4Y`DeY*@D(}H_XZ)Ub2 z(JXlEvcqxE)L`EkcCy))=`_1M8nBcnPn~;_T|CI`Ger&I5af9CYK!3H4<@Sr62sLv zoE`b9&Yy3ZO&Yilz{@p0lVw*zyMO6w=!rf;r{Vf~8>5r)+0gE86@32w*G|b4tIdpa z!u#)5QF@nV(|AJOT}G$O>3Xj36Bt-GI7(F zAh@mFxo{R^@@hC&IrQR#ro6p3KlO4T=$iIMtcTPUKC37`=;~aS#igL+D+vCNtfqC*Pv94Il?u&Iu)t-+kq><{P zobhm~+?IrWeW{gKH~8t36MItfArqRQ8*HbtHvjIMO=MNg$?o@_>wJH1>Q?>zN=hB0 z9nJIm#`5ve?03VgS`_)17iCTFB44ojOAtwEdy80nz!-%1y4n1$89FTt6Th+`A!vfx za_GOoLftQkt$mFTVVJ7^7TNjuetDGY=_)UcII)jf(@o_B(%3HFNYXw}UQ)pAnN;3V zS+Zam46AuO#MX0XY?@f3o$lJ!MuiKdSmtq|Raly@){_%PPoEk$W?!uK-j+{jW+lHH zbvQ8|?KFjYOOsrF@Lwfg^E3F!uIoXjuaE$9XTzm#Gpk;_eB+?N>flWvcK#Rva$(?( z7tjOp23Ffkz(*iCFanYTBZL=_o&)(P8pub{IamH)EjlMR(2IX)Z&Mzomxd%X zp5`F8W;En_z=35>+cN?UB(jw<0KAX~W^HTe!QFgw-Iw;n1Y|<9cXsb5162h*)M~Y2 z6?7i0BnO8ti+lg&NeSPUD5s;*zar>ZJ~CFz2CR+>?rv{+)0l8)YZuV?E^Ul^F=;G z<&7{0mo#oZ!?>+->(hEP1mC{_=z&@D0$)cPZ=VlsZ_bAXuI@i>n--b}nvw?#Rr$_o zj7h}^@*o8};W`RaY2LN;8jk_}0erS*0vmA;qy8Ys5Cy+8w}L?BVolqG>HLi9i1O?| z@ttrVKb0|ev8sd^KlaYr$@j^2xiFAE(3hV8CEoDP;?X~K%ecbyOPTj`EZ2}v91{(G z0srW*H*tz9@)XJm-}t-b$SZsy9U*lj&)VJh38@tscvzL*M0atI=trGhwaCB^!OUA} z*XwWY{?R_4=KI9s&)jA816IsL{aWJ-+PK=G4Kru7`3>1h_0|V$_K|ok{gkQ=P<+c77`Lzq&#mx?U2ZVZSTQ-^wpajbN{)YW^9F zFV?=b7b=(awNPXcsuM)R^UX|b@y~82I~n4B`yX@w62Y@iNQvbLg=$3VLNC8_GM=;J z&x?4fp0S$-^mNFN&z&oW6*1U=KeBz_5^Ip^aQ2m^=>A~?3VfWkQGIa##$VcTnl&eH zdH8{jxz5>&O6*+@LtxcJqA4;bcK9?5vJMvvov3{xPT`b#y30rXZ?uj;t&EMK*L%QA z8?r>*Pxml7-?jBBlL7yTzvNYsPuh?D8-f&_DPR#>#0Xkr(&ZNpT~XBR zS&McezUR$y^!}+Hc_glwW5n|B z#ea{@(45+Dac-z<+;|OrAb%(+1t}uXZ;j7xz%BMTK&Vcpb4)Gpw&p$A z)xd*38mp1Tv}WROIJ9k4EyNI&+}n|}irv|68z@%!i}mu$R6LMb4hS9JDbSnQ7w#L9 za1VoLHYP=Xeu<{GwYChY9e3^6e%W4ecs}%Xa5L9_XsZ)4de5~jpx4G(kF9#tFjVW| z&;mu)*$@i~DjhX>+4KCsKKvyfic6F4cw*vZOZ%Z*`fC5Daj^cDGW*UBwc1cV-s}^* zBILXmF*=Ai6tY4dj0~y6Mz7HFWUclVyBDB&;lErTXgiMaY4G+|DOZQRIRe^>;P1xsm`vXM0yR|Mmb`U?=`Dz2jsmhyUJH=a;PsGVmZLg94=~WOoZa2|YV;0@AEarlg zte#r;lb4|^5T(w7luIPoI}TSf^OFABtOQcSHM4-jZMuTHI+?Wwcn^+Vcysz#;wEA8 zPm5~EvS`x&&|BvuMC!mze)>}*%V~#1>$1qwPwJCj*`cbN^^tl7Wm@k9@6H{zML9qP z9S>-&&k?1B)l7hEnt5gL{pHufKq#cI_mqCvtw(nCu?@Oimo+6Fc@K5dLV8R-xr$zW z0*wzT;^(e9T&3Y-yE0<#%;tDY0e-O7`Jeq;fpAEj?!!QF&g;rMSWPd$eIUtqLERQuTwU3p&%8UF{=oc9zA@M2!kb( zY^r>u(D7eNNJD7Sepc>!O^p}uvfiPA^P>%COZStNOY3^r;T1RwOM1@@xE8T3`sD(s zfpM_{D(P!L>xx4Ua>)s2k+J&(a<@R^KS{R=&gbeO9O+?L|D`jKN+|Gg_$vS zb$83Y*OHWTluO0OKOQ*sUhn(na!7a63e4Ak^92_Ud`KtNrZv811J#W8UDWueRH=u3b>lDMn(_(V z!5bHVS0m|nsx)|&+h-YjHCC&&>})pkp-sPLr`!;yjOXdb9f+w@UiQA!;U;DkE# zGJ*`5G*8J;GDJjt=5Zd2UjmfaD2BXxsJXQ25%6CZW0s&yx&{B@(8?y)t1Mj$85bTO zQP>shH3GdjvK}}`zL-4k#vJ6p`@}$e8}&f02u$Z~^E_AGa!Mf$+Oa)Up7q1k?#d70 zy5)xkB+Sdtcgi9dw-h31yjrG<|2bIFLk8>xD6zZwQqf-cD8&iSGjh9iXLlc&8Q4DA z0Pg*>7uawx9gtwvTBnsR%+DDtEQcW)zu@i2N2=4k%;nX{>(oP)QU{dch}(;o zDDRu|F&&8DOpbYFMWCk#oV=Ywt6oit*>`A`rDBp{O5rCT)kpg+_RT%) z8fO7>4HycP$nk-@ssK8d@$HYTxju;yIgM<$c>5spz#%ViJ()?oxy05ZQGCvq!plP? zXqypkY1bZoN>__2UnC`gdY=Xlv~_>?>Ss0)CHr*IHT;ssu75P}{3@$fHfemJv(#_F z5Q8Y(H4KrD6V+@qRewykH{iD>Yue2Xoo-Wi`XaaE^M?7TLK1uX=zxQmHO!$k6=ayA zhy4owli$Hdxtub-_eZ1b{0yy(wO==tbI9Q!QuNzSmkjIP z3x!?rSqzbZ&V4c(0f?Cu!Wye+pBKoo>?_n}?~#gD>`L>^y2Hvul`FFSx2#&BWVG}H zJ<_}mYzp)IoykFTi3LG#eaQiGZD5K-f)||;=s3{l6ZST{J>7Nu*xx2;#B+?*PSXD0 zHLE1LFsmV?ftBOk^M!-fB&(g>OvB*ofKL`N8NmOfHn!3#ejYfHz0)81o#%#T8 zN@;9G1&LGm`DMxuf}mL@>}xT_34#<4f&OPVVKH!*eqvcJHd=+i=QWAAw?Aq&ah7MR zH4mh}28uuT7@Yrsh&_LTgtC;bM;?IdK>5w3@O!O00mwRtb{}v>nAOAH1MeQ!Y#Ku0 zn+JjI8(+|qD0}&fGuS*WH^f0Y{s5ePXI9U^h(zTrYrABOp|6XAg_clOd0yO_btR3k z;^kjQmiE#0XZ8XXg_+||B_i&Y#eH?+1z_iH1BDoT){ZQJ5j%__k6A-2D(~u%^0kdn z^m|H_1s(slKS~LaKpdA-599jZ{{nD3e^8)-Kk$-l+_`v=?%YFgx;ne)4dkor@YOox z&%@|u4DOxGGc$29u$zHrL$aIcYHGR1^s-wwUxM;A`!@4o>*V(t!fdCm`u)x;T+%7eIz7(stVSTte3|d8I=K5SE;v4i`#uz_ z!--eVw*}yNzU<%f6p34rEpNJ1ZF(w%_)SP8zF4Z`Fc~ids`;{WY3}C|OE^2Xzoj(H ztwKAu_uWy^hPJyj9aSV@ee^`9^g+#>&aOvFXMX2ZbM`8RYrJ!|R>mpBaeQthg_hOS zMuU%}tkG*|)_ZcIGp?s|jO+Q?cJptp4vzMY=22d|Af4pbP?N7a)ne#wqr*$gZ{l7H z^it&^zQ5V&8cxZ|V1dm#f9 z&e+lC?eFAYYEC}%EdbsD0lX3zWMZtUP)Z-PvsSukU zN$6rM{2b4cwT?W}nUYyw2pp4S4R$z7nYayPT)fs4;$xL=I;e(70)C?IHmc{4x7MF%mgAngoR zu4*+g5BKIfBf!>z1K>qdmED3vK7U3YCT@B}zP$)Ia3ye5chc+%h0tB;F&YxUs~B&-R=jQE$y8j_pVi|Ds{H_+++Be%UR zBf7Y=TpR%Kaf&N}$e9p>71P9Gzml33npl#Mgf>CCqgn#}ddm}6CxabLvKGtb&o36h zc@FFEY+##gbWI5r?)BtO)Qc>Bee5tnCPjb~h)g-R7}=nGEmPK|BDY_jI5R6|;dK7Hvw}WVuV9 zbD9I=iH#Ui@j8Ckkq*oq229l)h#8k+HfO%PphK6YooL(Ii$b!A_1?%fFR zp3FI5P7;Z|JLKwVG@wBz$kSX;Ct9VTqJ1dv)zS)Yx=;lf zvChcC6<>(7{G#c((FkD169UXFn#SC8wFYTDZj`IJk40$_68jYAycYm#;s9%4tkhuESrv(=!F_$|OB z-T)@?=53wA34Ijf?`eB|T27P(nAHM!v%*?%bnK(}etO$C4}FwGEDMk}0=g(W|3;?c z>|$A1-GiDu)T`&f4}Jb2x8Kz#N1tU`H6$NSf+PWnzH?KG(H`_+Q1#dQM~^;oza>`V zf(4HIKd~49eObepUvY@nn?j8L#Bh#2_m*`M-m)I_d6u$yFv86d2e!;}dpu#SkLA8B zvA?YR8aM(YhzS@)F@fLr$pHtg#{kH&z`Qqy0YDBD-I~$aG7?l{5qSB;ESDGSVLj;t>ii$Lm zB3-(4M0yDkJ5@zM0YOkedhd{+(xpg|DnW|$4hf{*4FvV~e?Q%G?x%a+Z#hr)*_oZT zvoo{vY%wt+7+5V;(Gzn|fIRSQg9aAI?dgTz{t>HuJ4L59Q|UCVllj>+K^A^N+tb`#6#%9YEKwG4K(_DM4=DgdS&U?VdW&5G%vY&56zAJTuA!EWt{aJx zzJz`R9HX9u*aM!#q?ccZcc7ZgYqO+uXG>xMgR1}*Rk`V>7_Z`I+Jf}QQQrO_HwbvF z1R!jtej`?+6OD>y=0S|(ez$Q6*b&n#o{N-9eItn@>9`aE^B0V?PT{q%MX z@{(+qpg#_?THCCpg3ANg@?my;aCnF5v(*(Tp(OwqstC#ulpfq_u?EBMrGnvh8;7t| z$Y4W8@u?IQvI5BF=bWcZlz{PTe*s{!eX#2Xi0-Z=vbNE&D}jCKCZNqtZR0F}3CU=w zn9MSd85IPRmji2FQE;o13rwzDD6vp6v5yK8XoJ$%TiqVu>G6_S!HV%+)Te;xO1pG^ zQlEM_g&hRuIR)@AJNrW7kx?m>ThpGrJ zzn*od8s+k#t9nMB4&n_s?p<$lqUzPG1c%*DP$UgB86oP`Vj?EoCsdGI4!iOTEYcVZ zGY(GAc^znp3ZLo0{d9W*cpv~aLILyi^mw=^LFp^oEAqF1^RtJUaX+bGZ2(xC$Rl=# za!c|NHnA3VvV5k!6^Yp62SDBIC@}b=eHz79&ZDw>NzBpnMbuD$0C*~JKHd5xU1LC* zcILcL5s}T8%Dhm(ywGF=P;)Q~Y7PXyY}FjR22Wpq@cF@X6`SF0?w(LxIY~VknE*>- z;;r)zDoQAts5#m5U+Ef$yd>R=uBuWocc&!Vt9ns`D>S&j69X*~?Ur}ip3#=z43^+r z*qN=L?;Jv@vT#RuZZ1CO7}>gd>#2P zC@byMr`GT=+y^4yxkqt)T9i;XnQBQ%IG{>B$|D7VZVPIr>VLGv@VGZtZzwe|Ybs<5g@Z^7ZUiHH{=-pyX6j z|BG3^od5}H5fGYYR0_rVuccixj|xn)!=fbdzQardVHWX{l# zsRN2u|57&7xUu@U*-QV;&5>sHt`5AIZF`=2X286ln*c4C%;2LQFM!$@V!7R_i7m(-_;mE|4pYtjF543 z@ZeT`M+a3hwk08PYoDJFy$tA`PNR1b(6QH-Z-FOiv?p>*{HCLcDT?BN*vqd}v99WV z_Gx~e4lH4FT~|ctQ^XhLj}J%JV)>r12$2W7cEO6441VdcyMo~nudZQTWr(^CDzfjF zZSu}3o^GsO+W*E9Sy7voAUJT@H}xC6t3U4A^&4jG)bh44MjzchqsE+jKIVwrN|+tx zKXa&9_N#{|t56U32cHb?Qm2r`mZ`JPn@^?-&3)Y^`HNd{F(&dQ3D2V&KYNHQ@fEuv zysqz{XR7f_3z7v5INO?af1^=X<#1dU*ux!d-zsr&Xyu!>-SW*xc zu&<9N-=#FL$x3>f^HaJ%9{gf+=p2hSThjw@0a?B6!P1tXUj~lYfDDNzON_S3P9R-s~N>%g*M;sXZ zB`z$+q2!t1b!^6$TWG!@5(ZUc6XWPXEo)2Q7_kjoJ+0^H3b-b~IgG|6X zew^&LSI17tpOleQR8%y5g^nNDnBcd+ZZPW&wH!G@AH zbNW)01Z(iiiO8OrsWp92qxyTO)tEPN`j!7zva?>;&`#(w`#PCgYSs*t$Lh$N*5}B$l;7TlihhP>fC6svU66+C-Nt0}S8&JW!MC|=Y$ILk zwVZll75dzO(8yB}pfw^z110YD*eAFAzly#jnLvd!-9`6iUq^bq#~0}A%Y1qM8i*B~ z5N|E9>MzPGmwRI=lt<~Y5V4O&he0$3mb{+ez_|tYw8Emh?dQ_^+kFW)@-fT?c+*8A zst*EcjWLI9QeSTz50+9$jhgLD>!duKyZ~C?cs-f^b=kuY5+AiF!8-Qf$(dS9Q_Q<-&EJXMGV27b7?P9VrbCmw7|mL+R`swLf= zdIO@bNG6ejMn;AAK}Uy!fI?@#tjc+N*hiSCDfCGU7wpoa9v@#(kB@scrZx|n;J%2& z@JS!NA7F2K1-62fJ%qL8S>2qfm$NxzRp)b>j!3}G@_`k2_Z}uoJ;6#fl8^L%swJnt zsJI*m&jJ7BR2u3jf0XcV44~Y-H&3pZ2f30h&!|4z-rKE*)7l`x5^?O`0W5DoOX5hea4`Y7N*3`l7Dv-mV9#nGJOQFHRdCPU863i#oqKRE7UnCEY}3)R z@)r@E*0qrbBNE`1s%z6kpN}fQmbT%}rp+PZUe3zHddPFXFTVycXtXtuNNe?==;wNk zLOhk<$p<254STQ5wmE4TX+abi&&s5>PBsUC?GB~lgnO4@_@sC;+!94^z`tBMx6f@q zatS(8JG~InQyvuymLUF~O(?u^Ws)s+A?a>ofNJei63)>(?F&PQ*kZkfT;|UfFsLQ2 z?&zA0#p&vc120MYynLTjJK&CV!OeJ(UN7)Z?-+D66$7M-@9h-eel>Z1r(Czy$(R1S z-?9-FCKC_nu<~3O=6-B@iLV0aWyQu`_tlG!?b3ogL<##?C(^x!2OZ@ZEf2HGs#Dye z1Uf(YgQ=9m&MthlybdeDra7VnfBp*0v))wH-GG64xlc&AGelxdx8S)F*ff;J zfxqE3g3|5^_<-W_$iAJAdE??u&qk=IJETw_;9Wl#{{a1Egjji>X=m1*5cYucS|QI~ z+gFMb-nAu%SYTEfbQ1E=vi05@FGC2a_RNra*+EZv1d<~uINGYKMJV_h1#@y*qs6#U z8Y^eWH{gSWg?LjsXM(*>fd~Pt?OQybyADaqJ9t!fET>g;k(l6cs;^rc!IEsDAmWbM8VPDHrgD>u*!q0`P?790iX82|g_LdwL! zzI{ETOqb3EDAkJkXmuhAPsybJh-Ms=RWB$kbvbNAJ?aO3A{^&!8}J>WGzva;3+VE` z-i3G~IIU~78^RWAs3JEtT88t`j6cHg4J!Eho!-cDbb&y2GjRT!!!XrD^Y9D~Iwv>hz0GoZs*E<|!KW^-Kciz|M}ce9tmHqg2_Q6}Lb+al*P0 zyToWCXWgAek=l~V&gq{=TwJ{OvI}bl!OuP+*YniNMxEl4BEC%OzGEsz*mqn9R2(58 zKqVj#J_J((nQ${bplW*O>$k$@|Ns39lvqn}nx$_pS`&qqQ{^+i%ZNHZe&(*J@Ks7lL7Kk4?YH~n+_`{Pb`sm!Rg4FtvF!P>^RKh6&Dh=fnd*}6f6#0E_z=*?+twI;HCgcU;IjM8;AV&Zci`vU+G`EF; z0@Cztg>hHQK}?6nXXSd?>9d`;0pwdEn$rUtAoIf+;A2SP)rmW|l@Y$oaA~M4fK9;o zd!xDD`rWg-8&XMj;D`y1J~ANJw2<7PeN-0^jxnNUgNSOFGPs_490z~yzbjc30a^ij{w0v;(=FLA_ zX@F(YnMs2zmT$zsw?iGUD*`p;BfSFhR5c4kKZd-34Y6I$P{rO|*AXZ3==n^HygUWp zD!a*j25z$HT`p5{yjlG9M3Fdge=x@(uY|+LCGjAFO$YhHbg6osWV=N7rC8CyUMJu& z3hs5y@7coGBmem==}d;an57(X8Z7Y$J1k1Py(c{Q>p}tP&ErknuA;i|d1hxUnD)z| zKB9O~vMOfI)uo-ARaZdd#)1lmt4>`}er72&O8gwj9-x>E+fNr@QvM4Zz3CvG`=6eT zP|na;Sbuj+1lguGB~98WHR1A9$8u55J{tg30}1YzqydXa&uqkp-B;F!K4mT1K&Etz zeS#@vz@BdEi3!rH8sX(I)w7ZkGplU|qh_~9Zj%D_=TO$PtO~fWH@2>A0R@#trTHrP zZVL$4bSdKHGQCv20N0IowYvwY#U{vQ=*R}~cb+l-ISo|(i8adv$T}Az?6{G;_njuZ ztM{}{1voivD%;40FZKuNNm5%t(0DqUln}W{S$ZP@n1qh z1mXoFZ`W=Ms(BMWCcF6k>biV9#uZ$3Ej%e$c{aN>R(5#1E-?#&q7TE%LpSnRR(Vs zar?YF(s$0$s+*SCo?22O+^hOU01guB&NR^X2L=6bJimYRwZQARyMYV72q zgCEFwQU?GNY^e-SW9j zbp;6&@x`}Su`IToJ{b=aj)Z+kAg94d$EbJyH+fKr-VFkZ<&Fh>sE@FWGY2+q4JzAv zVB~0j$DnOWu38a%f_Y%iXYlirhy|n`b&oF{>0%n57 z!S*ur#*0~vfsa4p*#qp(yd+P#t}PiW{?gxs3^)6TRyx#&XlYWB_cO~VS)G^(Q;*}u zX}tS8!85dK`BhN9sg$!g@q{CTv@%NG`x{rLwn=9O2eC!;Rcy}Cbc5LLxysK8IVTl8 zzLZi5H~hD%nn0gbX!g^Nde1kr+B5Oli#A`Ly(Wi_V9N>!+fp71HQ|0nuI78~a67FN z&~8KPlZ>* znkBGvbL;A|&Qr287L_fCg>IMiyEL$O(Lp(j z(TD5PDVRF)#8^jym4D$@y`O`~V)>chH7~|sCAA>2e`1{paeHCs2+pFyz+sBMfx~=7 z3}vMWS}lNmj}cT$s=s@4&%kJ&Z(y=f`Mp)%XH(89{f$&^QH;<)vbm}$-fhbSDKHwb z#(Up!XbbyFo{v*3?v2g_HLf-j3-!TB`#O?gZB)RR#LsG7huSa+{QRcmZ7>?K8()`N z4F;EaMc2Z|dTLvIM9(|@?z;P_id(8D_Zc?4gzR0qc+#*B(tbJ5Q5;LF68q=u4NM+{F-&r@2J>?U9! z_;~KCu-;|8ys8t9dFwEVY-3#p{o#e0uNRa_Y8cPjD6%hVbvNa|_<}|hOdnuuUj7bk z!E?2FiyDZFu#IL>?mXXwCfM;LN<(i)ICk3}Q#B7TU;{D*vr$6@5@NN9g$Q8q!s)8!9_C!J(HA*;Rq(Je(?t-#FUyc{VpNy0c{Jyy{GT^2K=8#bZ=Se?N=mk z4=aD)aO*U<@2uuyG#}K6Rvl6Fe?)m{bSYndxc)PFb%(c(gXcH;E3p3=xeKxo za)Kq~5!stBa;~T$4b0n%QMiI@>g|vn0ewTZk){3sx0yR+7Z9pPS24$b?6|V=qDsFP z;p;GEzsEVeWh5YT(w^4Ff%aB8`&IjalGGw6gB1^*yRkmINKn`=Z^GmtpM_G9n#61B zIpiO5KVtMdjVJ6~dPeqrJdG2kVqyy0wVKlFB-e#5+^R_XgZ&BCb@=M9cX{oUTNwYT zH7R^vE=;6&6|?&TNG~<=VB2KwTgEIb8T5;yh z^FIsQ`~fFHZ0cDTI%-olln~S@ou9XU(3q2+pMfof(CTQniOhM`erok@fPvw{{l2?M zA%XQiTT+qI8oK5$+|4=B_P8IthN=!EPLl1q)%WS35~n`o|BgvQH;>NXS#A%OHIjZ% zIgr54iIOdjb?gY-s@?y~F}M`cEos%!;yuDOHrYUW(ZUrGly+9`{@UqK$*r2TziTRF zUpJ4ezI}8VRyL)@Crce`cMJcbw}axgK-$39c-U%FEfNmNA^a#4nd`u!ZM z>_KPznkCoO-R4UEj?#i#{V)EK0uR`<%rcwxU9ULL11Y3Zb*wnY$h#2KC(vlV^#dsa z#N;d(WuhyyI2w2dG>${7i_TY71A(7y3%(ToXhG1txJzCj&>4kE`2iOm%Izg zeEu#0U(Yx{Vy#t>E~G!Mo>y?E@Td3LQ{FO;+9kJmu5$q z_zjzdfC*5pLODg2n&m|jpjTK+&-4@h91;v&{ihiGJ4CmEqEFFx_)HzhGnOj0mnl;x zgax-e0(A>Lp&CmtU!sYupn`{Up=lNxR^MP!Qc@+I-4@2N5bV0`4pRATfLv#lt5R?o z?RDZ9kpJqD&^ymH@GP$k6eA65Y5j8krd)$i9o#6-Hq^veLWd3<^1tJd^R%{t^61Wq zJMx;_G(s9fN7MpejjsFFVJWrP++OuifXZnIMgE7mCyZZ02XAl86i0@uAYsqv z9=R@m&=>{Hq5cqPQeXIoZO^kKLI(`-DQo@~v6Q*O(wPfppU_1e5K7Hbdvlbs!$cST z5bF-q{@@K*g5tv^nm-H}#iK3!!!h+T0d`N!Y0v(gT)D<(xeyzy!Om1bAo4HJW8|c=M>Z6Iq5}b zInWI@V2t}QI=tTFg3rsR&0oxYDPuZ2{$k%?By3Uw4CO+dhk?W08bn2}NvwB?dyXm6 z@b)l{InH8kAyoaR^f|__<6XT0(#6egvuVnk=eI3p=DvYfrXWlmaN*L@*c`!uPIJPt zwThI^Gjvu5W;lU6=o+H!*UcO>{qaJfr)A_0pC`7K|H$W2rmsE=<#`Kz;8Z!~`N?p& za+Q%>G%Yx4sS>UH8gb8|zVkDa^`DB3y=1P8Gkp zKAEFza@Y)M+WN-DQ1>+yu+rkY1T<3cFh|G~hLET>FN$K)rCZ0$lP3rf; zP$AjVV%zEnFp*>YdJsn1fx&$BAiS;98Pz`u3QDIjS8(%FGwa^FuPyu)_#5Yixj?C! zE4guhoxwDZ^x{hBV37G8ip_?HM%&+E;JX3vqs!sp$5F?Nb7K2@Re5qK;<6}7fARAB z<+c6+$nS^#;;GI3)V*mu@8>!GcgpU;{PhbQ#LA?XLyQ%kH+U#(#wM=c`Th< ziL0svL|*Q|Pd0kL2e5qch0ImS`2=me?yk8ksGz}7xUutHngr|MTR+u%C`o(@4EhND74A86YNh} zq)_{RZlw3Nwxk)pnte`BF1Au*3eJlu&lZalDY z@=QzqhfbjO7Cm&3!u36)?RR&<)M_1OIGke!7XFGdPnNkVjouxe;-<5F7E!pzEc^;*)c`1HO+0=(~WHe1BXx&|oe(X}tN0z5j!~hQln} ztHH^iQup-4Mg6-F(4EJxbYsJo^l5a>%tx9!ZpHK|2l3^vx1H?&2pjYYx0lcAaME|* z<1hB<53_JgYFs{vI&nkWfEFy;oD?nySrVBT|Ncs1;(ILK_YM+vBP4-S0{i05+YY9G zXUk__kDpXCn5E%q%hSCR6T+d0U+ft-W zD6Iy6mkAd(r4#bm$I8b{B)^DnAo1BFx78Fl$d&XaZ#{9-lkwEoi38-=cF4bYEOS0} zmNVt4BGmi&>Z`OJT_l8$*5jQoF#pTK1`~9D+5{`Gt$X;pm7WpgfBZYg26J32g1dSC zJ%F&}#*TB&r2j|mm$?^z*|Z(cM=x-%zg#zb6-;ovF!%4|k{5t=09sp zi}h@?=p-F8k=jb~-#3Ica|7uEYHB*&|NHnDM=qM$mj90cZ2q8U*8jf~Z%NDlC!{zN z;PC}SsjQf(_ZUKWYI^Fi-FZLnIaS;l92&cKXTPFSG0VIog{Q~)oZq@j`SxXKDno_c z05`ww{NM}yO>fSI2r8v4_L3>R^K1jZddtg=B#x9f4|!y^+OG7@Rq-tZ&rn_$>k~m4 z=Xu;ez8#MWT5q-9wdV-(3Q}J`foA|$k0tkpnT#Z^SP)uz=XnjIg9&L)qs@-VV~A&S zv$s(r_{!dZ)5Y5I*_Y4%BQc7cx#)#RZ7Zk;$5Z;{o#uomy&d(xqrYO~dY!5avx4~j z4GNbFdzD||1*0|Uura-7>-T)lVf#D7lYQPxb4P`b<-?CY5E2@w&HH$nlwn@c-C#VO zv@xS1hTQz83o=@8ctXypnsg6nzH;8ll_` z&djM7|1o5sY@HcYCh)77Wx24i4G8M_nDI1&o1WBCP=g>qBA;4o6v; zJ4Y>iwfPtGd%xv`j$=71)dp3W{Szh^EL{H{4bVPx%n{ViKDl}DqgNLM9(7WT5#gaM zH(lb{f2T!}Ej?n;@{Zs|MQ9vyKK!1*Vk0!L*2 zj=W44{Ngejjc;d&42$)NXP6qu>&a$SVUPpvzlipIG_8I{^%;`CBJif4E!>LYn_w6 zQ}ZzgfcYhEHhZlaY8_%@27phz1n#EF1~Z}9^+GWKuYaiR)it`Hp^0%nJu(ix6BN{lq& zhP`)h+f54MFo^#6hl}@Rgoi!JJ93F1p@L;yRX@u-knF2D4H74ZqD3ZqhNRd2I1#gl zg@+fejqQUvajp|e$iJfxGcw?{r&Efy=ThWiT~uk(m@n-+z@hPwZwZ zl`QbHig)Q6Vz_lUtLSkdonGiH`=k74el%BmOV{aee>Se+! zmt$NwUej(Bv&JL^2EuBy4LV~Wvb=8h+~mcElL=}?s(CccM@}&_tamQtaqg3h@LYmL zOqrYg;@rcGVkv zY6f7H)WW6k0X|eqG5_uRBf{;i{Y}UN@`wJr;PY#nL`Ql+p+pa#j~&mU?90vdtFmcn zq93~?geQA?I5@W%CoU~KtWjRYC7%MnKn^}hk*YiUxJ*Jscv2%NlxypjH8o)hN9Uka zj%4Z!i%@po9Fmff(Ym|Fz<^&{y&$#??HUuq`YVTw%URlBP?^FI%3$KSK*n9V^QbB8 z;jJbh)D(DNAax->A^RS^lR%H-z{_J4nl4!SwX$+)q=xoUX#jp8;_-2n>j*vmShOrm3$7+2jU3U<%J zZ~6ZEy|3p4NPBCPwr);>Gv*NpgnUc!u7D1s=olrS&h_v#F`Y^K1~X*nyYqWhyX~mb zElJ^Fz25y|YARq&srhe5Pnsyj>)dX93$08>iQ7Ke-Uz@&9dyEViL7J;XM4){h>L?+={)-BdjE9cSfdaU^!D ziU5=c<^~30Tvj57QUVh()|eyd2JJa%yw|ruc8LlP_jK(ox-TX?>DfJhoJ(pl{Jq^) z<5Cd0{{nR2ON%!C6ckFjyXqR0!MZB{bfJBlS#N=8ye)qpl}!&NWe>oF z+g2Y)V5#@@1OOV=Ql0Ip^MHIHPvAMtTh@F9n5Zq^b-_#>-k$JfaV7u&A*JBj~PN5Si|$nk6?MhAKlj_PC$t9!Z#&}IpQ8v+s- zl5R>PlL30kSB>)G&=>FFq}Z3~N#lcq+ho>^2a7RQ-G9jp0n~>)IP0Dfn23;iWV-EG zI|89{#Hw{eJvdocJwLjBF$d$!)#tamApzx32g;Ex#&qyl2%uJoMSTGSUO*nxv9(;} zX?iH}G$F+f!pzKoXVxwoZ3VBl%4BZ`&~Hfqf#_kUXX8Z}AUaytxd+t2q zxj?b_mQhSp05mO&Ivj(}1>kev3ABn&diLH|r5ypL_p>g}%m$}3WE#WUO_esf_DN1^ zWF`Ng1@2D)9OZjX&~xzU0UUcug8Jx5``$V{qv042aE$lY;zWi59QmBj&(JgAvph9P zw7=cJ-)_>{$B=7G4EUL~cf;SIB*xR-FKJdv5fDg`kaPret75=+7kwyt044oUOxe2l z4*!d|H4xPnyvFe412XijE#v>fo(6wU8{YCoJ_wi-xJk>Mx5oh;GHTv`1GEM{kID`> zr5~DzG3$(^S@$lmY4!AR>#*4ZL3YlzD&jmk+4F-9d=P8X7PkOFZ7I4@1D)n#U7eZN z*xAj9-+SuX|FP`f0Q7Ie(kZa)*!jRwT7=-w+x_gUs{_+|kGh%goTo2e`(MNx!Lnc3 zPnC0vPUaX6F43s+8z|^+gA_A}BcQ1xF6Y5CJ&EaUB9z8Xb->Qn>a^$RF#x-<#A}wG z32(t1OUs*p<)FcGn8c4s1DP-&4WjL!q`iqsv=A+DjRQ?V)5*)=hSYgfMHEZba8@E^ z{*X#ooZ{-(@9o@Gp|J39NxPUF`{Y%4`$AgZ=+U+JZ?H`d{mvu!O$%s_5GUBxIOSFD zLVW;@eCNr+_T1n$>M6!8Eo^@Y=zp`M>w4lv0O?B#OT`#~lv0_2_?)X98@g>zq5(d7 zuv-@c(K0|fWsYT=+!}sXHoC^RfhwKcH@_VdwN(Sl%CeXiYcB(aWn-t=+BjwAA+gP7 z(0A?Ax9#mSO%*6ahETc)-0VD9{dq~xfosEIWy=!3Smtndb` z*x)h%YgqxvS3bsY?>{4rBV4*b=6+0mv15mr|Fui!Z_RO4qAIpcSUOO*42R$(;3et+ zebdRUAT304qF^GF^?6+vQ98t{y|Rh&$X;MOU{FG`k1(x-kR0^WYA%D!d&Q6*gcEkyUFz z3GLk)5D2#i8fq_~4T|)FfGG|-rtbanqP9s~5e?r?fNpA^UdBNhMbpUh*tQj!fDQSL z)7w*=1XG;Mx+zHqu>e|bF@0JI=P7Sk_L*h{Wq^{)3^;uURo>!&lH#4?YZLBecEL3J z^Olo!G1f62j0O#R+l91C-joTw4xdVBzfr_QGnD1rtcw*0h8@E2VSTXDy!+*)b56#Y z9S3O;t^tScm2L86P_-w{LpDmWLCZ4< zmi!MpLebn6w?93i$#e^l>6Vgq2#DVs!gGZTOQ$zr+V1Ypw-w_XunTTH0RS=Z8P^A- zAh(Sy-l4pNCsPwRjo%5@L`PV2(M_6kxC7}}+XoVw$QpVmq2`)l{34>*ptPKZwKAZK zGQp`E&_y`Hj1pl)irTZ#yD;4OO9vA0M6JYfbDH*iphov_UFw10630-U&_h?dSCvXa zZHO;jTvp&hF4bP43&B)(aXr%vtY;nvnj!Y^%L`oD)`>rw12?mxs|m3B{7GZ+aiuQ> zd`-FoPqR2vU{#$npMYnW8yskcVh+ieps$W(rZ|w9P}@OI12)!0!>LH%aP^jeG0x?J zod!yNbybKn6`QxCo_~O_@f~xKILBIg;+HfuoP@q>wxMm39S&|XP z=fSp~{m_>pJtT7`nDu{ulWk=#r+3l@-zfr2M9)LSdToqe_*Tk~ z4$tH6GXoDH;BXCj{xeBSCYyGGJ;1fNkLp1wg3ElB78v`9-M4WQC!4>p&%%y3IEZhH z)Gg6r0pjzw@ApHXVba3_1PemxS`1_y(+?A?A-8@e9giQ}{F(uj;nY#Ei4LCq$T4|Y zxP~mE{2ZfNqH=p8n0-3DZM{m%T7Ek_oybln^gZVTTN4mcY&r3ASXwG3g_~PLM|E&1CDKa(HZ*&hw zZtW%D5;{8P6Q7+(dugB<#%rg%X|)+@LokhY{QpBV&0wIo7jHHjp4j)}<}1aw?5wk~ zcG2cEtuz3tWT2ER1KG>KfZcoQ(>yypp`4JcNJHT`AWq)n!_nXt+yno;#j-d3`gz^i(%|sioJ2;)Xh7kgu&q8ZbdXRW?4fcu%Ah|)gnM%?dUw|AX;BCwfeBnMYc}9ZnwjT!$AM!trjkAOALUPSw-j-6k70 z|9v?Eyv%Be>SVx@utQD%`*H>o12%)n1BEifkS^}ndRMp|oc1smqPwn|B>>hd|C%iZ z3hjJteXGL_`1k`ji#sP?yDplW35-u>48fU$b+!aqN>eb_KfrSn!T-XM6?5Xky$j-_ zK3jYXgzp5K)K0aV2a#1k@~R#VRzCsbc1Of+n-XcThe+SQ77F!XW1aOxx~?SwJd$qy zbwK_gU<}ABGqU^={QuHyeme&62Z3V%v2*)%_p{FGK?{|(O`|oCo8R+kq39d%T%4x9 z7ChIKt$lvmK5+rUa+QCma{^}5$q?4{nV#@ol<%#?L}*3IU=VK!=CrzqO zbD~9VpzihVef*{7F;gv|SGprunxlXg3ld1I;4UdZUMa|rQr}i)vBZSeOY41JmH|Ej zEDu6=AjhHil>6>J;d2|WI5DKi7d<8mX)ho5U(%ZQYUJDMf`h*fnnL|VxenE`OHn_3WI};__LK z(wFTGf1rf@;7v}5U#bpapM<^98p^{hjMYDuhtWYUGDN!RDA@St$9>6v?bg?K@rJ`b z2virSpx#P>Jkp&@vW)xQu1rWB&q&N22-RPMs3_kzx7#$x-|lLq`(H_PTymJ5V#tGZ*Pob zYFI*m=U|vOBS25sHIOhtJj}arbxP0XY&LC*i(nnUy2l6gTVGt%a8iaq$>5kkQDR21 z@!T-O?k1|9xC5r?+#TC{sR~F@sE1-3$y8&?wAJfYvZ^MvWVUX<%w!L3yZvm5?;GnG$GV!FaJ2a7QL3e(N?9Qn%7hv%?*JoM4KE}Dv>EjAg~MPg2M=A*T_Mn6?FN+>X$M~ zMpR$De+3t?$L(amKl%*%yCV7pHh1KV*Z9Nh49?vtI+2c8lEIMg^s8+nK~osac? zlPeF<5MW3kSEUEV+6eV2t@6d183%w-YEMJ+*-Z3bY1TW9YyroW*fr19EA-Z~XSq)s zROk0dfGwcSXZ6syHzJ3BEa^MT*bXY9F5hS4RKfR4#DK<#)eOeNOh`vC~GXiNpiQ*@5a;3Ftf09Z)@%@h~V)NvuYAnasH zE|)#n;NgcLHs4ySLL)P7K-_`FbYDHs8OkvB==Zls1M*x|D7q4u{+#1^m=(YRfgxt` z;-k&LU4k=1WMkrk4AXQ%q3OW4%dibPcz}I<>am^9^g3AndYv5quLVkFb}jTrQHdItRQ+A%nK} z{2y=9wGpoKB_9P%JJ?-h=F@+2RXhi@eE!bgm!s6znR(u;>VbcK3#NFrv)I_<1$Ddo zAv{ zu~r$>qvI=p=DS-;($+WVFiEhK?6Oqx#V6W^n)Ne>YpNZdD4xz;t%VNd_Wm5)EP}kU z-$h1{t*5IKgx*rSH8ObhhQm)(A)dgpmwF3?s>OaVV=a_4tjT9hWLnLukG-M44XzVI z`#IJ>&l(Myj2{utr31RUb8=r_3f#n~iMx_me>!8Kdiu+hY2Q9~SvoTqB&WAc9ZPkp zk>{atK_G%~O%?*e?K4(+eEJjajQb^=hfDVU$F8U@3iG|3XWm(7ET~7oxg>yc^-b~5xxLntEIW|Gf|{s4~tHC41M0?KucVgBYCboA{uCOp|Wt zX<)XTcl;C?;EH)vhqCqMe3eCZ!D|;^d}aLpk>e%d@K4L!zR^x&!}~y@1*uFg6CdwO zFsjnw=uHIzp>d|dU3PJdVf}NJkKnE+D^CLR1=3SRU*FIi7P3+6QFAelqIN>-hc=ZJ z$GJH|8IFPgl`P}$dFXTagR#_=Q8wP{FG+z8PD(~M{fjTgO4YpZWosDCBq|Y~SPc#~ zzs;hyFyRA+viC_#YZ>2}%8Tr_hCsk75b2mixQW+L^p}K!8g?J$)nDt;bDC`oKdJ+e zXMZclBuAkJ!PX5ZcLow36K`Mt=4U2U9AtkqDr=(Tv*9LzGOcXYGGFRF>OT&>1z(+L z_OP8{f-zci(bej^enfTFdoiC4U z1yi&N?TCVfz)d2mBVB#02`pc}*+#uV|0<1|V`YOBF^;)<8(-Ogwl&*js8J8ZwpWL( z#*GYGKke<#yam1;$*|sCeC3Wb(^&14%1sI2m&TWIDUHQ*ZwS{5q@{FFggLfF| z%E`;l+3jDJjtsnSc|F_!)#YxmSl4UXsc^FD-dZ0usD*4~tjv!)R6uGP)3rViJpzh8l6DTgDta}V*hHBN`Mt+(9GzK6*uKjIr;@BO;X!xmG}`vU$5;(Y@qZ}qxIAJeRL z2N8KG5ZzDTRJM4!z-_djWj+w<1Jv1fy12;chOn%yywzEyqkYtbQHq08$sh#K4>-f?e=KW|UCnk@-GK8wEERCi~a9ek%0i#Smt4ydsz|F}Ky*%A2voJ(x%(hKy?lYz-FVo)hZV zt2`Ulf9g)_Qm>g}MKoJoJtZe9LnzhZq`3=$XeJQBV)F73%Y6ABSjWB9BDW(<>Yn^?>3z?#G<9P=h_^o4-O|^m zjv{~;{(a~eCvutC;B|#Mam-R>2UHpeNAQG?8zStom{iP)|hqw zdi+m@G5Y0DUX}()#H1|c=a7b_U-5;&ve4e%G1+BHqYlA4JQKhM5Y_!D#uy`ar<)z?g~~ zI^;xW@M%;Cq(C#^TGY+Qz#C|#w?;(BE}*@+vsdaLj8kJ%;5&ijy#cVQVp`aZcHEBv zDKyxx-v$SORBgp3s6SQ@0oSwBUTQl7vlX;p1VKLzr|gg0G1|@XU|z`oo%a7F5yA&% zc8;n$Q=4XP$NU&h9TFA_9XvvZFdF6v2dTPLSC%{f9U$U@6Hj+2y-J55{{Cq}ym;o{ z$~kB{cSPtFrx$^+6D}z@VL?nU+uymV>FLu4%2Xia2K1YuATK`)6(AB+CyP2JF@Ubm zc1)0Q{m@Puyjwl&;h{fBQU5hT`pNh4ewttPk&3%w1tG8d6R~Gw6v7v_!&RH}bV)5n z`l!aLTRoUquR1ICWW9KaWt0}r+5(gYw8HeFJ(MUXJi#jXZN}9DLLI6D z8~EaJ*TpDFVRk8|j{;HEf-rfO`Q?@u+p+jfgjNqOI{V(X-8-{?v1fpuWq!>^>0d42 zV{hP#V`+Y$Q2qXkr?);GqRLU0Vl~8)g^LK=E;67J5#;Pdas1JT$iIBTr)_sb5YR9E z^nyOaXe2J1l(ug>^0GNpjzQGATKtLk^nrcjtZtB@nuIU9FhU z-OhY(5-x*LG@3s_i_BaZeBvRY`;5wfAzCQZBjOp0WfZJ|W6GGfI?$Q*=Bs~{1{{R* z8#?b%_)fGMSi^9}DB#%!tdRJZ_zF6Uyv<3A0UpKMx%^GuL~&jvpNUzjnZ?1Pe)f>$ z4-I36o$LHxCl5u&CqyA)Ddjrid7B*~wxM{iUrj?ff=02AJ!d^3>FbJgsFB~ZTK&;( zgfd2a^t>xfemf;W6%{iLB$Tl1JcCdgRl-&lDBU_ddg^LYmu3xX73S`_+QQ=iUGpD?#G56xfra4{e_o>YKWIpxG^4T*ck5bi z|1!0SlW%!#(0yY#DiEO%CIg*M&>`P_H)usD2yvb_@8;SLt^!+l2uW0+6!XHOwa8^o z8zpPwzUBMwUus{uDJ#1$j7YOVs`ro^G70hC9no2SA(ThF68G)y^!>GRZ@C&0#)aaR zeuOM95oE21_v;$fWUns~*w!@}!EwVzgK*7vS=~iE+i1f{!Q(droVggl;dPKfgm$RWuHZgFD z|MR{aqiDgovunglb)6@|GCrLyx+S*QZb+8CB6v*iV`jxIoww$8TXVck zEsxT-bI^cCQjkU~u}YY7GEqZcqh(PIcRp8I)I}%1uO=&y@_cr=@{xy|1Vo8BQg*TQ z%qVb=tcZ67&E&^Y|IV=ksepuT_>PSz@Y>k;fqTa%9H6>v>p6|47!>ECQ0$xQ#|qeZ zR1^JzZ8lPcg@#U(Pq2JlzAXHY>26^XEsS<>Zwtx6oNoO#PO$7{2s!NHaj(0!1WLRY zc~%(qRtP7s^7JrB?&2&x`->cNkB$_?h#EE?Ymq#l#ZpjSbI5)m}<$ zh*Fm+>i=o$N`soZqA&zT3beyWMl-20P?x$;K|{sSKwjx+si6Wxtr!D>B@|^fffx!T zF?7(eAg&M)Sz5*w8!1o-o9~UShy)T!krWb=v|&>M2`*X8^7<%*hSc}#{W$l|S-yME zx$ir3pPTi=_o9Ff6&1c+RqPNaC9|o0lY*Ne0+R91*S{g_%4Rf`WUkrT^JU$G0=H@^+Y5|QPkD}@ zw9E_k0jlCyEz8P7WYRV0Y|BTr>Lbt&C)Thpx+4f+<%zMXKf)!IrmAq@Eb(h?H4dON$%UyNea?!_O%)M-j!*0c6njswPeGQbU?Ufur zZ6wQ2fPXz$nNE5;)N%_kup-``@hX_zsZY>!@J2$5^fuWxPce%>e{^yt(o4jU8fq4kX`72!UmW z&b(B(>8ELv9Rks-^x%E2| zr}7HBIhw`yC#><%lMlFcJ;hFry_my-7pWV5wXHFc1)S`;ne+=~NJ%`ijnrKFcc5jZ zIU!_BX&hgpi>sXbGhtLTe=@a+XFP?2G^;W;_H#43?$he_C`5%DRn-*&%r{cHC1r4C%5Aq4IBYRhmGn_lwoRk=} zUfDZ3J830T7sej0gN&I?@*e*75Q{P;nC9ey)^LwU<-_M%jkP#oPj*&U3q|^YUA*hu zV=A}E%IAuU!f<{EE`kIA>2iBV@9wiLmuuPw1viSE0%j|y)x)9}xviGLqAN%mwF!S& z14JiDzrt4c@bdx*fkp$zSx4(!Zq2-S{80t$==+|dM^f)2R|n+Tzb||*@6-7Fe*iDP B>JR_` literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_speed_limit.png b/selfdrive/assets/offroad/icon_speed_limit.png new file mode 100644 index 0000000000000000000000000000000000000000..0aa7038f909985af264c1c4451bf9c143d724c03 GIT binary patch literal 3321 zcmV8>qID=q<{c#LCjVw zv6$=?^hc7id64oo&?T;rofZmQ35mPRPTQy`avZW0caX%SVs)#c-A%Sh0v&flawU1# zJBK!&SAoXi@!wFqBTHT1`rCe(_^#E8sK+RGEadjPIr10yfBV6QQJ14CkRNN!@u;BRPtsRehx zuu(n~$3YMlr#%pTYw&M~iXARJaC9s*#2-K;bqu}U0EK`*z#b%4odg~n$lhf!{Q7!g zG1so=?CRsa7Curn*-DH6Sq@{ufb-#8x3Wn^to*Jpv>S zd0ic6p_N4GG>E^WViBm|q_uWVe#YYg<-X0v%{wB)sXn47GTVT(rzj@ha@G>srH*5q zA}7c>4s<=SIhL^2@@g%nwu;jpS33?#>;&`$<$`=wt%KBN6px%5QujPZAu!M9aKyeA z#pNImIiA`izNpGBUVL30bVkT6uGTw>E1v@)7AD0D(Aegn#*=-o*z&sWBta-Alrp{Bbz^X#)ujticx&{wuz;}h?Uf^t* zI)2Lnpj!5aqL*_>a=J;bnad3tgU8mkq07a4WjV;&Vne{}Qd5QG{7i0$uVvOHsEHOa zAJ2A@34)zug`xGU)bR=r$Z#}5;QdPKY5cv>si?oL*4NMmfeTRcL)7F&m#Svt7|W=Q zk{JicCmr6;q=mHzs86a4MI&T|YSXEk>d_AP7aw=_QNcc)b~6_@^RHZhpD?G?x_-(N z0;pQ<7`Q~{AZ7#QtCdkO_eMTT++0J7vlm zA&Opih3Dr0J2-&M^s8^wj3Pik{@U02^&XxKu(}lyn;YVrPGmrE+#7hRhkxw<2ES@L zxk0Vs3!FXvAlk{$4uCIrc55ZmUm*FG4Xl4vKP0?b{hQRwx4N3l)~MEDZ#=PK)1GUi z!@gE=^Osx87*5tef}Be`-yGU$%WYuRF@uQigM$tZ`~m1s(3??RbQhpEq9>u-SU*Fz zklcr+Qk*$}7o^}0Uk{cu1|A?q^9#g{!GXKAfE^@!M6W@@xK|5nJvcCjw&0X{7}Zy6 zay7>5=44teXq%T0KWYFgWD2X0;c)(5z(l)UVAeI9)v6`7G5TlACGGYeJCF_0qY0VZ zqjMz0tKD+}3VE%TZ&yB%y>s~17zB4FB#T-LNP<5RZGA`~ukGnnw(a7s^Hk<8FSpfz z2^es%nvP6 zctcx0{s3%|fVW8dB0mK^A&n2~!?n=&S>yrqoCC&>XQ9gFM|BLY>^Nm^mmOdN+8_r4 zQ-8(S)c|StME`@DT#Avt56aP1F|ZF=q3i~b;6V=1diH?x1N3F7eRiXxOn{>4zOVry z`A-MgYk#)}fpLe#I)g}=(^< ztu9NpqpA0q4IzKD!+Z0xQ9dxQ(&%|?Y<*(Shxi(qyh6Jc;;qMA=VicsOub{C;rz-} zrx><)xTr9QIt*6FtjT$GLWV^{yI+*dIN<&furG!B-S8hkuL}O=A+Kg~h9U|%tju_| zOu(<*E{rM*jw94fyndL${`^d{3gC8W8YsWjl$GvwOmV- zltZR^eO@EF*7%NrnqRp(nXjQAc92#R>^v0($!?OT$K6P7?5(2;NgGvYXJ%_i9-IIh zZ;!Ku6A04ZmA=nbDi6fAMWHRNpKUGfNWy1ZYqpy4XSBL*zYha=w@^-g?d;BnoVM}7 zv%2H**R?9#R$J#l=AKonS*$@r8gQqp85?hQ{g~~B3Y~GaWI;m)A>F+u9yg93n933S zY~bRK0>^!E779Rn|Ia(%_p?BPV00baAJrMXatZgQh%*5nKy%`EVReGd&w#dkQ%q9Z zhh$Q6J0qGazi>|HZdx1Xn=02bf$5~lA9~`b)lQL4`Sa0#qZ1We{GR0XJn?mTvHF=#N6lSKGM5m$kPiU~~mj>7-)hlU@pMd(?3DqOn4QRA}!tavb z0?;G>z!JSWfn;MC;vZJ$DWBrE7!O;DI^A8bL8FPZeA3>Fe=>S89Iqw0$c0xAt?4hX zrc-xg1k5dD8Lv>UvrW9;{k@7y!(+2uG4 z!rjq9t|fXR-C&?jmI9bDXe;0vbPzdqBtxOc(^`7ftLQyYJtgOUVsqd~1~CK)q4-v&WRTelBox&UTsa;kW#*=%$V?(}vpm9)jq*Z3x zGy9TJtEZBM8IINo1h1{@9Z{{<)<>fyRNwyl;^5bjS(5Me;-Oj#(9(@yZZDDq1YhYI zs0rK;?fNw;kXr7*YMgdSmjkTYGG`g27)cl}XS4DJT9csmGpMv_*1QxpN3||gn zBrg`lgO+xM=GkY+wiIfu_A;82+1a82gAh+aOLsIKf!SpYaXo6yMsw1AMD!RZ#E0j| zL#%$K*PsHR)21ZvX%q|?fOtK0QK^HL`2FN|x9+fioWbs5`C(f)*Ua!*=qu3@BI%^` z`!Kz(nGVDBfY*;r?&LY|%A~%_Jp+J$&weW$x&i1N`h2wXXtf!+Yr)+PemnFSZ0*0z zLQS;&KhTi}hc*v1;r_**-n~vmQz^|&wGKNIvOz=-%Dn|*|6>~UbCQZ_x0TaV4hl6N zP4M}5vxU)7`=_M7%e}hoh7-3dq)S4 zj{K_vW?F*1EAhKr{jTCHG(F;`5L+!%obK2xfiU>PTBd!gCCK3{xVO*nYrClua;KuD zrO+khs#A*g5HyvK8PBjSgt|GtloAL3v?4EnwF^ZGf4NvVKmwk_c5NVBU$| zovHs~S8bm>y!&RjE!2Mf1a*ZWllC!ue-Z67mMjLI$!L1L^WEKpqiuctrd>-EZ6@U8 zQG&S(dA8rKAY3=*Iw5vvSFJA8y33WMe(%~z)B`{#TAN*fmL{e&4ozrwz1O4LECjyK zmO3MTh>AL&`v9H}?)YpEV`DS9m|s@NO(;yi`r+E1=+@{asBUDBpbOBs^!qsN$c27) zg!E=KH#hqC^Zg(3AZvTAci6~Bznlp9oI9f>d7MOPZJ8f21$uVV19eGGOe+DdgzDF< zXQ11q`DN`h2K~@b8?oO&>o;jO4r1wAkWek!Q(VWe1GNuyL=gg z*b>#@+a_;_2}?f#1MV|{T6lM^B~$L+KID49F3Fa?iIy>t0qd#2|7S@4Gn~E5hC{Ch zqq?r?8mNo!()oeQh(8hI)GwRnp?XKGwOeiplI`{XgyZ;oml__l00000NkvXXu0mjf D0wQgt literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/icon_user.png b/selfdrive/assets/offroad/icon_user.png new file mode 100644 index 0000000000000000000000000000000000000000..9b653cc4b3f620c507d041502df189f37896b4ce GIT binary patch literal 15798 zcmX9_WmH>D*A1@0B{-AAcQ5Yl_T_oMAIV+o zX04l;lbF|4FxDb{)Pc#7BR`O&pG z)**TH9Aa@ero6((kiY+y1-v`Yr$cdt*7df5n=o4D`(N-K$TBUs1Emv%UUByN?Ur ztt6Z*H=q5?&R+kmRjGS&b$R)Nk-O5c!)Kb5+tz8U8g`S_zl%t_@P|x8ON&?Ll-BB( zomR8Kgq!7NN29`{vb?-^Q=WRwUtVlq9&e2NZf3QOR-6YZwx@4Z0UP zUMc({?Gij_;M8wFbgEgrS=2el3$y#lBI0NW|BIrveS5v@I-9IAXzM@<5^_JBIbg-P zPTFjqdpo%^!KnG%t@ELVWu@Kw3I%@jX(XN1_w2B|+VFn;?bS0D9fds|liH*3%gP>D z6#hWXP^>oj#hN-Ngia)9oSR#4O4+EA?}EbMc5<#Xgj4#Q27H3a1nyQ-d4oH8a7YFinAGkYBQ zr@F;KszAS~rAE8Ae4L#&d&!>DL!je1YV|n_Nei_o{hU=<*{y2fy+@A-2FV>JmH+i5 zhy=<-GWuhcMAPC)SfGy|B6I$J2#oSo4ilFc$19Rg4tUyj)@jJBUDa+#D`=#}W2T%= zWge`M1cby4qi5^@-qC0fK}04lIk@DcKfQ%w3*D=lm~2i%e&v}1OVFRIP)TT*&52Sd zAPt?Ubz`dOvedXZHxbxWYtON4o%i8VwnAm_QYUGW<`Kt9xyM1BGFa4$SW(Vf1C2~z zaElmCuS@lu8WN{?#1LM_F5oN05IeRgxq_XR<4lPvYv=Rj$odXold5NkVDX(93iWRx znXsCF@F7^HtMrOLxE`Oc#@QB{9F`$(^vNTWX#j}S+z|O9^A6tuE&wGbC#_Dk=y~2K z&_9*FcFj5MTN}0!JnVOQVz()h3(laNeDXqB_+2`C%Dh+DPM)?}ZFR?vbcFwn=RpVO z7WBa!3#I9;Sc&}$w$5g0D>#LFr|i%z#@f=x@JqWJ;?`R93ba&UdmXGsZaA6$ZM)A+N={K1zpK7NAORC{5WZ60|^ zTo5uU-xBxJ-I>wbL2-6xmG{-I)sd@KvXqThAj1@8)ESrAb5?JRW~)*4)6HSdmx;aj zCFf>?_2shJN_*A1dMx3$BqCj`mJc5p>aF(B6ubL}fhu)(THZu)Vzo*2B#H zRH3~83HZ3>tnzfnp|4hsV5uXO?>p5;2P=@Pcv(r7m{PmV&xz@MY9?mL@=W%`bdA`H86YtwaD{LxonNB_ZI7ALz zu^5|D;9fgB;IY&lTDfill-5163Q@MpWf~Fy|5d~)Z-!8UsL0#Nhng691*d7JNM+DF?G**^adcG8CWsw-^Oj1bsL`i29-&*)Md!|MeOBJ)?l#UYk5{ya z$dW`xKL~&&@80TmFm)Y4_T}UD5N#rPZhh_Nfn<)U{T2L3N}v5tx=AfcX*s#W;Ez+R zsOt1`<$AZk#8@1CD9lg6j+=@mrm6~gNkHlMOVK_WxM zJVk%6hTcn5gEku-9<>k!XVjebO@%%VIp^b694B8{TEK6Dhk~8S!`bq#j+fiz;zPuq zdW~ZIv;;NMsz2xK{GncW2#jw3JTh=!$HwdPvkYGN5?-gudH_nghN4&n24Utv_-vsMEoWGB7@=id@*QLR(Bvx zUiwF7bWP46)jAxN7RN&qA?))9(Ly-H#R(Kqts%@snm+u&I1*Q#)((`W{JH~T6Zr*# zrnEHkoRa({-bq{NRagi`?z_#%QBQ%p6<6hQgy?S{wQO4OYF$0)B3Nn3>tp(kNO9nPxJ-xNs85r7m}cs_avE+jsqTFR5<*;cPmmqxcHT_n#Y6} z9K1Y9B^RA`(zMqqTn3pYdns~e^r9z%OthuU^?P;!G{NtaU^5RNO`?EEq{GhqgpR|q z@-IsBLxenGtfl&5M)nwFBcv}RU{vMHxAREh4%Q zGxI)RCJvaA)h?{8wI~yld3q-S9PkEhTDj`;?P?)07A zuB;b$yW%?TLB?Y*GZKshJHc-4mL^=&p%w%?)O7#;{gvCLb1_K?OGeC4LNiFp^-lcT zDm@^cmLPfyJA_W{Hv8d)x8oE|^q881@tTMpq!Q5IiSRXy&4wsH1ZSO}HuRmzo-Bik zA(P%WVDDOrIW=INhGnG#it#nWyzd&f9`h>^<~C|J+1p-Tu>5b~Ib ze~FHM(}_`AEyagOHVuJvXkE<{v6O!DxgQEobI?S^mkJ!k(RP&#$!b3QD#0P_o8_6Y z9rJG#w{!UDbT6d6W8^li$h%r}IRK7VIjo+MjGjOvw#(uq$dC<&C3qid+Boz(WxqIQ zj%S(P`s8EIw@{SMLC1Rsf}nqwVlPSDkh8onEGcmOWUPRrxHQdjx30b74z~uxU%e}J zSf0KtoUxIZyn0A`&asnL^xm@#rp`&$=enRc`g6bLpzs4!uLZDn`S`*_U zB^3YQ`rwF`dom zwZ}2wDl@Us)hYIJIoDji_IKn48@@nq<^e?xg1JZtaW0|b7En>fv| zb*EvXM~D_uwKm+)&^4u;H{meB=0x7)6!)}L3R$l`-FNp67&fie)){1+yg16A5skj^ z(A7^B$?^*})X|I@HBLgS^j|H4;gFfv^GV$`r?$1hj*`4fIPjs<-$y$UI3&?sPVve&14tDqdsc1SFXad1~di<8bC=Xd^F9A1bh2e|ZN)pOlH z%5-ERj2eNl^>)dQp^QbOX9(Zy5QNT}%ABe|8V#4X#yzh;Eo#^BffyuI4hBIVJGb>p z@;zSZu;JetCK_fk5TkdEakFK9#OK%7G+`EJPmm;j?nc+z^8jQ%>pg`)am>PfS9YVh7+eN59W^Q&*%} zSEUFBP!UaU^E)gx1eOV4WMdM(|LgWA}0R??)AAcZ(S!b;Cy`{JdAJGnG17JToIxzb#t)Qsq)1ol^c z%gqlqe7(R1lUnb)CmG(gwKP0h{mT$5e-}TcpVw-^H|o|C{C9$aPXIAXuGuJ(j>`M* zo93suBohX&n+7i+XaIcaUS#hJr0t|a4uv!+!Z7_yBlMF34303swzzcmHAm%k$U7s> zb_8xeeH`Ss(%n*5H?}l$JV85M%s-P+!LWtlcZ>RfE#AEUQBz3%Nsxze`TdHe0dbR@ zpcoyZ{4;9)*iKWRo^HRNK$~O%M2hjGyde^AYbGvDT_~aD$`DEmRWmQK?9sMG{!^ZS@J#WxKoK_ zOPzCheSR1(jhmE10lRD4mTnKkxBg5_x6SXh10)i!Xb{iszUr5W>A@J?TULxzseHqO$#u2KC$G*%iVAweG>?PdFnp`N7k=pwiEu3+nDK;m7vXV zFB9$3_w`|qO7+uR^?u${Ln2Fw!Z(Es)W+Pu4Xe^e0drwJz6;&~u*m!ti{dGW+g_Nd z@axaZJ`n}V3-I7|lHEM0vMg?*U1~+odT)l(#4A>_T#Im@Q1`eTl-FPtNAgHGw>amp zgw`1v5MISfC^m*E?tL(%9%NYkkPi2ccABy!OhJ>%O;Ca#pgfaYI^sV9uh(yB=I47u znj>(^YUq2?xc*Sp4okwC-?dAB;>sx?*6z|xzo6T#hTzCmW08@;uiK2N$xELP5vf^} z^@vu@P2`!m#s8JIChM6sL6xBJ>vcUd?E9Wmcu=A}t>v|Nefr%Wwgq+>9mPt5<+9Sg ziQVNBJbDEhaPyS6 z^D~+B?Oc+A1GNzm1|%vOVD+3zrSWl7IhDqBV8!gb)X%n?Hg~zBG#(}gRVFp21UiE$ zxdGlvTUPJbO&`y}oQ65-u-@y#ro&oUbyA8e(D{!qkdFTieDcL-u~%d956`MEtv%7Q zW<*d39AMgU%A%#x(id1hCR^Cgbke*e@D^k%T}YB^+*FtQHJ1-xPW>Xdyx1|g*}C{u zdB9Lp<;SR+Uz0&!GiJE7iE&>Zu3N%sZE&Ak(sC%{Wy|!qMO%FuFRjTw!RqN>#(ids z6reiKbkwM5%fBo+h0S34;W>|kDT|7jbt4<>LIq|FS-`-@bx2-lf1Y-yI!?y7Y+KgZ ztbetQUx8oD%ix%3>}HG0r(PGr?9H->EzL5F+ZJjr9gECOTEEB_8{|gFrGz;BtEm4= z8p-@YFmwACR8Js}Q?_feniuS#wp7+&Fsxtsg;UJA^Tu{VT?3)o&nk?zSfvB?GElF{ z-i8^CrNOB)xk+!Dldn0+7J(<&;l2W?DHh1AoQG?_blle4Z;Yuhz%^I&QYBV1zbNY- zr6n(FmMUE9YemNwMxrBL?P3sfRT-Jpr+fRao?C&wdXUohxcJ|=lr01e3p4d{Qjljt z#|Eb`?Q!0T0xt3BMoM9Sf409o)r6n} z$)&V(KIvwfk<#$tmcE;Sa|**` zLMc?S;l=j$*C+~?sL3)I_29s3V9OEYI0#u-U682cy^*4O*r9w>q*r+cWa`K^+n~XE z(zBISW2u6muoGzml{C!bWQn5UNlv!m7au`o^Y?t*pmhar%|W`Xh3#r-S@Lt(knp^ zcBW2ghq0)0^DF&^0u>c*-Eb(F1df)}`-0OOP94ZiswLvflwZfrS1?RQ78)R-j`rmK zXMa3(x;J7)KTcK~b>+LC#W&O+D|T#c$Xm#uN{)zNn9!=Wj)8kTC#bFSN)we(B)rnn zml|yP+TjH9j?{qf$40k4)gWDwlGPH%tFfNzU@u;)LLI;5s~5tB@)?tR^I6tcMcja% zZln^0U+-Bgc6~7ZK})b&HylUH-E(V}&0>_1vrOQOP|CVH6R$Q;vQlr?Df2xJGbW7f*U%|aHj4$Nm-atnNZ zW>3ycW7OV6VfZnkk%L_ao4Z+_Yu>6)1!%d}X#08+{dyqJIreQEGi4yH&*pt0%r{`5dnNcID@=$(1M)HM!(5 zHl|&G7Qtvb|Mz4}HEabw{Y|ybJL-qsp%|E9rV*-F$Mxfs1vhkSh=pe7drX01V1$Tx z3CSM45?#16xHoRQxtS6}O0(6pU)v;$`9Tz)%MTRy7*WTAg5v?0y{C#CWO6jiQ~@y# zW?Md{{`&U`SEulyMi`j3x@jB$Mc&U!Ps7 zh=~iYlQAvo3lST%3B;;A~tUv?oujRsXny z-WQ}QZuK(bFjWxU{M!GOPJV5UNwYm1HdEF(F|9dMjp?JQ&*B<%GTk`{qD=p4!_684&8==FwZi&vD;l#HSD!+KQCfHBNm{!^)3HreJsPnd@ zoQZk7R~FcGmyPJN|0)w!-6HFRtR>eqJJfv*oNPmI%M-;K|yM;~v` z)m&KcvxHs}zQ7^(IqtHWzQwOe>glM8rBP>TL@DJd>~fdv5uMQXq_-z)E#GQbeqaxg zni69~keaxdD^pY14sZBmJ_e&{p28u03+F`0n4pCB2bJ|<{+b~T75vb4Q(9z9d#fWD zGk*13tgNv!6~Ep+DENd7%LBa--k8g7uA;3vxTu4Yrc&ktD_sTX(+M)Ry&648c+m~y8##M#1=8k zq9fSp(!cY59cn$pNI$>I_R;eV;W7ydgzAe?&T*E@&%?GHnJ6GSfe81HUY|R(s|^8t z7^P;~_b|GL0L=MM96?GWT)6`iwCpZ24`CCFa-t^%=@h;a#PV_QO~)GKYh1M$YLw42EOU?5#`URVMjOaHYPxF933Fcc^SxF z?1TEu)?DLVL>Sf;PUig*We~8`Gt|JZ_r@sf7F%&YhfA87i1W02-3-<6?oGBoC#tc_ z0qQp;e0lg2iJA8^Qp%I4JYauNAYzz0W;TIWcSfg4a(xJ+-+m2P_>TdDl)bE+bLx-0 z4K(bIV*e{DCMb?6<2=^wb>bU3Qb*-T^t(P7Y(f)1h<=PV)dbdv=1XSze-KSvY$ucJ z7ewv_kaJ(tHF@~Z0Fm(Iet+RR%*hE5weDd&wpA6reis#G32|8BvP=eoROf(rEO1yI z3@ghUGNZe!sd*Jyf)Tg#bwcYHj1dNfar(wy!@PeKtdnIxBRmuVqcIzDvP*$RIr$gz zSNp2F#7>BY;-R!Z<#%DL*Of9z?bQ~14*ojJw$?MPvRkfNQIg1K zvxp%*#m;UjesE4@0eL~ZeXq~XaS%>!48jUgfkLo@axI1wJiKVKgwfgShRvw`u0VP> zx4DwKHf>X}?C;Wt<=HwA_g4wg&a;3Us6iJu^G3c1Qlq;UAY*FkCu5n?qQVyYm2)v8 zzYC-zr#jJ%4_(NZx>Kwe#2+f$48>gmWYuk_t@E48!zX4E6rg=Z>-O!78df%f`iGCm zsW$D2qHsOJ4TN)K>@yFRiM(+w(RF!pTFUL@l?OzMDnewlP}Hocf-A zI^nG{X}4P*x(OE>)%q+TN%eEey|MjkdY`p%(ylVPy9J_FM~EN%iEPTaMkZ)Km@QzyaBPTF#P~Uz0%1aCrFqnf(a%$|RFbfVM zXHv{5oJ=p`wGG^7{l5ao>(Z}#f4!k^tVhAYlE6@ULi6wnOr7rrn+)BCn^zSs`n_Y1 zG254=f6EHUH?sz9LXeMJr|;g~1CYMYqXy+F-pji!4P)R|*!?bh?^vr-ebr%P)KnjO z5doku9NTasvx!+w@>tX1`sxyH#$zOg49m`e*46dAiMc!N?q-b%oT(7vgJFOUh&{wf zE*m58<;ZBA79qcIjPD0bI~s+_MUYm@?jat>O=$ZMLm%~J|0HOK*_E?XOE>kIDSejtJ#o30gF>r{F9Mszy znn6<;-zIVij!l}irI)QW(99;@@)fF1G}O8N0YMy@y#6Q<4rA)14Jy9+!Q}(cp;=8B zMFfkgQd1Hd^oEp-tF}QmCBSq4L`a9@M}8=RVb?|ohGEjgqTW9rj6*7rXcJiChKv6n zNR!k678%~to=FVdH7GrrPeC2tn85iajn`CMD=?Vb_mvv|$nN|6X9nZ;s+z;vl6uw8 zpIdetrj^YRJ=Jycf)hc zv5ryoS1va|C>-Lv-oDu!Za3<&EJIrJr6%lAWbEByDyZ5*=ZO@2JMlyV82v%2rYXO_ z#Z70UUG~^b*z|X^H*haa*O))wU*LbIo!A>nYX1`p^9Vc#YS4&?f-KhHDJyVi9JKH@ zN@$iZcRBudqFg2*(6&SiE>y{~+}il&A_Ga?X2^X1msk-pzH@MhNtVavnmF0LKF)V_ zz7z|;9E_7<>;;k(Ckj1U_XML*%5=diOZE1_?b?$^t2J(!n-EYU7`w&1G4zwMKA5CV zk^)^~LqmtZ(#sieWAgmGpPA=RV{6^dGfQ>UD@2xCvt&-wZXI6vSpU%O9332fDi@lT zpt|4^Dln*J#>6SPn!L_$BZIhbDB72`-CV8McBo6HOw2sOC?wOs-JRU8fAk_ zaAsBMuInYa!tJt4Hf!zPY?vVS4SM(Y8P&$}944vZDvNv>d(cVy;>QfDUyEtqezu?Ppj&S08Hp*Z(O7;T_%zXIw_6;S}CZo z7r^mH^FOZMPZ97cO5yTIZ9{tk@e|pc&f-IfP2sejVF}ASLx@t`Y#oz}2^DLs=5X2& zv4_G=T)`S&3+s=lakE0y0&2-?Hnj`#rBI2jG2bIG)Eyt7(W2Ems+4bIQEeNa^CxqZ z&7LTxw0JAO8D1BR7P=s>?sU>yr4X~3nIUvCS5)3 zWe4t-8;@CBYZ?C8N$ahU<- zv?&2g(NMIL02vPb3M8pstYlEJDUEm>jwSqjj*ym&5odp9_gx>89F@>)#bd!FlDj#u z=%}oaH&yllyr2p38S|)PN7t*&br^UmU5{riR9N`fR28RSxzCxD0T(KUNiO*VZKXi4 zG1hB8l+W{2;Pb=hj}~!{LwxAo-!Gh5Pp6BOpWL+NHkmAtcLu98dJg;jc~TZJa=jG2 z;}HBfLgUSjpxDNLL`7ebG4YvLsf?D2`lf`oVdVzLW;cxRhoqnS0I77OX|S&XhU!{L z;T*qowvXEI>RCaxAhb+p%Jnx*Na^$G#TubmHl+ zNzKMq9h}g%V)US?RgD`Y_PoQmM)gnr%g&fItft9gHxXm=r`jsD2f!Vlr{1MxKNmDU z68j#k!S>HekO^fzB0D$=1v#z~rWV|_jduE!216EMdKT7vVI7PK*cWjoHu7`cgIPLG z4&*HfhxbbI6T~{JqhDGgn-;$4lb_&O|};#=OJ0bf0-5M7hj zYQf)wK5v= zNmQ+x$31N=OMJtobpEd5J!G=RE5&BI=;gC;f6}OH%cJ7E`M5Vkk}cLtsYJ?EF<*A% zhceaCCI@R@hQws>$8Hmf^GapmmxlS2PVNC=sfV_htA4B2D@HhULPP0Ty6Q>Q#D*CX z+W4rK%NXXW{R;GndjM8>@t699ic>&-I_WPnQ>#%QllPX(L{d6~ZKLg_h|+5fDu=mR z0fX7-FXNIXM=y8ZE_U9nlY9982}eoh}u7hdV}C)i8DctWe2doBvolL$xJ#u!x9t zNa|Qn-F^v8{u*6vvD?4UaA_rkNH#bpf6aF7U5rJVtKnxZcci$+95@~%_A|9+@eY)WttK}!ap=zUB;WaKP$L=o>t;zmEWJ9^uGMINWHWq3H{CP zsKBh8EzzNZ0}+*NU;$Qj+%5^uR~hh+>@ddMp_2&tpZ?xU;(TW&4lL3M6`Gy0yUfxLOHRW8_P2;8{(@n)zF^=cgIx=XO7jxwEVk{SjoL zYMDBOgm@z^d*gmhx7yzk{YeWI&u?Z_WWv+8Zryky@$&tT_3NEwzs1+JXz^@F16X>}@)xvBIHjI6SgnQm>S`kY7FHf)i>$VC2zw<0+mlw_hj{gT~AGa>>rrV3Rb2Dm*qw;=nvD7EnE&9(h>!DL_rml?R7En zGGX~N?Yp}L_NI#VRd)2OZ*8I?A5mk8I?AV#U@72Y{R>U$n%%eM$E^hZgjIhYrXZ0i zS!86WzG{`w(Qmjo95%j%ucVtF4Ny3}96oWExwc&@-Az?R20$D!Aw_LT9b>kakDHPmn$z^Z&%Fkl;k(1NTQ z;#C6yi^XXX*ETGkvbL9T+(a&!p>36TA4;>HfeX>ffStCpK z7_j+0VJ5@kf6jE;Vz>hAtb!3)70DO;m#DoS-j|tvBXF6TuWqfiCiWz4-AyUvjH7W00z1QS# zY|TkIo2k@PgK~H=xlk8B?Tf@~=PLg;EnldB?iZ)J73+1eifTDy#%o6TG6DTzW|!i} z3IT7~1?K-eaE8$AXbRoDOZ1F08hwC*d{VX6o*S^abE_@k_p_Xwh*Z1MFRwZ!H)cL`NFK34ab{7`jLF@W@Xk`qmeS6+SXnC`LSGiTxwieZ4jZ?LC^bu z`fo-75A8AOZEa^}`3q&2R5@WMt?^YtMN;fIiE!@g;x^yYWmg*8V(6{{N$zZ*fu0o3 z2uSE9<=>*X<`hoP4#4#4mZ!V{?{k!{>|m~2YAKmMDYKZ(X)n632W-|(jRGajMCd-* z!o5qS+8r`VT_0Qz3kgz`6_t&Mc7~1k5sagtB z4SQZLNVTX}pSiwgA&oSp_x2*>pP~tSnbHhdtvVaHI?Z%mI6_tF!}$4o>a$K2233#f zMFr*#k*hLxxjy7tNqaT4-yef_#J{Y!t&z-JX@^edY13~2w?Q!%pdSNrP=VEkB#*DcKZcrP(Z|~7; zRIw_ag}G@NY{ifYd>DQYF~VFJ2jvI;5$i6g7I--4vABYM4_FYRB`OIW55 zx4go?FsEMd%GtqmQRlKY>mukDirNUg1@FmR3GOn z^}cCQOY4B)?8PEaDE?h>iQO2Au8bf^ zJoc7{F};Enj$QOy{!hfIcW~Z$Pi`S2oJ{s zHe7TIftl(wVaf~CP2b&63)hiT?Wy_# zvc39aHRe(O@VKYWW0P`OJN+Ye$#%s%rwjhiTH3tsb5vQ)EX*6Wls7Kxi(anBl$*K} zJnt-Bidy;^I_Ux{KliAdy5S<1iCyP^BKpa0q-h&^`wS(~G&6Oj$*nVPa<8a@^D+vC zQP{!c#vA^h5yS&S-5>zj!6xjpvIxYc7Je!6A` zMZb%KI40wPQxltQT#g(kHch_UcTDMOKDWWl_p1fWv`C+zveXu6u);U9SKe5Aft2Ul zj9++wHq*nY*?X*b&FPXJ9`}S!@=q??qNIJd28N{yJCs^VXx5ismUm#;tuOHPD*LXV z<^{dC7%1lzlghsWrB&(#rcI0@Nl%by3$zqjjHDlN4RXl5-4S;7XAG@sprH}0!fJ;`zwRt9ecn8Yw&HZ4$4$14C~!BKi+HA{Gc~UKZ7+Tc>j1laxj7#xZ;7U5#369 z5dQOJ_B{&G5cs2GNdxkJ{s|h=|lgNE$x*pj5$Pk+dJTyj$eA%E`Z`(AQGA`!~zCR!in~c8^@s z84X8hSbYVA5FV~_t?KYQvN9CvW1M44Om5F@KJFz>*FD)_(ig$XHSeriZPvX<>wul3Wy=9dy;=~}*Y;;%;|zTWn_ z!|%SogwP0%o@*i-%&lYW0V1EJm$SO%1+S`MsiK zcavH=37(^>bSZ#x^G4;T^z!OXpQ_KUg5kj-H_A451oXQK5zJpAe@-$1x-W5$QhBwc zD^j%73>R|6Bfn^Eu5drm-YbnmJoW*yu=VQ13>+xqk zOLCB9ovh2-1Boc@oQH<%(d?RPQhtlPdB1|iOhQzTV zxt!xai-j}aA%`5L^6W@5Gh95ML-r@v-TX^D?EZw7+8Q*K@86slPEm8;iK=q4G#A#W zGKn$G=^||s_G(4?C9m<0K}SBslX9Eh3P|Io1o17z2Hw_Zulm89z<<-B`^qi;=tt%V z=+pJ(PjRmJ+=(XexrXlrP^DXzA$Vftest~9;-BKA&?^&2Ve}Em8;?hF2i%93WVPS| zBRB*LCJtob;IV@}H=tozzmmX_;eVSAMtsFgFh%X+mu=K$K-PVMTVS-S|fdT_#3L(N@R#@y2IQKh53z_rOWy} zE3{5_AF1%{8nPq*LBa~GALz;{?fF7iH^099lkRA3cw5o`3U z&4vaM0fF^J7T~OPcIfmc&1u;yUS}xAHzTwGVdpW!q5?7itkc=Ep=@@O-Wm?G0rDz? zP={+4>7CRdk7+`I>j`mXBbQ-1*XueJ0R(CQ&im7h0yFLk_bMPx@|k?e-$FGW1cZoD zUyzLbHTsz-BnTvPudh5Pfc5dDVOr|&yxGvCok-EbT<~Dlng2Rs1smo7TidJpz59c= zA7?-r!VaR|7ym5$&KZ?wio$-jO#$j*3^My5vj3Azgyj!9Aa@TC_Ghn^uexNcpV&x1 zAA=xrn;xAGcM{fCr)`(J-cIJ&e$fxx-0Zz!3;-M=CK3@qs5dGg_*+ea`y9NO0HTIY z(B`GtS|8s&&s#7G&8Ulb<%TQFu5g4-{c>$O_QFkE2MalOFGCCKtKG3oE|iM|kEtb1Fd!rjKh0-^p&h=`kC!xeO}QPq7c5F$pjZ2%_7tL;%3cx~1BRWcnHTZ3n=*OSs` z^Lhom{r^muC=PJyd$A>y1up*B;WH@tNgJRDz)3j*HtJW&Kp=}cv{pGZ)C*!23#5pV zYz!QXdI0M1D+}w2 zI?*|&$nu}vPgPf1RF5TYJ8PUbG-#}^$-j*}?;1+RB3dX5_mhWNcDBY1{cmO^VL16s z!itCEk8MQ40gF4nZ%ZSG)q*Y^Z zH?Z)0h;PtxU*B6x_g`R`Y?D0#`+JWP=E_K%YC5n1lv&kULJ0J+rS*ztS5`l#B?!O{ z$NsbYg}#NyW~!ixh^I+~xX=RD!}J68X)TrNAVrn=VP>DR+6v3;FpE?|yCS8poJ0@d zZ)+PQ4T5LY`sysl%tl~?N{U@LYw&r zT`JAIlb~qq^8@i+6-Q=rTg14(sf%b&M<$E#$TF+45vwRNrdlb37cpP3Sy8=APFcU1e7hTf`YOmM3^`1Fo5hkGybPv*L~I1r>ag@S8w-reP6w< zI(5!}{&Tus-@e_|edn2{!ZNP}d+yx13qtR8U3Xp-y&v2LIF-i~z<77=T-6WWra-?i z0aE!xro2#}Kx_uCF`Lam?lZ>tV?Lb$nBIWV`VvElj*gqOIU|x$(Us9%(3Gk1`BX#S z+LU!2)y9l`gW9l}s$^%w!9Ln@l6>tD-BDOz(T!oPh$ijd7s49m*MVhNcX5KQ?8# zz73q@X?Y=M1Obhi@(lA-;Q&*~=zq)T54xO#WDo-jSO=j&V`;G-GH86@2@Re38=m9E z^<)U041f-Xc5aptt2a!qhEdWD(vcW(&TKM;H(51oib}5QdD54dK>zZ=j#41DErF+n zor=1hQna4s>dMrXur+OHwmd>Y@@5W(^c4<~nT+~wB~aTCP{ZZ{qaUYB1TE#PI3C7P ztpCYHoe){6O~~AkVvF^_cdC}*rCo;5dtK?e^eP_%iPJ-fgxHwD1Wy%muE0Wey=FfN z_Hz`LbgO>|No_KRpb*mJNV9tfK^!V}9;!&0O3Mu{45dU{q24Ply;5TunJryFn%9)p7x{@#&I|ca8&aS4BhuNT4AF*mNcL6tY$R zLU0lr06b10REmI%TV(!TBDIIrD#}u7lhISgw9O0%I=XGz-dtdoQPD8uS2#4I!lcPN z?32@Qg_B`aprh=uz1eG~DZlAewkQDOU=1fIcm*xO(UeY8hHcntys}BazzW*nUS-Jw zOF!|-Itv8X_$7GBah!w-FUBEH$BTsvOu8EWs=}KOf^AhN*47CA6{8>OCUZ)V%Xo^q zJe)lh>LIorw+9D4XwXu=GEl0q0WNn~_}ob}a_1^g-V*X_Xs}Hs(sXN6ND;VTZ|!2) zy@R7x1UGRZY=jN@PO-e^=6DD&$kFM+{6gFLFkegW0q^;^kc>`x5&B2c3oy>ma0-7h z)@(UDzgM-(U6BmfmF}7<;Y+O3#nD|gcL{j4^I4V4E0;xXK-bQ

Ze=h#d{4~bitD_2ZtrYQKoAETS=!z*JX^+L7>i0NsJE?2wxvH?YX{}IDiH>q;v-y zSSm|ypF75FL-(ZvKeH(ml2f+R;>?-?h3#jNP3{`|^sVCnI7fk5m5c%C zPf<2%Yp7Ve&`++#lbuybGN2q|TWI%bc1cs>OX=vgO2%ym{}kpR0VtVpZY%ZN9fczH za7+Jp@1$V!!F+?<_A0Pe)eFH(|3F(d=TRfRdv35{fyOPH zb?ZPNVI2?cUj@Qs%rwk%lK}`;(uCQFGN!T)u#VO7s4cT}Yw4JYrY=DHGPk*Z)WA!+ zek;F*fxAZLJ0Aug_CvTefU&CKBzney|By*MmJ@xtWIik0VcSQIWV})dal8Al5s<#t zAbtoDzt9jy$$A(?-iqUwoU71)Y0`#|e9$6(`e|-Llenq*x1C8mjgnSoE^dxh-G@)L zoQfq){s(7=P~H#yA68AO48A@KRL1FS@U(P*{i;;PVFcS_b=>Vd#)SPk_SR9m4h z9lO-Srkt0-6fXx8-x>*|D}76rK%S1-HCDpD64TZtoThN(NM|7Nw?@Vch8r9UgApPb zBF~2llKow{qh+6Tf08E4@~DTPx~_Zw7P!tQmtj9z1qr!}lFgKDie>^B$#ZoKR_y=@k9PI?^)fscC_KP$x8p`F5Dl92nh5Gx?~`VYq6-m&mojf22f zW`cjLYSQpIxN@xdFLX1mYL3zI5$LD1U{&*i=#DIaaG1F~ni808QSY`G!Cj&S~UkRz{mnfqf){f49%B(Qyzyi6O1l4+e7s z=7S7wP894QH3Z-mIZ#}BD2rQ(J&4}NkWC(|FY6GvgO`XfJ_e$)e#jnROAP?EMhxs| z7~n#pEn9ER{Vhw=Dnhlz72C^;ao8c=gr_vkJRN>1)%5N|N_p#UcX z#6vkU-#vUPa&W2BFxDU(eV*Cl!ROdgUYt)u_Hijzh#q|X)bK~$KZRh4ZQ$USjMEpz z03{R|zouyA67V8ZIQ)X?l=>p$qDsK!z5?G=6em=l3sjed;uf`oPxb@6D2`KK4@_&T zwdYRTScCBE{PGjaj|2x?l2_+zxlqkTCH77og=B2Eb{bVM2><6A95USsTzVlh1SUFL zc?~%Q*e@}Gk!elg^y`piSY$ir*WsV@k)<){eTUPv%3$`l15>SGHK=(2lnz2Y5p|uK zU9;}M<4shvJiscOLRg(_T2kNC>-*UZAVq&*@}?ey%qpuM4A>7QHQt6TIO-27+>d@U zU$vQJfXm>;6KD?#qncc-;VwY6W@ZoA+Z$hI1FKmGdfee9n@1>dmsTmXQcn@aij{~+ zN-Te6aKLjN8&|?r*HUaRjd`ey^N6;x51@z+OF+%E*5Pz!UgP*6>Sajoa4+m1p`F@HsQAx16qUW!138uRP#0;2-4J<2 z67QsJ7AW)x;`AX(K|P@$X?qq(GN)SG&Fy+JQlS@Q&w1~X%dSN>_`#71>2@0$iQ|?# zTkarb61?g?8sG8Kpf1ID3C2k1AVHHXNqQ^4gkQNzcjrXTd*TZOOIVj^JfQR_{s zBFrQ_cPOjMcjLGSeqkm7bgZqcz#qMV!Ys#B=FkBg?E}i;BQu1kxev0%@Ih8}(sQ#q z<_B~pNJppE4^1SSUW;L#HT%NF)w^^Eq3LI`Vd7!^z6I?3uiGb+Rs#&(J z%%KO^Btm_UNq2@3%Ty-7M&D)+KHL?>AJvi7%0Dy_93^*>5zKPLY+$2@L>1^jxN`Ob)>X z7FdlsjGf8?A?WUzfyq6eMa zd9~0^sqLd0+BWzwrD0Upw9JyAQ#PHY1=kcycZ?35X`6s)f4z)S$xgHx4s!p?aJd3A zl)h=!Q67olggf-z9RW8k1d`33NyPGEnR%x8%ozRv$}LPfJO(yl#G2vUv5s2?5sNp6 zb3Z2xkgdSjG;;rw;gNj0Z)8q2>a)s$LJpsi?HmZ7GXpmFe#RSficJWZz)2K!-G{}8 zDW)IAi&jkVw7*C+2O&Tp@y`sg=#P3ZJ~&abZagFo&IS&?!Z?W@8|T|9V+fImo?wnz zEPgWLs18%GjDv~J2g>*g{?LT~TNuZ;<20~}=W3doS(`C2UdPC)6(QN|yFse*3V-zW zHfO2OxBAT>-T#SI`D1b6nfsZS%3fjve^=?za&4Aq1R;Da8q;6lLkgU4jW`xGW5J=M z%11gX|20B09@R%&w0P+Es;{=l!@a6qWLr4l0Oy_}*rABi0Nog0+XLK=n;_|%Fvj%s z#?p-3DJqn3IQVx4Z4L-s%E)7iN?(|YK!!VHJ{bYm4uOPoWjVV=oDn$Pk#nre;&^hS z=>D{Jv~Rc>?{M&d=0r8eGD;P7;Osrhp=J9{MXocj@cm)Ve?}=r2Tqo&#gT<9e6x4g zHBMs|)97OOa4(1XNmM5uFfF-U^9GN3v|%`3mLmX}Xce3HLlZ!|gKbU^ zAC!AUi=sSGwI5y@Kg3O!qQ^9mYKlJCbBR>e+V(uHt(u=yjh1X*tdj?lKArKmA|@v% z&!{>R4uJDB+Gz(4Pv_(f%Idm}r-#TLQp4XyjbzV<%9S;BuXVLKBARUfx_Ib*H2-=t zj0+H+)KSv*v%14N+wgCFopqf&bYI}KFO#FZlN9GAX~sh9;4-Y}E{0}ONfQ)b2XJmJjNxoq(4B3_YVZ2;>AN1@=!GFI zTZ?OLuK9~LB%33alhGb=l-lkU=7<>raHPjtxFvR9H&h$zf}isd$Ap+8*~w62>>Z9l zj6O&gb*MBl1Wvz8l4kjnkiyu_mT@KiOe5?&=u{=lwp9t=-KL=A9gMwp%E;B2%9mw3 zaoTE8(8aTAkDx;ik*GcNWLes~4nl&$EQ^vZzGPs~HwGC%f@bJRvb6^W)PT|gHbp~z zPsVV>JIKwKjQrTT`FA!#^CFuzBmc-K=NkD~5|z85&7{iy#gb+^w@{Gv&mv9FtQLXE8Dvz@%FV z^fxRi}-9-pN_g+-GHQJXx1LGOM zg!n>%NklKTTdnTg!RMz?-xBhC4tnpZn`7^z>nz?)Pi7NfT+f}Tue8Ng1bFLd1db7?~8tbo*`U*V-zn~AV>2Yw}))z=ReooU|d;b+@ z06UuAJkGrv+MFZTS4<@;Jjkz$D!H`yYv}d&KB8v7C1BXG|9~nfXS9TJAsPsb-eUi} zAi&3<)4J#63kBONXET5u`mcf=Pb&YCwd__8{OP;JgA|CTyoT{ryA@r}mdyZmVg>e)Pr`k zFB|Ga3`20(d4J>Bf%?!$El5J(AJl_)wC~4Qqd!_R4D+y(7_ejLnMFzYWhDe!4vNIA zjw<AqK6$qPoPW6_eU!;*=Ug zAKD1P)G0X7^PN*smq2aoZX$fsk2&3gDk-g7WY*+9tkpO64*j0fA0>MUI=j?L4$k0{ z)|gA~EItjre{6u?W$-I0oxb^1cV46T!(Le)^+mznnFE~}QJe}v;LrP0P7dBb6uOC` z1|BCnxadRYMRC}J_%nd4&p@S#>npE7p|+*2@HGXM`|(U4Pjmbc2p0BdB8~=pec2>n z>C;WK#!ju`MB8!{Bv^V)xAp}^;6^L;VwH32+!Y|bvyeF5Jge*()H-8soi8NzDB(_^ zUvH`PNCSU#2`+Z2;?)w?{R;B*fV1S2aj5V9S`$>|01|(JaQ0kSB@Y`mxUDDTS43?+ zo4=~$Ah$9qo!UvtHdXN$8C+zUF0K7ul5ObZe=4M=Ou_eJLXJh$maK_>#tjHAib|(= zl5#-CxbMg_fb7yu3A%(PDW8`kSEC7%F}`4`Sm_N|jTMlfm6*3FGM??pjS=mtV-o;jxR=rRi2|5_rxm1v$m!PvEUN(7`K({WHv51cDkBC(Y3OS}F z4w6$qT37!J_TloS97Z;7%>+kc=q}!gg80UuvkVgdv_Q8`74Z)v2}nI4(5X!Yxu!*G zl2gIOq4zlU<)*cf>w+UBdTY`L1}%W5W_S< z91<0}o7kFDM{eGLAFbq^i7F}o&0!3+3|aXrRLN~&N?`3vNkftkp0v(7MtL~Ie-kzc z_6A|VbP2W9|FqHahd}ocCWX|tisrZmAn<*nKx{VE8)~2$%>{xu+ZKo+r(cI#BAVki z0wKU-jG%2@y2-O<8)I;B0_We_0xBT?iOWYD#}J$J&0(}(*J@)7r8yz6p9yy|-SVDN z+F=6#1!8oi;+O`gmv)JOihMGEsI)^NK;`E}2z(Oio#69P0Vle_u^g_u{z;(QMwLe+ zkeU?%qjm`FvoqjSdP+$@Jn*GDNLD(*5d319@x74phlGa9jyN(N=??WO&rh;J!W zx@|8hSGPYRgCU~&h$OO9=WxTkvt7iqMS-|&s&u=%^98}tWz+j?K^pRh&|k0z!=*wv()Je#$Fb4(71 ziSF=~DR;!=(-tfw;`xHAqUglDv7x~vKfxSu@Yf4`mk{c-eObCf!{!R8tQ8TqmN;p-GMqupc_vG4nK)1 zEhokE+Og>li&3RzM+ekM3?Wg|P%m{P>`IKSI}*uo z1c@A6)nKi(E;=G%2Zf0oZHP*zx{@*rN|H;}6I@_$xCA-XxeMEQC#?Gx@-aUu z{glb;sJ`+V6plun+-Ghg1IWiFzQk$c^vY-1uX#Z649(Ejq#Zcax85gG?r$L%G_kMs zCCxE@3C4nNzWEt;O9Q#s(~&D~=>5(JVR0H~<&b^a2{=N7$kD2(k|VYwoyibAlRDf_ zpBI=H$c1#dt;*}>EIdY!QX0Z7y~3*-i`3bO;|h_B`-ORvsQo-HyY8YPSw$9TsobuU zi5Swg)kuMD_&3;$_wIL)Gy3uvv(Vdf`+^K0sY?eWmL76XiaOsrRtXAhXBW^NcGbrt z2iQ;WG@)3W^$eOt7wK()e~LW`g4P1im&B0U>a-%PFUSCP0xbbPE@CoHh=|o`D9lfK zI7S_ai^TGYL>T}dKn*E$opSLa9*12Q`JhXKWy@j1o~I)5A(?vzCUpD^1ID!GHna@Q z6Y)io?$Sjfr=o^jDx^z<{Uui;xyZ?FsG(&(I*BiGLEUsj4~a^i<}qlGMi;rEONVq+ z=dQ5a4f!`vmmiI66ps?QIRrJd%uGDOnpO(F5sCu4M^G0iPQSP4GhojE=F~PN<|LWY z<8k8!o$r(cqxArbD7=2#XP`_5FqgJ1IUmWK9;qBJ=+KX@mc0u{Upnc5(!TT=2+jcJ z(DzWwmWy%(fVgv6)YSgh*!Ih2a~bXht_)z#ybrbPL6)ZAi>UnSLJWMCG$NJjfYZqD zt-BK0kF_fUm?K-Gz7%QB(W=5_oe@IeP^FKl6(#u_80?2y&uaj>IR}P{HTE?$mn{_$u{gloC%_F)=MMqFNaMktj#*^^18J0>sj4fN76I@wfqJJIj zZ>oO3?K9AD2A+WbZ85P2s|Ia+L=#*YW1`by^0QD^Q?h>BXQ0LmoC#kCVq(82^;zhP zAAoN}T^*JFG2VxIrPNWc*JmIg1GGx>Xw)e*=TP=R6;E#RSLg^%2DXBu`_dTOEv+-K z?XQK~lGV$(4A7eTD^Slty&4m_=o)YivzPT5814-G8G`IQ;HEgOj1ggN=cK(LFMx4ai|E4sv&5Sa(k5B?AM?YEKu( zkP61Pv(I+>6^b0^HEt6WN?o{Q%GCOU@d-<(v~Egjce;7wMBmkfr8*O)Bq@reI8IvR za`TK+kdDX34Kobd-tT<3v-bI&>CbJ-_k7>`wfNq?=XdUZ-udqHhdnwG7fNfi`<U$88!CCBewMgttp#B%joT({NAO7nI?C-j|>_yhO zM@ssi4y~{(dzzSbcKd#&r4@V4BhR@^o@cO7R_1X0k&pbYKhuL3PP{N@oza91onBLg z=W)4C{v7{srLDuAi2jXY#}Ca>XW&Rv(8&AsC{C?ZHD{M=WK4m|MK`G+8^Hx;VNZNQ zglf|95(;`y?5(5{ik=Lt2OpXOKqDe zeWzSDC%0|ylm1Bu?w0bNJu1yBu%=A#W~WpC5q7UxyAQGNe7fuT8Kw9=vmL+oukCS4 z{wn4nZGHW^{QmH&DBd@meYcKGNcd86bc4D@maucv#ml0H=RH{A%fspBAI?+VwAjp0 zMZz}L5UTKxmiYg-x0=4PW*5ahKhTgHQIqrDR6w}wqsXUnep7+o>XkcB+Rl;cIH&A; zmv`smxy%;}luY(=eq1duKUaq1;!K5_Os8{GKZ-nm5WlgeRH0ClW7(b)m8Whlm#n#? zmvtiMxy~Q;dnwbh73-&Ge~>>Xs9ZQ-dRN=jt=Tpc+V6HXv+-)beqQ_FfVrB_3-zCC z^S%CDQTOKkoIPWE(zNuaUWUa&mD*{QVe3SU)hAL*=+DYCH5vKc{Sn)ed~c`gKAdsi zea7DM7Pp)f_Gz_!w@S|}*imfvTymAT`t9bgTeIDHw?;ns##_25@rXp-iib;TgWTIK z^OuXI+nXh@zh}F0`_%G4i61)?bBnLFl&;Fnnpw}g`{XR^66t{Ii-FrOxvqJozI^N1 z3MQrBqMt0+tb1(P^?L8|oY^-_SFAr;b#0mUXY+*V75=FcWe)F(>blj#8y{^t@$xl? zNrzhVRIfFg)y~|{zWa`J*Zs$3CN@sFp*DiYbN8-El>fCf!utpz6U&YZa=BkQMP=?Y$W#UnDXUpDU;j06#}m_ zck)H#{fOTAuty@K*0uUg1wedQU`gc6OS%n(P7B1R7@k)0;16hwA1 zsK|E3NQDY?#V}0bbJgqB;&9bt@N8F_?k3uzB;K&Zd7}4XE~kmy4wn|5SQ^N>@C2*E p%YY}BRx|}X84%2Q9AFv7;OXk;vd$@?2>=j_MMnSt literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/illustration_sim_absent.png b/selfdrive/assets/offroad/illustration_sim_absent.png new file mode 100644 index 0000000000000000000000000000000000000000..554097409bc0a54f27a8d4d3a284699abcec2e3d GIT binary patch literal 6608 zcmZvhWmpuzyY_b%78WE{y4j^c8l{$4nx#WZT1n|nVOfw+IuwxZkQ7m1Nu{M*B&1Wi zBs~1j`{h07Iv?h`=XvJ2X0G|o-1B8(bhK263F!y{001#cRZ;I=^Y7a=1P=fJ`Y3#_ zyAOa~dMfgO>S2a$0D$%lN>T2qKX54&XBKyLu8YZVnZ24=&9y9Fat129JJM9Vip zlqy_Y9=b2eYiRO0>gvm$;%Mr3Co0nm#5hj)DZY4_Qc|VW1WDaSmWB7>J9AC~fpTlY z!#X;6cIg4v{|-J)XZW0(1m*fHy#JJ&CS||hdLEc__Hik2xXqI4Tx480S!fp#(9_k` zh0~@cviq%c!rqXuT!%)qC3ZWmI#TDNu(A1dYqG9D$>{Au{cp9xX84-vpxS!Cq{Ixb z`twvg>n%c;bYkRU4VmTL{GO3>1^LV>;DpV`}w&< zDZIq9X)rjgG)PnXtig%Zuu#Y1_lmATHbLR3Vvs?x)gyrmt1d3e0ZM0OyEFrmN#5?} zb#mpgv+m}B>Oqd!W}cx6PG$Rt$CmsWw;4m@>9bk2!gmJLtU;^1N?sDv)arq4#_-o4 z(;9%LT0ysTxAZOx(OfMa*wzF=;rxNL8-FKSgjES&=zaEY7ExW^DCCuQ?6U zSEh}0r%#@r|9CmNhtUnF5z6)>Bl%TnN>jsNj0U?Yoi7FEJ28d#eU2lU#L4mLUqFws zA-3RLei?LKeC&?K3(dQhs`Iq6Mw&@Sr+vHlEZ4tEKoO1!i(b4g zcr^XQk7qUimD2S*>|Fny3&QA6>h|8G$2${RO1~F(0e$W1>tPc_;ZCsjczE#Wlrpg9 zjg>)DL~I`TGDe@Zc^q%du& z;+>S+nUVhN`YS}0vaF^oKiq}=tI>p%RGl|`~7%9oS8`eAn=La`Uqc*984U1A*X8H7$n`eV{u$0h!_So08LaH&ZLi)qPGkh1q@&U7K zn^r^7AO<@l&MGmoS=G*Eyi~Wx?~eG{Pj0?iG*InZR@hf~?z5d#NGdfsY3m%UmgMtD zr&`)ie|TbU8x?3aJplcn<&xWk!T!U|~(R*6f|?DriS|Rj9Ca>zKc5+5h(hG)*S5vX# zH1u?7xJURV#1gWNKz-(Os-b|=?TXNsFE<-RWVEQ-3?#~kH~PjlB&l1fBvd!evYe;n z*4LtTRU7~0dDb8E7;!Q@)v~Z=oukE1OVO`{Ng6jXHJovI%@vAXn|r!z&oDMz83h$) z8su+x@e|j5K3K`4e5;ZVJw@AA@!(b&OA$UIcrN1K5S2|~pj}H_?hQ>7sO4Vc!Xc9U zGG`Ywy*~Rb|NG!G3DRZD&Z{uD*{sz?jnz#n=lG{-W1Y?L>T#zAGltl1KHS$P3#XY1(QoP@hsh`E4;%)gM}7 z=*F#~1n(iCIZSdYnaJMDE9j_%fkn>*!4_Z%^&^TOH2$N~l%8TXVnyoPLgFXA@9sGH z#u@oZbj4R+m~*!;7fvXfUtTG#@3Kq$G-_1o4ao9vQRJ@nsakp+cz8v(esQh;x6nCK zPGeg&rEzq7(4aR|R;gtU)^(UHnj>zhHsXm*X(T%-$=s6d{1k(2YFeOlbplk8^|VCli8l6R|#`=XG9pCM&vT$eFK z=y3@_-tt#e=S>bKpiaA`33kpxHkb!EmH~U=SluZF1WX0OCqS4L+*<|>Ay&B7~|M$N~VFsp|aC8Uh;GEx<n$Ku$~uCp72gZ$_22mw{Omt4un^4M@a0=^W{whX$sVd;i-I=1n5#3PbBzU9bV*p7rjtLq zzy0!#&Q(Je4`25i2wUSxCm8Uk{|!xg_-ls_EUFVrb_IkB;**Y{ubzNYlKR~osZIg| z%=r=X?2_o-zBT+M0Uo}JEXru#$FjdmI`)vi#N4YMxtf zA*ad;&CkCp^riyg0*i%pK7xINxHa-Qn6FDMm;pxhSS)L*_6MN*+qa=sI$6I-Be%x; zurp&&g}dRC;hvUI&=~z(1Lpq&3i`4X%JjS#GIF%2{-3=_wIAchgYT26!?~D z*srznqCSa z9S;v5!`z}l+J*D)5egLk*Li8BcJdVdwl)(dX;ARuf{ix4d!w2iVn}+&_|(4%yBBP|@LqVIIw9kVi>FkQcw~?C zW?gf8RfKD!e%7)65ET74moN3XsjD%wjD47K?I94;9DI9iPJAJY@;VG6wecf+F#y>M zXn*%QVOHkdcua}2^^1Cti$`Iu7Ovi6CCD)ZEQSSipE#kj^$45a}$u}=|u{P#K#U?&> zd{M+TGnBPsk{|L1t$aCc+#=d8l-U}pw07WRp#!SsiaJ> z-=Gzzq*fY`E+83324i}&_YW|(J8cIvUZ%eVtn3PXmWAD==$auiUWk=6b~5qaXkPla zROXU}vFk;5A=H#Ue*)D~jqJTPx$7b^70H>(*f%GAX#J_cr9C5|@0XTUXJfP8{hk|_nyK4ey{)5A#A|q1Sw(UMs zl5&85ANvw3mdTp12u^0m>|BA?p6G{+Yb0~zk(8b~yTmtN$cGr3mTx{7YsWFmpg1#o zl=5IF=Z}7S0`FKm!u;BJ(yQvDb>3ZN;``GZsr9WHx?^PKRVVWN17+)<@tNAPvhnWb zk0TO)Jq06}WoA;z7_TacS@Q`)%@EuS2TzZ|}?pQP)w zHWijKYRdvc9xwzy)AZx`w#sQjb3{~W?WM7&DgPIF@NDh%n z#Ldf>^9}edApqU>%SI0pd(XLukxE#^<;J8-N6AJ0FB5l`T}gHy&ZCQ4%ULY`G1KYA z?Bw~YFI~YI#O)*rc1Q9@oPx z(XBZ4k{S-^Ui^==F%g&1O;R>LF9aCIl}o(=`$FR0oHl&09Gcx<%K$PO*c}ZmGgmM^ z?2c|wegXz0qk_rA>>(1D0N)LGAE3g)s>bL`a+@#m!+76Qj5j{u5hvCHj!OGnBM*}| z`gu=K;rRCzeFA1T2%FCWia=G2D*BSQo){{>W9oH&`xFAu5XBY*LEUY)8K>P9!7lTG=(^?Av4PGAnl<48IJxXw1_FJ!VfVZ-3 z4HsbFEK41nC&Ck?1a#P3G2;Pb>&`tQL?Wm+^?+Nk0~We~pH1TL36b_s&)Y&p*Um7T@7{2DtgK}u$YS2#A<^ar@rtZE_b^TGI_?6;1OOlPf?Xhe<=EmNiQo+E z+t@@xf3wH&$l(Y!#Xr~i7YT_t3a3h?7r4H8_?z%DCI>7hkxU zT_;0auSqI%ybmoUwN^yLMzUQNa1SQ{zbklka&?NyhNTp8nuP0O1bP#PYKDsblWPwf zR~#w8=wfPO;B;E_7XQg*bvP83e!lO`^du5}(KHpL8d;`MU5rSH4{mj6#N}KhT+I!; zF>F-cSUMcsS}}snyujuhyzqO7f8Ay{K%4F9i{}z-@ul$iL()kM_QY*ecaEDG)FYT}3z6k8bS#;t-;)G{|h~fvU0KWW+Q^I5Q>n=IO zkdza&E9B^R&{W=uSMw|29HngM1#4pK8xetGi)qTGiW{9aDw97jtkIKm2G6-Y!#LFf zPr;3nz=Y>*^jG*~8CtH&SH?C?;W}=S?MYbb=e5ZI<#WPlyAi9K)`0;&KCS}o+cgsT zg=szYSB&1D(EsEh;fXPFSNP^YJ^!K*Hb{#w5AAJ-@drN{53g5BJsVjX7d(*P9~XOt zZvPy6+qYj3I=q+nrx;SK-pyj+P$=%gIh(k8lK*>;Q{EWa?th~?7oZSLOwBmku64bm z*FGe9c*4>*IAFbSt62N*0~b_nMhb)o?EeE<4- z!V{o8rj}qp+7TzrpEN>Xzyc=#c>J2<{-|p?f#XFVAm0zUTvnIuL*OE@H> z&TB=3DHoazeB$s0P!m8@)%ufjUuVKQ!Mqp+;%w5+o{_k#)D$;u$B*HS{xV720YBKp z#E(S=5Adzi$Wrb^l})@)pj-M-nS`M(>j1&;rrmVslEzmb{MEmGf?Y>^qdyrwGse_< zDF{nNu|cB5HnMl?aIH5ZZTv}4P!hKvh?!LxM#dADd5J~Q4!1uRZ&(kG5UB_;HLpK9 zxtK#{L8^b5?o#|wd@`5c9-OrkHvw77!Jt=!U3|u-E~?!SrzsKrIWmL?u1&6Be69m0 z3?`QjC`gZHg~`$MYB!KW6JZ(vU5)P#6JfEdoIeR5r`ubX3=Cr>HxpSdho%qau^u8E zRdKpZ^{&hqcWJyW9*CuYMt>4NMpw=G=K~zEZaUh`kj-%DCLXmA7X`{o4Yt1FqV*8< z#gn{`F+x_KQJmjT<$H)PD3ItZy~GKMSX)gU-svMFS`rj(!v?#)ynbFo3!?ev73ZPh z8MjdT{-S$ZF``G5j`+9)h>~VO*R}kjX^$&66La1mm6wde8`5Un`!1E>%kGm7=!JCE zjc;q~HCM(7=Ux_&$176ni9T(7eSZ0_bVTk)p{EQ!7JRH99nwgdl1#_e;YZm<;3>TJ zS-C~Z@2@@NtpJ@Zii0-zr%s_<8NDqDvzAiNW^_QZA7w;>S7v9735xikRqa0duxC*- z(T(MhNim1dhXwNKOpE9OgQksW(jL2i^Tp@*fdpN?SL(a>aJj5UCGVr@C?rE7ES1I~ z8;xtds{kWu@UofH|n;HW3jZ4I^8Ym2KSh2cy(wf=2ltT zkoC}CImhkslkk1YALRV--o*tXa<2>$<(f;-2`h{P5#qH*g3ESw#*?v0Ku;h~8C*%p zj`x!T9fUQSlw9NWuSO$oL~@IMtz;g{cAOGCS-Sc-22*@-08V11q{JjItJAP74mLf0lc(ZJBU1#3uTNYwRf8RR%<47gr3^0fb{gjcgLa-Fsb4bE!HARgtnQRc# z?xo;W$ahYdrPAORg>&R$J|;M&>0!^%axz*a)-A5Eg@X_KO ztqM%05aWS^T_QHA!g$zLFRDT}SmwQ2Am2A(mMUVR<<(hHR%_fjYxngM<5$Ab$TgH3 z6IPJ%EmF$mamF7bj3DD+)8`0eFk$wDST38aRT3;~eiXGR)K>j^J5l%De^;p2QK%v@ zg3zq8;(NoU#}^wDvfUdOqBS{wZ&;09Jzg+bB8&)^^W`=~6W8TjgF`ru6yR6&!%Y{9hC6a@ntPY`^ zwj-4NkwWM_La?necvVboIN?zL={$Q!-71anwh-eG`{mFb0m04N%l$ZY*aK+W?Y5y* z?_XX|6eB0PE{N3(3+>Vr68lCk=!=?;sFhy)Xiq9HZo$^je~_LoFk=ln-dzcPL=mp9 zH;5~!Ow?EiFO{c3OS*K@xJ-+19~)wH5b-^v-%e>0odsscTu@9(%LERg%$;9Y2h?7B zR>~RwPN5);{f~=DHSi)0o9X56w;YkV#m0V5nxd5E0sNk{yry^ZJzCgBZpSet` zZ{eIBml(le?`NjS&RjN5U9vK?WSZc3NZ|7L5 zFHaX0S6-w~ZDt0zNE9O#lD@ literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/illustration_sim_present.png b/selfdrive/assets/offroad/illustration_sim_present.png new file mode 100644 index 0000000000000000000000000000000000000000..0856795f019ffc9bb188ea0899246da6f4c903bc GIT binary patch literal 6331 zcmcI}Wl$T?vu_eCXcH(9tXOGqDGtT0xVu}C;;tn?fItaFiWVtQpg0t#I01?~MM{w( z#jQAn+yC5oAKsfcb3fe=J3BjjerL~|v-{gQv$0wlO2h=z1ONblSox*A&Oe?1Pj11u z007We4paNj0D9{v$pWgzXmdWJKHt|NlLSX=zb6Cvr=K> zGmIn?&!0f1vC88!q#{?DO&WMY9qE%*LLI3aw3q62Ok-6lXRKaEWMKj$6Cbm3O(0sD ziNQmouy|V+ZyU0gwV^fdZXd=o8zh1+vKIEl(%U;(D%)SpZJMs!R6dwpjO;IvDRa}x ze5+jKws^tESKHS(IdOBmQ;?r(#y)Y39YfRvcLcn>O{8^qR%;mku6aNnZ^F+-UEDqx z!sC3Mi}yr>Qorofmks^+tU>W@YIG$fF=b|P`&6&3)bahs@?X3uJ*sxEgCb{727TCk zcSQIUXW@{vF-@wav);*zt&FHa_lmD(v%)H>Xp7+4))~ZeH#@F!y&*jZdEZYQ!~C<< zvx3xV>B5U}Hhta^>Dsn=H-uBI>?C3^D6ixhvD)q*swlS-b!y`BX$K!8`)MyeXO*G0 zTwXy3dy_hMo<7C-vML3y`|1v|w5Cm0PH)F&eQSHh&QEU)r?$}d)Fw6_?f#+H z@$&c{?qEp>jMyt;Y1@diu+(l|S6e8w-LxXaV3yckYk_cU4MrWJh;DIr?^VMymq6$A z>JEMUbdNoy+%4aHcys%LRYK@;wk#0G_JhofALQCJF$w#0UoL` z=9^#_sN4G70q)yxvl%GvR43Cy(zB%eJ;8O6>L|h`{$_^jNqLOxa^B_6NRjJgcP??z zqN&qb4{vg%XNy;FH)}C8lCINw&js_LQt6%I;*R1)eFNWH+?vkrPhx+|pE}uK8c2ka z(Jrq+g?#YY)z$rj-fY(&gKc&8q>kv6%(_K%y{iU$O=zjeLQJo15!q7?p69l&ZzJ#k z<;C{5sv9w#n04^C2dE^=2^vR#xYl25p=@$~OCP%H(Fx40+M4Eak4d+>wd&3Z34Igr)7nOjPWE+Cx~Bg3 zirn=tJDkJc$I|6q?NA9`%8*>NWj!8uv6FI))fKlbqEUu6**i4O`sYhk@}$xzk7_vM z6`h-y*5#{tPEdxh$?QkYF}(TF6d4jcU)Om%lwR3vtH$UER5jHHJJ%Z7rIBK+J))v=Ao_;8@$bb@ zLwOT|s3bg?k6YcC-%cO1fnsmbOUWpaV;8Jptf6bn=&T+nxWfGdS ze-yZ}qdxKgS1x8&Q|6bmcVDym+>VsMr_IbyJEnbYvtXnl*&MZwWW0P z&a}_wudIYnc)F#J%omqIo9|m#2Tzu!f_>Nj@&0o=ZxUWYP;DhdUD*Cm%Jx7GtAm_SGOV&!Qb`ph}R5l5OlHlPVq^!vN-5g8mo?$J^MTnrAN9xs6&YxSl z$F5J<|xr;U! zC7QAF%}OV;Eh43={IpC@qmj@D@NQ@$rL)tRmED{i6(q2f9NB> zC@(=-ZWitsrD|!+u-js^Ng&T*b~6Oh9`9o}WH4EqGNeESaT~ONwBPMTev|ynLp|af z-b}N?QG%zARwU{7qfq=pyOQ6)(=myjy55oyTLMJ3se6Du;Wk$#8CLbh(wjMn=M7YV zJpLU@qA8BMF^IYt)wvi!!SL3LU6+ahIHWR(SO|iORIBjDE)e|EjSKQjjP*^Bu2&SA zM?m}^y;4oU314mt%*o|o`dg;ZTU)JS@j_ExDmvZ;sU;RbxIOE>< zeM{?9;o5Y=d737s!;3@tJJJq{3yBFqKiF#*IKIv*kukJ*& ztRDHTPLG^jKu5JzyaDgUEL%9U(uD~z4Z8nHF6b4p_9~l?lCCWZbi`V}KBa{MRij)y z+8-Bm(IEBH_yO9hsrl^VN0BIU+!9^#`e5u6UgCPzWBfT`$T*wQswL=lhfO0$8|bi< z3ZLmaoVXJI_BB6arRQ7@w%B9zCOq=*itESG;)E{dCY)n`ZVKte1_OrD0Uy@ngZv{0 zkDYYRiYlGL`$BHIhL6NiqzbVH1W2+FlWu|_!qrW4aGCsZjjq+e8r05%#m`th(0+jv zFADYtZtv~wJvg?^FBHjFCN3(PRAKa{K-;`mg-t$tJ%EsvwW}oedc|%$ez}Oh7Z`*4 z%`H-zh#=8|%ealzICwCoSp;IST+1JL5mhcwv}MARW;W-MXe$^3-WJ#lbi}N#aV(%5vC8uZ`Xz4w|M4 zUJ>bp@r&|B-e=IxA>zFt$CiDp7^bo+20-~W5f?c^4ytbmLCl6krxA4JqslnsMG2N@ z1?A{#%VTId1Vp-u26!~8ny*02ny%6`R4yNrU3zjSa6SV5JY8Kdd&~-uzz-0j#0dha zxo@vYMo*HJ^&Xl?ocwYql*rV&ye_~eI|UOYeh010lie?5l$MrmY>@5!J&IBU1i2Ac zI=c}}_|gCNx$Mxl1Bu%b9&d-=9<_;@B05*Dp?FUa;dT-W}QRo z4mrz&c&3+V?37@lyRRfCBADB?UwfIIGAVylU*1?-Q=AJk{B)W8R9kj@_5$OCv5Z^8 z-hZ<8NHxB?>Z9|`N}|!yF|UcMO^KC0jmT?C2%Vd$*i*yeNL-+EY_@o!n92dxK?E)mFV7SK~d<6LpT5lPtBeo?@tO1-5KV4C313|`Z zbJbzN2qX?FWcF49_1cAzK$=t@fRT84sQ6U=zA{T2f)G_hTs<=g^xe5J^V=){&|=Pd zyDLs%>NNc=L#1KGTIA!=45yai!0-AuOb`$_+y!pn+ z|NmRN0#A4JegzlzTlh2=aCK4g%_ZHR1^v*owC2w<0C)}`DN`%K9Tt41YFqOVogp*5 ztVX~QPB+D&7&1fZ^ND;F*fiyDZe&jkI=%;+x@f$WdUlLGA3x8=B&G6HU*X7Z*j%l6 zRY2HO@=%R}CW$)geGZ|tJ)P^d7p`RXm1OGo?)Q&!&oVQVfaAM7gWtw>V}$6CWV7}l zp9MTc-?G>JI3Ks;@uh*kmAmR%ShWB_q{lAY1pjw(7W^MKFSfLqp2+C**u3Bo-!B#_ zoHVeX`hC@Vj%rJ0HK%3R(Q{=iQxRU zQD}!u?6K9>3^(({*E)2VIJAUPw$`T$<-ltmF*j2eEb838WR=7i%ai90^b9tLGtmjj z0=(O)Jr&g@r`l1Jv+G1+q$jhotu#5(kIrMYG2e-`1vc&V_~NdzvgX__X!PQlI^5zu za#;lb$C>6tODt7^VO^&|E4%NpviGsBzuv1y7h8()6?b+I5??+x^V!%_D8vytVS_!u zYh+3VU(;hWZ95vjesHQ{@#*6Gl&^_|C0^1!wr|cT(6rF*tjXZn`-v@*Y1uy$ z+P9>G#yw@)U%rf=l@hz9WwOlS0L5cviYG`h+hU~NO)Hp{Yb$_Rg}eW{Gbt|h_V-P* z?b+SIGhv;JEaQbw5`Y`7U5Wn20)^lw#SgeKJ3K%zkX} z+ard4skr4N^xrn{Kh)ZL@WiWE>oc3QcZ~jE)B~i1P^!FE;rDhD{mTi^8aRJ|O#-kc7$&!^12I;k7%$ZOAG z&68VtXZ0?)e(Dz+k?`NM>i4AZtRiyX{-xR>YK5V;yS4w;B zq1JTozb*|BpP9sSC_=6Madb+yA2V0;zY$R^$$>C-X1sLF2Ef;>!6!o#xjwSUd_1m; zYAZVd+}gOH7<`9OR<#>O9kXvZ9O8mTIN$ZGlEG{Uu#(y*pj_syFp{cH-4>FvUHa_i-M6 zqnmSoZ+?@9Wb;#u)|r$~TsvItd5Lh8hnb6jij^)akU|M+j@*ZgtsuVT;lH7*z0{RT zQ+5;tj?Mau`h$frr}Y$2_HDjI8Yo8l_g3_Zey?tMFycJup1X$HS^G@+NNdn zsB*&u%|QNU^OjxOwAEodOThOzSv=c>Kn+h4Uel!d%&`4?1r7D@j$#~4w4;FsGoR&= zIayVcJ_hn4S!au-+JYBa932HbIHmkhO~noIl?0hTZ;t3(;%!z1+y0_LjDKlDn$~WX z?^evMi}v#8_K=XDfdD@$8w(e_T8(C82w1y^A^ehY&j>>XIorQ~w09|&xEz$inmuL- zuTVf{Ud?@U$0aymLD{@vV-FO&8_xWK%t;M$( zvnV07kNTDvx~7vXVw)x5{pp3iF4jhe8Ae^ZUizpLK@1w!`xn*rsgA@ZTk!?WFd7$X zU3j&3L@OIYcS7b<{K=xH}pw1Z7;}}k1mynnR-44 ze089e{gD%U;ubJ|c~Uuu2{5UcM1gIS4w}uuC+Zk?8`vXzxfW`h4VK(h8F?7(jw2Nk z5;*z6(gHSyfEbSRMBhG!M%#*hNn^m|z_Np`o?cN>K-a#hz^}UAUCS9x!pSevx+F|G;|P9FsRyZw$&7A7hNnn!auTaWT=qa=|{)n za}qCE>azh`hfkXWh?ySsy&zgaw-A1TBM*LBOSFR50;nh84+Bphyyyr{oa8&mbe24&t4LF2SYs;pWYVwazzj10?wme=9Jb*MnyE3>XS_UMWx3} zZ~-CN0N>OdLS<^VgFS5Ha>z<1kE)dasxD?;N!h>*tfhpSNgygd p9w45=Axoy83H0itJ7o`2C$g6?st0_Wf71wnvVw+um8@07e*w=S?uq~a literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/illustration_training_lane_01.png b/selfdrive/assets/offroad/illustration_training_lane_01.png new file mode 100644 index 0000000000000000000000000000000000000000..27d9bcee3e1be0f637f09a27b18e172456c5865f GIT binary patch literal 268080 zcmZsjcUY6#^0u)eBC-YPB`Upxbi|;7hK`8z5|u7Z1cXQeD!nVc1fn2t3r&yaKfFl)>B(JQzpd&|og3p;gMGiAp|5^&7ZuvSoH5In_OG}3{PFm)e#~ZO z`;$wbM5@@+*+CC|BY8%L<$r&WFFhaARzWY^S&RO;=YKxu^Zumg*v$s(ZONbSKbcC< z*(A(GBc2YzS(UA0`x;>$>3Tpe-g+E;7hYM%Ej%+%>MxS0+pzu7oqx}qGjwBU7 znJFtK{PT2u*vZwvGy2qHRGNS8`v2DH)|tc+%B{hd)EUip@nf8@_8}`$+|y3g^xv1N za4f`b*cMX^<@bXLYfY|8Aktg`wj@1~!Nsi&}ioKkrrP3vn7vRcgIVQKKAIrS6{gD>@NHTsG6wcMWxye%zWXMWV z>iC?SVzUi-G;fKnU#z>yrQrH99aXV=bQ^M?5*y5^#Y{|j4Gj%Q)D>AVr++v6#rNoy zd9KH2=F)y`S!D1Ta^|J#&}~+Nr{wN; z;!oevq@pHdm76-t_N5Z@7;w6xPKxAJ7wYOXsar6v_VLx34w(cv`SGbN1vguP8m5EX zf=7ca?ViYUCDTg_)uZ5N8?2%qxZu)W$0NuJuVPCp!>qK%o?MOZM?@Ul_+IJ+4=tS{ z+hNfBaowEB3ST84ji(U1h<2pbawge}Y3yaCTSqL;TeXIa#L=Q; zhMpy_~zXQ zYZ0?vMbzs?gn?Tizo}P{00z?wd!=0NH5W}$f#<(Ng^f|_xWJU%57VM+p6xtdl~+?S zr{;&5{C)+6=SERS_WIN+pDg_R=Y;+@=II-qd>OqHz`a1xbg+pGw((jYFjcJ4&weuG zabxA&S_zEHr&Di$cA zHjqE?$eQ~JeVvl|Ln70F7$?J{{K~{8j;ZvJB8Qus=edBtu$KEB}(|`hS zAa{EaIPltQrHN4&!n(xT0n>K(N7DD+7}D>f&UE?p0Xs6-l9K%Yg|5GEIG#PG`LWbu zgYbx<1G+<0Y#f{)EYG{2MD0ov2c!D^7}^4_9emczX&vWodHy1rpdzR_Y31&08m|N8 z40)sPDM#@CDvSre?e?@(W}0T+&_$+*_N2*$VVd^76?)#J6$_pAJ*pOOP>zlUm6fzD zwlJl@*dyOqb8W5@prZ#9QBsRX7~I-wMe%9Uj@j@;rIgXCOFU6;JS#gqF|Tr>(Vn+k zT+{}o2)anhsFCZgVmW=o-6JL6Nn@iU=*G1^oza8>JoV%45yXfw0;j!M_(g|MElo7x z$0HE*;g9~#Zb;EH%WO#*|C8PRSqC^R$F;s)+H?D|I~xo2xuGvNqi-g<@bP# znK(8j%`}Z!+6iYOd8=w?Rc{#%P+$6$MR@9v60^2L zMEk{FERd6Hx3U9uW1R|V>WFkMz;hfwNUksOxIcm1L{WIX6@Q&@rB049sgu8N{CBql zYp``z`WgRl?x`J1_5;&thvY(N1bD=DUx!?j6{Dy1QJCwpkULUZ zoJKn!@9~iu)mKHs8yAmqv~iselA}hQmTcVPI{f*tUMIoLQ;5<01f?1lSJlM%{uxylA~n_dJ_7{o8#NN_V9XM+F3Vx6tQ6legIHY;FzChl3>G$kLrREM4BX|-Rcju^rj|G99PkI*x}SK;3OD!gT| z%(Gys@u~G;a^O*45k*ZC1s%d$S6}IkC*(*?6 zgx^eP^r~spAgM7NKS0!s$4jT-j;kzP1_^u~e&}VTce&hi@|H=4Z0Y-VHLFs}kQuo+ zl^%Pe=I(bc+>u7y+nkXRo*`*1Y9%hP6I4pInGdd&n!k!cXy)^>7o?iun>sEygYEET zz5ChpGs0ps0!u^8jfCCT{Lr6ev}Jo_>wpxsjqkRormM@N#`)j_;SXwY$Ca4J+d=~= z*1*A6U?vy6@cpG}pC^PL*}wBAf%}~KGfliB{9xUd+!$@QSO(#Ry=_wG$N;2Aq4E-j zqTQQzdq-(I1=4lrfdO4xe94q-S8!)%`@GQ-mp!ykhi#8QaU577o$Tr;+(Tum>HEZzS zTvS8>TEx^7Pkm+O6I*Bzd!e>IoR7v$SFk_NX`p8LBF|6H5|ac+M60GLXYCTU&@wmy zzu`#NJZNeIo0fXLy-Ql2f9^#xMChwwf}DAtVzDQ(SJow{oPx7Ie#N-4D<7}Tv~6Gc zz!3J2EdK940Ce63=YXsF9mlsEAH}VeNx{eI7kGL>+h4*SYEe4w?Nr}NMScwO`;quH z=K`+dBoFftB%0_sg3@e1bTgs`#5%aFvcTJMGb+Vd$f#6QpM-jwhZS zo?ji8y*``CIIPKU7^R&eg!G!*<-C%dw7Qrrj?2aK?JeDKOoF+R9(XEmD__?PoNukz zv8aEtu(T&rktAjcZVhaK3pVBd3|^UgO==;p;NUY{yPCM{rDx9w5=kYFKg#7-1dlK{}@I0m5uz2Woc6IGS)o{AJ%eO@R zE!N=1h<$%P0p=&#BQY8a7RHTrNveK(wovNSYj&NbSJP^<$2;MPu6CAOA#ZF-A65y}E>oJGwEw^& zcCb8Gp3IYcB=S|&RO{w;Pl@(W?;H4&U_U4y3n(>s@P0Pd8<$ToFDq&_PwbUq{;> ztV6D3Wqw%}(b;w<-rz~4%tTJi1ACOAzJD=am5Zc*186|yL3WWCSnP91#?3y=Ug5(o zGl7_3n5BJ5tMZaUBbAszxFmv1$X#nnRZfO?$SlUJhI74$!xDo`cO~~9N7pR22IcrR zuEcm?qIX8)$X%?0Ju9!j@aZDUJri5H@MT|fJ)`xsyLPt3?(>x}qHa`~zOyGIWm^xh>9>#v8?V{X@Ke?1mY~zs>!&SH-w7>Zwr6)rXeKWrL zuA8J{F;u(`$Io?N>Fl6a1)dU*cV#BX*br=h@KV2AzO%Wc7R>1XB(B888FW4}lCqJ` zx*P_gOctmtsT6u!JI3oRs2Ywa#;HyfTAmLhRLvJFMQ%miM(n4tLE)a1Lw)M{{loRY z1jp1u_bJu`B)OBtK#o}+N+yj@(zyNn9bj8!zwCERw1#;e|8qfQgUQ=+{BoeY{kag0 z9a05~DhA#ggFpNxW8l*FW|j{)nxQvH#%C)v?(2TG2N{~SIO>~KLTYnO18F{UuA5vHjQvvl{0+D(DBzb!y-RiTsTxh*9ZN)s8U1a~lJAe-8}9UC1yUMtZ)9e7 zh`rUzm|4<;HG94fu6{oBh4{%N5l@3=#d_bR{d0Fw2h5MEy|V^LYi)CulIkQ`rpJ@u zs&V=0?|HWdn_Yfgz1d$Uw_eOU{IAsboo^_1G+Gq3lVs8tbQ1PzE>DV`3o2bjj1rjG`oV z;cE-n2NOswFMg&ZIgcCys^1u%g6Sifr7yrnw%bzJ6}ukn z#_LrKSmn%5tGmqT@VPzQ5PLJ31pe9`n>4vwT}b;x`)n^#wzz4IW(nLlqf~$gT}tQBmAAP&C_UeDuf*6CqNIPi4>Da zxAbVJOxD~z>8cjJf3hx}>5(l-KQHK#pEjR2?T)3cPOZpFHZ6Q&Tq# zFPfB>(9G(%g6q)oGRXkc;k4Md5^Kvs1<=mI_lgap%N#GH#`!Z?rTi!AHv|qiLzo>t zqt4vgw@?PV`YmC17X9r9%k13-ltuB3e9G8UYNKK1J~&2Ev*(iY&su9IPG`$3>8vV! z`%u9FgyL09s2W#jVK1!GAi9y!` z>|HF%`*rmnt^ws(_Mgfz-6ooN;wU2ppAEhK{adjmm+I}(+L?D5>0%{LH_vyp`$q(x z*kjE8AdQbuDo&dE%KoOJ*Z;~O1Tkv072PvOhOl?ZEtSQY-B%(~K0%TV#%wELHNzM^ zWKI`yfVgn%x^mb;{IGj{%m5J+nu8VzsE8tot%zTh5rD55r{e)6kqKvc@eswKcoEV@ z%|h&KG^CZdM3`26!ZH|YWpy+>6k}GRlS!Ux?vT0Gt`?Y>wA@=Iho3*(LJ7%-oM3Z$o*@LYi#Wq4gY^`J;a9k zwkKaolhzqPkOL6xbM$*>~Cb&NhG|}EqvRh+W zu_9>*+gA#rtl0-OK*|nZ8PW`bP|Sgea-b#i0bqMup>N;3|lj>*28#blFPbVj+A9*q@4KnQOk5L2D^Okc~> zYh)+a!k$;+d5B@r2(S0kzOGUyZp{c6%mh*WM3K@R-3Q-2)5)`}kt_*>+-2-a(D@B{ zAb1=De$>BbwuPMtGP<7iaVqT98W#FuD4c*QnX}y5`?4;vu=$SI@%UF9VQ;4id|&f# zWcv9U<1tN(J>}G0g>8%U#UHihu&wbhF4ae6wd0{&+Ke>Q>S_myYk`oRBYK^Ut_2!A z)7AVj&AWSiZ9GRWeurOrH_gY;lfq&?`b9_P8`6cJP#G~db;*daH~ z0*}*qW8J+KcCApfLF?qnd4HM@ocpjXn8YX5UtIP%O!_1A?w?Ay+xKa-L`S@KGsuAv zf?b?k6cT6N{7_E0wpi*XIbRz}}l|>&6*#;wx5Z-8FedQClTm z)8$ZCkjG~&k#!NV9d z!9x3=Zfz?)v}rlM*(S2$I$=F&I3vSblPr-ygkQbaY;k!ab$%oQS7=#hQBS(+zp;C~ z#DnTDZFL7YL9|*+J9Wt0VFZEphU0se*HS-sl)3q@Bmu?VtHs}WhH~%TCms*VBbV@h zF`lunjx?R`8($cyMvMsdY%YzC!dIf8u4t#)oyB?`EiaqV<$7`;2;tPn{ciG|ofY@6 z9hZ1^G>stc`@ma5okz6Ukb~-a;>}vS3N{-)dxV}}Y_l_ea%sgk&00?Tg@BjBphncq z#~&K9PFxQ7&})*-msamLP+;7BVxEIVXJs;t&e$sE>f*`wGdiAhpJZJ0?SzWj(-DdN zCXVOz`4-+zVv^8SwU0TdxzCW3qsKuwPMN#w@`GMq_xWx;ZNn=7Z)UVj{Z-1cBRBbaXa4W3G3x8E;FD4bv za{fSd`wpEBA65W$5lG7Pbtq}ru$Y3I zp4CE%*+i%ZRI6PH4oQywJRDZ5wo2DCrkonIOT1j!K_!V5sn3%7k@+-EO+?*mJ zR6)LBw^MTaPM?8-=jVOxEvHe%ltzos*$1ggkUr#h1?N}|n5A2Zn1#{}-*3d848nvv z1>2y}F!3-@fX7~-VX9L0CbSaP<55Kbv&hcve2X+1p5s0M^dQ{7J6U2fEO=rlnNKrT zs<|Hq1?0>}x0fLKj-5YQ)8$ zR+nd4vAk2PE31f}egm~Vj=Nbhr=$`u``#eC{qwBZUOYNqC-u*3u|F?(e zsCrB@)q{o(rGD`8lizfbDJTD#3?QN?>N>G-qBZX|tD1y}a+pY?`0g<2r6NBkW?dW9 z5b8_u?k$mHd&ep}8$n37ZEb~#=qKC5(E&gPoAk2}7wu7wjVDGyCbJp16s(@jNk^g{ zP2J0>gnMIcF` zWkS8n5=sQ|Plxn|gWs>Pt*;f!cZ83_S+=#;zB^TO?ZpVUs!rx+0flm--+XDuz5>&5 z)Kbml*%1M$pA`cnacUz|!y3)Wb`p!!mA}GF@xRm5wU8s&kM;jfSva%9bZ$(KN!Ybn zQ!r|yeRk>j!2C!<{omS`UUJN*$!jR+C7eCe82M0FyR@x!$WUvOU~xG{ct%bN79TT_ z;#y~Cy_Jra)HM~K(e`WOq$p~q)AxgqpO4zea^vqBKCS`*pGl0M2Zyler#?h*Qbbn~l8E_0EDSYpDhzSN@s%S#3ZkDVk)^)IKB}wA= z`rXX_x97|GQOu}YPD7);1EpyB#t!j1N9(OOGSs0a+OXMK)|+tV1Z(o3fry|zVNyFE zKk>XMW%N-C0|WSYJV>yXdhuu2t7YPVSVJ)h(0(nAG|=3gUVp^!-&^F7Adt>({X3mK zmyJKdpR6!3))=%8(fH_sZuq7O&{zgu@j;+dC&9o}ddJ!BQnYF9E*srxTm5(z-S+G| zNAZVg-z4*DL%t{}$ zDSy{=9?jj0v5k?g07#?$_xWl&zTqL^GwYGY zE|qp6lSs!3ag*Skt*C7bpJeeIOkt;#+r&ulD{yQdol#^b8~uoX7HFQzYlnV4 zH=CReO|5WS0SHdOY0$_XLy<#l`8IOLDhhkH!P~bt;1dkdeLed3a{R?UMxXz0T|5^3 zfQHUXux4Lo8}g+?OY$yEVO}>C`gA5&K)>qRmZ7)FOJb`z^m5UZR9EPjbAn~-^i})e zK9z|ao6<78a9+c=bHnl}4I^<6d1Q)Rfz#9h`srpwI8{|@Sw;S;2bX$o^ahgZJrG|8;NRbrL?YXZmLM|RjVNM+=E*yoc2NkGLkOcxtRu45JKFocba`0D4$z<8NRy=*;~O>N-GVjgsb`xKUA4>TI+9L! zRtDRq;KK{Y#V%TUvS9}&UaC0>u0lG?elfm5JtJ5kyFa( z+{eE|XnNH%lD|b^8Jo?*<$9E>g^ckcYZmk%VgF0+qa9v8JeBli_mLgejk|E{^;@nbmJMcqi7}n*kdG<5PddG0hXN+Ev;!Ofr5Si? z0FS=xSuzE~l!Uy#F;F|vFYJxETkYF0?Lq^p*Y`R+bTvu^kU-EpBaPg$G41_(YKV|I-8 zKc~N6=?;0M78Q8qN~*5$1g3BneyU)&^ipueN-@i zU4{P)+Wr2EbkNr}K}4c+fKUNG@Yn!}4dk(|%roIr1_Ttr9;n9X!kp!&h-w`scSI>+a#x#0shFt1@fw zm={d;+D=JK$$dSZLl-{<=)AKI2ph{W7&J1WaJiLPe;rtsvB{!0nm|`F5Gp>@SzR{C z#NSq|%eI$kKe_3SA8Uyl@G}!Yw|p5n&(|SY9Coj6m!T- zp7*C8!AjTtTczl8oqVY=k#wqv^35x*f#AxGxGn-bzXGOU_DV0&k1~3&iF!vgOwh* z)I&9Vy#b9_aJh1OMh#mMk~EzZ7L2M`EKptSnuomE#LiSrUpNL(Iv-fS8a~xfl zz}SQmsxkcwofe11(8u?98mQeLlx^OLW18E$G-p>i)_hj34Oh9j+)f*`^8M+<5MN}N zOXW-5b@3J~eqi)Mw7ZVUQb4!0L)mRwX9=&p6(1dNDa(aAfkAgVvfWbXHI3!)Q72|@ z^~y^Wqi(y62!2je%HuUAmJY!g3bNAXjrz0daRQbxL(GI`9X9*HyhqJ;h&98%A(cR* zbr~45w$@aeKDAKeGxzPMQ@<*|+{Cm|j<=OpmZjD$uJN~OHv3*y#nX-FjTF=&3os5E zj7_+IY>a93a?_il8*!fYeDJRl>g!ag3Hexb-~w&X)?exy28R|R??Ckz7x`>-4pHU^ zfHH$eYvL}JxY_=ldFdLt7??~k7MxjGxlroVJt}0wMNM0Slu%4>L)%1 zUZ?LrdXo-ELt_-IDTfA= zLrPQeA4+3eSv!(bwVL&i(gtApmD;&)#r5~ji*L_HLi-1n6Ak7ICtio5Qw_pNQ3E6I zn&?{?G!A!;;e8{17+H?5;a>M1@bq!a-C_oBC79M>;?HaAiiof5TW8Py8v1wD!$BN$e?L8SM5wBg`u>6K{DxV{dVx`NIe zy{zs=tOsYgwVMQ74;s%n=$O(IyaTfpgR*%wf2&u(F#O4Q8?;5mK6Y>4S+Ot>Ewo4dwS`uR-ibED)V*lT|%j`Wp*;>b~8DzEq8!4K7`9-t^0 z#B5DOx%D}%&qlyi^r#h`2h4jEvbN^^Aq9bV6Bb@E&52A7&E2_cwOQ^SRga29sz^4_)p(mZi)XKAs+F1)X zC`XaA>D8dtYtRgXa_B-3Rt_qR*>y$Ol0J*MFM=MNF}xD z#t`uTx^fS-ABFweNxf0*6Fju#1NRUqnq`JF7BD`>pY5b&M)9Pp@BIj_c z@|2Ey!}_-Yzb`H&3LY!Fmv8oiwRfG--a_^B7OPC);r2?n)OqmsVmhg2&}66cadC&A zD!(@?;}1jx3#mYb)Tk_gli{U1IBD)933?^g7Ik@0gq2X1pr11(fN|B%f%}f{c*{5- zQzq=w;1Fdxiy$0o?t5yu!|LvZrz5@<-4qI-|GEMCSAPc)z&HiPzb=ut@rU66Qk+U2 zJ>3ZGt0>L6!_^P~YNo6|)J%!@XtXlKJ{a0`ujWxgp?>2b#0a4*Co}8XfW7S^hq8#x z)WFkwKZ|r-1l|ct3RLrVM_e9%YvAsmV(mBc&_7;v>HYbNsY3b`yis$?#8uKI@n^(zL{dWAc@%>28e>&fcg`N2oqJ3G?J# zJR&)1qRXR#r!2(@MMC(QAStt~U{$##XOJBR8{(E;zAthY6?k-jBz6aohO3*|2i#0Q zb^RFK{UjEF!{?8~{(k%f4&B>mo zAlhNtXOhs8!WSKo2f0M4Y!42dIw5V>>9hXZ@HK<6e?3! z-*3iPkWx9+_!o~03gXg)Nm;i5wu;YwNV)0JxVLep0LkVtR1x8uK@yW#1@CN}TUTMW zS8@DGm}(x79)#E&_FkB+h%_NS?T!gU=9k>LnGY665CGbTW=&jtBXF?V)1ZOSE4iuz zlIdHIX^zIn(-;~ged7jty$MkhmnX|#tzqgy7_Z{=Osm%rG^w72%P*%4Chm8RM%g{_ z8g{FeuQ7or7~Fr%IAvsvVvZ&_V0qCHwUoK9e#r~uD`UfiYW~L{Pljb1w1vbtoj#?yA@$m;`!)VMd4$e@cc5xiAcJF}h=LABY+ z{iGTT-I?&@gLy3lc|;X{P7>bZ$R@ZWRcxusG}RmEuSYM2gG5k5H`4(wK zt2*Lg^Y~O6e4wW2qlFbf!dgECCVGx!*~>ZndL)2sm%O?}Z zVygWMa5IWv{zR8bObWZY0(WJjZ~`W@vntmo7UVX9PmRniU!F~_BqL0#Tlb#y%pBlz zws&)CG6DwwX?1UO7$Ik0*+<)VVf=XWkYAWx$)0^ID&r4F?XB%0p12pl zojEW;YGt@VP~G2}>;Ww88CMo-a%#!hQQ7H~J#vx$0TUa=$vQ%=&gexUvCaVGXSKXAEp5hPn1KAvq;qR!&meae^#7S zFH(?dLplWZDtK}FL?%#$2R~IQoL0X|>Q@*i1=$yYtv1k=8_Lf|0Z^RbcVQ{Z%qNSN zsVlfvI;z>qKLXhfG&6N}@}dBT$K!(kfhJg%6712}{$ysVSPKdiB(tUQ& zMx8JqQT%%K=EhyGQ6O6Hn(AL$haF1BO(fl#`j7CxS7gi%*fptt+BK0!_}e|2Lj!2{ z>Q~!GfUf_>k=Gc9X9R|^Bf*1H;8Tl$9&!fLl^~rWU3$u)UFG6S#V%KmqrdkWwDt%E zv^q9gIiiM+O}kovtk(mR5dJ(mtpGjeE$m?gfmMT+VE%gD#-`RjykP#B0tM7kR?QqI zBUNLlaq3)3ZM+^qNy27@u7jXEhJVDH_CNQ9Fm+pHRP%6S%!F z>7nnsO3i_h$nq^CO=+n08%zd`kIuK>9!dl;K#)i6^eh&^r z7xNFye;@*IH;hsJA~uaXB_4xEWNk(tr*8ZzHWHGKGLifQ5^Yh1)EM{RuT8xTsnx{U+SIo&rB75QBd8RwWZWv3x_ls zj&faK*FZiv>2oEGrG|mvJz|@piM~>5TnltnODqZfEckA=r@NZnvScT(8Lv_E3@D3dWQ>n$H%%m zUO>k|eSrGvuKkFqPk>x=FPho&)@jeoP2;i{pamYBqFZGRuJ;BS!rLYH?U^Ax)O0^O zl><(p31!Ds%oBm6<>qj;Yw7Yi_4tEROoP-#O5U4;`=3Z&o65G{)}zfDYK8dCd%v2( z$iy>bwh^sbWsk1^1Hqolh8^MWS^DT~ZXcinmR~e*U%CuAT3JiMU71v0u-oPr1l@EL zu+?YkbRa7oM<2i2N%{*;2Qg29-q%(TNSm*3FKKu}jjl-zo{MDh(M_i(#J(TGH1s0@ zn~*au>_rK*F<=^S<0=KD-}g=?dU|LL)PGH@tY*5VVCbtVGm|$ZyN#!?qg~J(c|L65 zSvypR@=n_(`6oJXZw_4qFjc_6Xa@`GqVR1MzWf%Ds7g@XnX(9|$MI)`=M~X2yG>%~ z^OURu>X&8ovmjO*ARmqnA57g%|3n^i{)0;@-MIv_z5@oJbo~mn9S|D~ia%a1fe(&9 zJK)rE4^UDz=0dPPJ#mfA^cn4i(bJ=qZv#&_lpZ$w###aX;q(Xo;TwH~-voDS8Fk|T z^@XHr=1wTF?rC9E`vGV_76xV&%@3^&s|I_4Y%6V% zpi{Jr$mD=Tp|I`(Pm%8%ug}F|V4oBopi`evv$HFC6vo1eZsn9W0bn9w6s;xQ6HcH4 z(uq6^0N3S%5xD?2m%od-R{%x(_HT-|%yXZnGjZwq7(NG@qWH`|fs2149dH}h0ycz# znDS1AQ)c%2XX==4^uFVd+Qz~d3}Ctry>WJ{<}KPN$l%;nPJ#eRxnx%ZL+l%9CpQKI zIw8kkMjqXk#s{+Qy}ZFy&;#p$wP<^Jo1_;G!C9~eE92pVjz6NjZ4a2dqd7)HBxd-d zMjK-v6^pi?$1*anAF`utH)lyzA5W>Wn5UiD3*1*rc9qru7x?0$pQclgoifOExay@6 zeucEfdeZhk5Xsf{g=||K@F77C;aMP+Rh7iu2&U5d-qCCL;;EF&o{$}X!10AQL}0z2 z7vec`eqp3*fh=@uec(60Xd@=@Oe0BR3ctaAM*{Y-?s)L~z1>?dBx92zBY11<37qWXcWpp9fvln)ov1R`fk(zxJRB~_2Kb!msk7QI-w!;h&=Zx z!{X&$6UPBf>x#n8oVXI|q4|0NR(TLz*h$&9PnqtC<+-vkc@c|VDe=0S1=3=q%e+~J z{4N6qnqUMoUhYG@Rt%?%kkk6UK7(f-Z*leo$rw|eh3}+ z-A6LepO@fOJ&zYBJAe(90D!oUH%w5n%jE6kLTR2+T6LHcd~8NX^EKsq_OIl)nRx_z z>Q5w2>6m7`^m~fTTBGUdc8wWz#;aeKBa;C!6~xH$*81!vb?HItCzQp%yP>rk!tJdu*A2 z-KgXV2@B?JSHIz$HwBB*GA0#cjdcSecEZy!DZ6_SRk^VC6j$M>m9PhOaE70b(PDwt zE7T**g?Osfv+v=(0}=ulyVgfp!%u-=&sl(1G%Wo%K$^-14j#CE;>6ldz{4(n*il`^ z0z(_Ze~9dK_J><5hz6zJSaCjlGnG%IAMk0usa>p_TRnCyP56L+o2?g^x1~eHBj0Rg z3C#&h$y2jS=#9$fniD7N%^9FkY%B7v6*K9Mm~XEdl~SY@^fuzzIue1V(Dh;3pilrc z<+K7V_}J3~`V=XsP2G#^slYG1+8-^BLoZo%2;>5#M zZfI&BUfm@sl41&sv>;v*Dqn+$#{^%=p>D=8((z2Huc~%TJpF{N$YTl!7oXIT>DXa7 zYoD^x^wx`WC7t;~ptVen^_e~&pY9B4yLIKIG(46?c6-8V=fUND&>^2zTls2aka;-u zAV3ae?Odonm0mUOs{u$++Ho(jT~O+`>V=*|T0pUXCYAUHEy~dQHu@;LM2e;p0q{OfiVx94LH}qcecpoDh67VL5oV|MP(1bOBG-2XzjmHsb1Ja zu_3kGR5fky4&S+ebHVTJn~&m*FKdB!4P(0j1|?08sP!wuc2@ zR*r4F^xinLTMFTXGnD9RO|YxzReca#98;F07E_jDP+~7;ooH`W0W_AxsR?dX5&Px( zsePaFL{O;nt>rIv?ANy7r>MELMDBs?`8vaO>Mc>WvTfx4@)cX<&~L)=D}mhhmO6)S903L;p!c%h9-4@} z`jA?$0;BfvUy|fHypeWaRb!DI?ZM2Jx->jVUmHcQYeX@D1xw%Jt9sw@zAx&vnasa> zGwnh9RZZxIswrpbR|gF4+;n`ejbBXSy8O6u730yHM;j2(E)A80xh-k?lZak{6stRR z=vpGwf6Rs@$H6jwb9~y!wzH$+^7b982Yh&I?4hejGTOU>1=8&NHpUwXQ6{)HgRG6Q zm#$;a?}-N(3^+$FEqx{*ON_oN-bUcC&#U1S0XQ@VAIxpOMa-nfqn$9JQ44>3-iB|% zI{+sTw<3}dvsNKddG#;s3*78u`3GjNaAA<5mw)BJJAI?I%Goz9x5Qq8wz8I}Sq9cX zGkOVeXso&&B56vnU1h<%3*<(Sp^>MCV>QDmQqjEXfxMYo`#&T@@5%0>ZxXQOF@Mik zKRk8#$T(*9UpwgJX|j-f|z)iEh) z|IiplPQ8i&LR>lw1n!8z?f@n%ulp5&oywxgM8iB7n~g%QAy(Gr@q;qS?N^zu+3pXr z;&TD(Q5mLK1rh?wup0PD#Ef!p+M;5@UaX>7fYhp9)v)tw+$nLdvpI0c#^=44%Ykvr zTXM@fb*`m)d}Hya|5&FG>PJU`7hH{za`BDkJJ9uMWwh&?m_-$j$?E}^SEVHDHon;> zuLihx=^f{c8BF1t#EmCYP7 z7z1=pw<>|Lq$vx@JL}Zy3w5*+%ji3bsL)XX1fiPy#VG0ARF{3+WG-x79Qp`;akoyj7_c zy;hy59M%q3;W+DU=Ud}0sj0W)^|S=73HfFMsy?oL&WO8D*Id}ZL(ck8*VX}Ianq+z zufaB0s}WewC4r=wUrjPJz6>$R0DxFB@UZ(cqrtYTOoA{J{ZJ`0O2$Gb&u2}Gquw>U z#6=Q%Zq!~X6Zbwf-avL^!Pr0Epe@>E0a_Mu&bYJt)fZQ{wI(_>=_YyA1t{xr+cwb! zEt$9dDjzKuMN;&>`t(dk9` z7k^fCjkGsk+q-mYtC2O+@z)59xbQLRO^@rD!@oz)|GQlsPXdlqtB{0!g>6)RrXMg# zx_}^>LJ>Ye^@Zge%vT!2_wU}8Hg9>iDPbWNkt4sJ-j98og0zKpZ@H>zpkyk2HjJ;( zuT=C%OqOF^Bmyf_4Gq-(rfKJlw2bIpsZJ*v6M^wk#{pm{R}7B@hKtSIO8j0t0h&W@ z@0t!vy-xHaflRn>45i6YSLh&Qj02_j&@rOsy3C5Hz|O|}pw~4z0x)Pt#e({Nn!w>pBI@ENoS>nxlvgw8)t6L6ME~UujZ6n!;qVyOiJ7cvb z)Ic7q_o&?i_wN#Ia1!9jvwVRG6_# zFO0Ts_u*R@(kpW~2T1Atzz=r;KJG5ioNQZ)qMD%amoDP241=zdj@|H@#IqEVJg!GO zXT`nT^ZVNa!Y=z|vsqDLt@ZyL`XjP`aa?;m@w7-SZXc4Piu1&KX2?N~7S{qZRT*tj zX$c(Fh*ZSUz5UXu@4q``17iZQu# z`_W+Iw;@N6&66Hx1JzRcq)%Z$TV)3qCvI6))Px|_%^{6R+vY@M%_sCkyPu)KPCUc3 zwI2JB#%Qx92r?7gxf2c)aXsiq0Dgj9sD% zd2UjZD$K~UUfZopAQLrv9A>3SfJ!}( z*;Z?6s(#IuK>VTzcp$wgF&^-o!3t-iau|h(lnXrd9WbfUsBk67xOzr+X5|dkLhVuV ziS*F&&Qwgv_|8Dv4=A$V#w9krzmZsRA241UI`0+EuL>WZuJqEVU2ZmpnDE3U z0{){o77}K77x=P-hzQlTb0xEu0SV8SwNxF`_8>@a?tvWel>|gG$)~E{!nP`Ijy*6O z(fU|Ywba^g@Er3(HnI*Ex-*-y;;*)CLy4u(`4@G-A`DMFT|?J+q7Bu?>FEa@VK$Ce ziYHSiHQ5kJc81V&NF(rK`wU@x-5u2~r#wkjw8LOXiTpda$-In|H>fztgXX>q!$!%& z>cFNvtYo0K5#ahS1Ee#d!AgZBkosuk$jCvkOqH>jYx`2R4|x(*>NHk+h+|&I9cehV zF=+1bAMNzd(%wrNm3Tc4Obq7tdM=MO5f5kW{ZK2wto4YvwaUt81@PE{V(-D+DLns~ z(Uew0$}26$?9i%Oy&$|r*P`br^|B6vF0xt1JhJ`}bKLE42Z z7~kv&l3FO_bb5PRRno<8Py=zu{|p1~-r0%_rv8me5e^Q-<@3g*UL%p%8r+WP;4LW3 zrddaDSQ2HeGCs+UAbco`utgfQ9SHli8u9NdsnH|kw_EAuS)9VYm?LnaYt*XxL-1<= z%)o{CCZO_Xy+&XG0xC-$Qt|;7x_1hj8oO>d02j(#k8xM&s}*>!)-rp5vwQthSj=4@?K3r@3$RqJhbEfAE$#L)v&UWA0%nZS;fLhq= zbQ+8x{qXamIo_1lT)E z*Oe0^QLb$xtf@MX?Q27`hIuyW-XjqXJQhXfsV_JOrlX=gJ3W&iV^^g{)Z2aQ2&$~o zpj?O6_|evHRlPEEpIR>#quKw-E&K-iMU+OGZjm|c6lCc;JcIIy z`mN_@j@WZG`ktPxi2Vll4fDGH5$&BqejP-91U49gfZwh_z4KHo+r}9E2HC5D z6d2|qSKmNdH4u?3R9PSGSQSYpF)>LNs|yjr_owbE0e)u1VoIpr`=Sd_tFIXGcIG!b zv06AAt=$V2#PkHDU29%ox>GF6qC?6fW@C|5a4BFoq+8W@S}9^?{kwbjDS?Du72IO++qrdxV-QqxVqWa1O~g`))43`G z$M$Q081J1fr|?4u4)k`#R&B9TYspDs7D2FidoAC%{G3aN)~`eh`>U*Sjng$?yc$w7 z?JXI3h8p4VEe2K7GJ|e&Z*$O~gk=N>o3A3LHd^{T_|h0$#eS+* zT!z$F(=63CwO;XTgr3Qhd-c*qc@))xefu}c)xv~L#;qf)}B@=t} z)S2Dc|MR^+zbx_cTHWalojcTk*`6wtpw;(-4sP#*M8_{e2PyEvTC+OYsFQmg|4ECx?2oj zxV!!Z-v@f81}q(wF6t<(T@A&>IyXN{6-yMDNHKGBI|b?zsyaXF7IGpqRb$+X0}gp9d7moQEhsp$*I0l@y&MNMFL#y}hmzhGKZd>KFCcK!p3i_>^(C_Y#@vIv;N2giv8c!c0ekh^Cci>-)dn^5 ztw_@>&qV3+MEFksRQ?&BxKIJBogZz+&(PNLD-{NX6z^}+m>?2c0O`@5LquQg#qH=Y zb$crt0^eR|PiIc}Gi+_oMyI+h6v#k60Xpu^>hCT(qFp#%x9s-h0o?2Sr)*P7QE*)p zgnhO5n_vW5-RLRwhb#n7uTO*-pZ>HRUaj1OY!{y-vV|TKqdwG(%1Pc0b(waqTH_JM zN1?@BH6y7xx0OShyGL+9?ukUJ8n!^6Wt8||=pk+cGEb%abkUHL{fEaPcistqX=&n~vvZw)Am98T>muTk!czWQ_Ny7=0gD;$ zxh_OWv*)-^iL_4}`r0qSCV)K&=K$sM!!YFK>ltm%6>B)D5LS^iOKHmQ3TEv!Ro}!T z;!jQL82%WZRc8E>7cFAo8+Ss4zW9QRl=n!U=vQojgF>!aA;s5{w$tYsnr$D$#Y@=y z@X$b7zzP~o5s?gMFSQ|*UkLHV0s|uD17kCpK1+X8{?ob>bL?-bEvd{G1_Q3e zuLO>IE8_KMzmhtHGP=D{XVec~4?Gz8&fMP>=fBvS4_!Fve@>m|xKU_+u>x>T+ukrh z`^TX3Cz`aOQ)03HOd(ixf3C_%WYAV@i@_<*Fx{M6c|yF_)>!qYd7}Vt z9P9fVjghIVc|m2_-e>uhzZ!L77gHP>D_9Ks!!4iMq*5Hf0?JtXYd8_8NQ+M)+LPt& zff-k(bh@!(+@5Z`L9qX0J?hQ90$J~cT7n_}sQIMiZVz-;hxD$t1-oUkZW`WHSx3$6Q&qlQ$ij5_*O=cA7s?3>T?0pn(@Kg>FIhvD;v8PjmxL7-vpxROl@A zrGox4{l-z`+P~I?|53`v=&cSltyaID^t)79sZ->!0USCc85CD<`SvaTHTf8e>wemn zeF0I2t0sn@DxA6}bXPm}q==l0dDXKh$AavJrHJiu#PDnm0|#Ifsu82&Q>|>d-D5q+ zpXptiR+!}F=UYgD3}{_zvrT&Iohi-0Ow5$F1gd64YQCsp>*e`)JBWBJLt=l#JO6}K z=k8J>V&u0ma}Hq?IoYh7gY=_u(ySTs*_~&>sXL;H}S=l=_s>N83kd)$MSb~+E z4kPIeC@`Xa7DjV^wLb_$ZLRI=k2V2LQ2jc&>Gnp}y+p`Z?LnwXya9Cd(!bNuUz`vH z6OTM6Nn%#H!_(~Xj#LGF3+USHvP&j{ZQ29U_tiK2L$cq}r8(-=^0a(i;jk|eH00cA zDSH%pMVhgXXi5Dv%V;1w#|x4782_4@6YD?Fy)hWDn398J8BpVBni;e2nF%<@W%AZH z3*R%NnV8y)Y{G?cxEFid<{exD)3Kq2WvaxW~ zsELc6uTVnawG1E`kpWIlN~=>5I?J#LWJ54>K#U~*vrvGsdHa+c*W0PmnNWP%KE#}B z_lHvN241iw|B`SEbAUx&_M-PA`Lk71mU*^hk%m^Ufkyw~Lbp$<`xGOcJ@!Y3#A+%y zD);@+Q*zHmv8x=@tgsruBDp&aoNC@t;U79I0?P@d%2X)>;8vs9C0!45uRQ1})8&pL zb^qbpGbRZKYct;$^*SlVpM47_Q%)9Cw!{Z@9B{OQbR-zUlqAF;1>vm*)1$)c(6>^#+l;as6G>_omgt3UqNDE z(+}4@q(+~yBO05-uDI&VdnrQ!A6?LNil$*`dRhh5=6qIw-n#=SnZS16kGc3u+#y4j z1I&_2)xQ(gz^-f%%2$|wcep@|-)f9Fc9I(VY!@gv8AykdQ^7{aHhZ^S-+csUeTOTn zAg3ffi0vrLx}m~@Zai7;`B}@MJ2-gxWDnfm#FO$FT@;_uGxZx`7F=~=Ur_iF%r&Nm z$eC&xYim9!GH*-k0}!ypH>hPzLss#~;9I)K%11jfmt*#s=h4OE)0rzfEPiZ1&+aqV zcSA8UnQI5lSju&j%Exprops=d|itk~^GAtE$yI(FLef$P&LEgW+fucM0D~F&=+q0;c;p}i1stA9lPXuaDT{O4A=h8Izl8E|^1l}RH ztn$?rxMsurr298>D56i!c8F-WvlwMq{PR&9BybwHGAZn4{wI9X%yUTqS8=SUI&_}2 z;yeF6eQ;Edd|8{y2Cw-+n7df5?49_pwc0dQF`S4LE&3}MuN*~+{lhhBOcHj;nH01tW(h19u90Wp>^=5&;_K{}55G)J1@$MAH@{a$tlN9J{jnkFb+50}n`s)h- zA0(71g5T}pCKFmc1d2Mv^bAF=zy?lN=s=drt$+}inpzD6X`_K5J2z?MmSclqz+`cL zFXOmHTS_@tfcyOcnuM1(I}wMXe}!>z#?_PYU+Ulo=;dC_^MY@B8?EY1YDI;*Z1Zy1 zqEpHcLD=Sao_|&$0a~&6gNOUVjx_Y!P}2{@wN|*gJ~2Oaw|(df<+}ICy3+mluF>6^ z>UIviS7fZ>pj+GSs>+5rH6Kmww%gMn=x%*QStIMS>aRi-cqT?)qN{bThqww73%-do z><*DBlN;66WWEQgn6Tv7MpYGv5!s@54uthyTm>Z3VvX zFxhruXLb3C5pX|ph8*%4@g_>e$vDsGpJH5>5`?~L4@mhgmi*DwGMs0K=ni;(U+aTJ zH+aj#Et~I?9pd^r;kXBe;c(-vp~BvnscLJ}->SpN33X)XccTHg0Q_}4j_e(0)c2!p zEx&LB$Kh;!YmL(G^eZ8 zzU@R#*>#-X?_JGHhT_7uKH)cQ1{Cg&b{fHd%mv`&Io|JOghyLPu6SPYKd!_V{WXL~ z6GwYbqI{iHnyStN@)#QT_H;F*ho}PRiD;$D&|^NkH4HNIpk@5^z3ruijn0yu*Y@8B z8qrrxGFvpZeV*A0&!T)Kpv-D3uG-8xum)`_b4NPOmaHW^0diUMz28yybgfh-`#WE1 zXhxnCi5Ww!Jxg~1b|Eeop=g)vZQW1bRV%GkaDiPE31Qrgxwl=>j%B@KRg2d`?A!1> z7p5k^$h`x`fkxk@t4{)F8t2sd(S8xW;8FKw8-h1ZvqcrBPWy^#^sm=o$wiS4OuwWg zxtHw7CH$0-ys8zfXeEeApYs|7Ls*X-*dbhZ(WXlUau>todBv3skF-GxAU_53|G-x! zC>l`N1ma|I6eJnrwaib;e2yAHm@&kNyk`XRI#pQ|9=GY_MokQIDdcZ@+vL?G_h=gi zN;&)+lxUeZRZgfr+o^QVdcl)j3!O2(?Eu&Zdk>!oSXFtLy`q-}e7r9}#aqJP@Vw&G z|3!?RoS4BM8fhIpJw*#`&&?m74=rlm17PD)k6_8wD}%}}8$?o9LTV*Nc*U>lP4L8c z3YWhK?wT$JBcZ&^$4@G&gQl;GTCR{Up!0;QYk^`_e84lz+&61yidpC$eIdi~>BhTq zrdflWr$}GH@=YqEt;cG3Z$C_aKu3a`!2;gy8@%=`;+c80jcIHYG7>yKJYHuQNL6oG zaHs!q#ueL}F-iH3qP88eF)?zSKiVlTJBrphgVrgJ6IfyTZ_VL7?B(R8TEja<6M-$% z)a)5ppw`(3a%+XXUwP7WM5+r+-vI{`Spu=uu=tmC$_;ItDi5XdLah$q3=11zE&ca5 z&ssQJg5+(Uumg zQ9W7_-XND?(@Hvj%h&iGbyDsD=L3S{b-(^cD+LUQik-m|_x)}#dDee+n92bN7UjIN zrYJGP)JhX7>E?e7CXC`t4VwDol8t*r(oq6fE^DDOo?ZM~%m)&BEP_bkP zE9MN%=+^9`!}e8^?S>Bu0|@iFyK%w_l-ATe9HI%X z!C&EK!oZ$CdLgZ4YQ*?z@>g&1yH%XAnaqx4*!6Nv>8vV&g`l5&l5Xj=m*3BHKw^-`l;XC*C@5d2S&po zRLzT4+)NiA-Oy!JpOd|x?G3!Z&Je_kD%#~Mu}$O(bV*gI)$igNUQI2-h$!SI>wmE= zt^Sj3IioL_bxt{8(vI{owC8|*Uhl3fJ82jCQoMZ(u}E z4$M{z-o=jnR`cSN5&Mbw!7@)LCVyb%v%D6lmtpjzkw5 z<|lx--6vO(c{Lpw zI{S9ps<#FT$X$j zp8cwyMa_x9Tk-Zfu~8eJ0IJ!>pJt_sbxGV#a!22wbmTIKDDBUg#oGH{3cxKEOsd>j zTYSewmh;hRB0YA8Ru#QN-vJAY9%%X>LtNk14O%xtgB#^i8G+4^I>Vtn;fkDdgEss& z8Vqn#!G#iggfs<7!s`{RJ40{U1MKZA87;#Z_3Sk}Xx9Kl45W$=R(E=aJ%$|5avKTm zI>YjkdWdeJvVe)S8q_Q@=DCqkaNv_PHf8-%PkgbrEoH3Zy!tJC zu@pep?fMyjv#u9ORpzvIxfH=!Hkz=Thi&*5%2~_^_?v*{Dwg`E z!;3KjCGdPpf6%a~Y2gANo@eIH#^+f%>As5gx1LzYzC@JkYjYQI?w@i?&+i$bs&XHp zs2a2Wmx31GAU=>Tj(N%uhCzNk+`mdC$q?CbqM(9lUp~60{tr*hUmA^vM%*O6ub$fQ zeeb{!)H3r?o!b`3uKNB`Tyqz(KHY}ZWEgv49KPQ;d^=%AjGgh>{g?N03UT4I@JxoB z=)njzTqjae=-hyR=eNs`hc7@Ejzz`Ww*gm=zU!K2MNpj6mKFAk!A$NbuLisA`fGB2 ze0alxTe2)ZY=h?LFNH8HJ>?o`*}2AbjB zu5B&YK~~I}d$4|GcQJ47_veYTpV!_*)mc*4qdY}j+A~bNo}F2dTPev_^?gd;CU?#; zk9p`&Nme{CmT*3pV<)ZyqXq$VZ(fwy zLSU!j{QK4i(06*k?lel9tk|rxwD|xUBWW1|T3Rb63&Y}v{F?DC!dCW(!IAd|+EYuC zpFS2L;WalEaBQIyzg_>3`;w&%@ZShKwj&8YEqvf!_~Z)vSV+`A!~y)Lj(Wk`rfPuX zd*XvoO_le~Tsp_K_}C%m>PqAM=M&!60I4v{7oF?q**H=8X*fxHg~K`urD0JEA1aAl z35|*`GM2drSxQR~cz!m0|MTMgyjV!nyBlliMg^Y%DFpb={Tm!j>k*U7mdmk8K9UFA zf3LL;O_eT72l)LrYx&Vz`JXr1W&D00lM?p|x#s;6z)?w;}N%Izb&E&4j7hnLT7Hvtm! zt3)jAGNz*FnSfOv^^T?oH)tGWYv^YiW{(Br`u@EE-eLR2F%NltHlyyr_8r12(&41- zQGfq@Aa0*IxFhrM>kSU*25B^vM(4)M{AJ>mvP`0X463Mqu@D zd%eH}mK~=>N zHa$VVOzUP7)V+E_Jw8-Z83kjx=h+!L2Ob!ESP%Xccrg& zP%i5pWQ3}t^sA~Z|G@oLE(4Q0%U7!vk<+^YPB7pF(gwpQ^_qb(ukHO=j;o79Mo7;6 zuh$o&1%i@}-PLxur^A{TwERV6F2&qdSQC9?=v%s`J(`h;m=_}6&I{2}2v}6+VCaNv zIwqhRP)t0PGXt0n&UDAxZmXgl-9kAO;VO1u@D47+B)0R<%o4Luyh`;{q^Xl}zSo)+ zZ{>a8`5^?hss&z72)~Wd6f0j9f;3@X@S2MY2_JZ>?ClGjI9(gc@WaDI;X%C?hXlUS zp5g?!q4~7GxXkr(J5R5*gHB?o^7}kzPC`EU*NZCOPC0w>H=3?S!f5AVqen#rqo@BI-^Z;TwpepK4!3FBKv^_xVRW?a@L(N&O z86CZ|Nx8ab^cnON$4)JZd^T^l3^v+J8oRl{%q)`m)1MK=I)PU*Y!w1H0>~X5XFBfe z6o~vig28G)rge`-#-z|r`z&dZ-tu4LixV;}k_4P-8(@KI)xd_kUqRcY!B@0i3RR*> zKNTbnv7UcZBj3O69{A3PSuSZQSWqD^)%BC?&Ge}}J(lUlpv*kx2Sw}yH&u178DG?J z>ADm15%yl6@em8g9f zFf1NFvxKjo-SmaDN>pn?T)v$v5#)1R<*&B-PFNk0iIu?J^b_DIU3zm1+e%zQz zXQV=mR}K+NDc-%1`&3YVH@=#ZpifOuMz_g+unpVA%dwNW{5_U4bL(G&-o%y;HBl`p1B_jn=_+B$I8d5Un$dG84@Z zpErbj4qFr-eVs5PoAPY53Kb_(v059Ut*}(!;5qxc??lCk)fAU1aZ_)7^A)Kzd2#J& z46fdOu~la?c%jW*$!n(X2X=keg&`5j9pc@>LfM}GrO-`a5!xO|nbuB32!{}NONZir z`zg=YQq+2}eHz;L%@`2VYO37xsqA=}fu04~C7W$_RecFFuuMWQ5SJ0xo;uIvPMWULz2VPX z$veK$0QvYb%K(I|gTrxhhzHC#Bq<6TSy=w4Nwf(+tFB?+>SPO}l1H*f` zhjq=*1xG)@!xgy?S6vp0VOD2lcFJZ&uPazwj2cgUcl^=z*c?aGNgb|z{6rVV^>iZJ z=lYCpv6a*$n4W^W(jyo3GHR=5<0tLc*i~Yt&=~0`$?XOn$fI@SgK-Uj_iCM+ebeo^7WkS@8{VV%II|P2H$l4Y}xpP3;m+3dfpTsb#bJI*&tU!c3m&zh6!o*=}r zcJs4B-EZ};=&0}26CW`-pNn_n-J$OE%bB)jGk3Yf>g&*xnj08IK@F?FB5s+~+bPtX zWi&Q0do(D3la{i7g&4rF4W1b0>}m;X3$B<+;ZCl?|1iO<(N3h?L^Y%-CRU}5&`?mL* zO%}Sg$(nc-7OuuPD*4o_4HW>>7sI9PQBv6gC%&+Mg7U)pO#IB58KWoN=0wrWqTWJb zS21z4lJl7rlzX-;Z6#g0VYURXzQ4~#&Mb8J6*|!LK-mJqyEGNNQE=Nwfu%h+NmGdz z37Uw+>em{nH5l3ZWf@^*%CI+>!DW)fN;Qo-zDQ~juCujQc|*G*x68S>)w?WLb)4Zo zs+FZ<4gcmK`~Es%aH#t7kAsZ-w_F_X?TAO0Z-g!^isD{*W<%BIT& z=}2Gmd=BX=(v7qL?J_Gry7>jTz_B%s~&osaE3INK(4CaYI4D-@jmi z^UQ1-gr&`~=0kbAFRUgfojN~RDm9v!$j(RV^V&$ZZvXIu1c;L}oa4576*H+jBQ9rh zimpTIA40-{ly6OXpB@fcTI+vRIV8V2D7#JF==2(a$I0ynFF|R^JO#U){?QfvWy>Y- zkq@$Y(>E3f{g|V;ztZj5Z-@LCA7}i#nEh|^l`c6_^n}Wtx@WuqDHa(n2GJB8jLJL$~PeUit(5DdG4Jq0%HEKb|HI{H6 zbWh}5g^oS<^j!!cM=`fF-+w+AFtGSV9I0n9T`76(S)OeCc_T>(1 z%H6hYV@@qSpXxDxc`k0Cr`S_ddxv2d@KL)%FpBGqBS6sM0uqFJL4U4LogA^>FH2$ruOaL+Z0s208L>^MgV}rqTS> z_?@R~dv_OfwY|J%v=;_Cg&1+etU~!TZxUI52<5jkK7vBGF6KA%uLTk09NCv(=*T~dIYyI)1P<>)FW=Q>4gYyrNXYoU7(sOEF+E->yu!rURZZIU zH_jWgQNftjF!aVydq<`Cy=T=6ptlcXk-d%oGxMR}7ESkhuy)!7xF&e7I3XS;i>38? zG_3d9V+f`r&SCE>9PjU$Mk2f4*sg7kk!A%-i|od8L+MZgIrQq97bAv0>a@(jv|@Zm zj`wf|Cv43~4g1D<%54ohj|rqv?f_`WE*o zte46O%GS;;BGwvN>dwyYoTILZ?uw#P_9C%|&&OY#bgZTb= znE7X%as2o7Grj)JKHKo6gMarHV6Zzr4^cVD7FPlX6s_K1jQqRHh#`Ch)kHF(q7IEY%E`r~(0 z^Z>=$>iz?WoCHjN3-f&Yag}`-%^UUnQ!f0c5ea zS5fJb^r%&N8|L7~X^{+BBEkavrzjz&D%3AX6tb+U^Y}e0TECw_d~4w@Z-A7xII$we z?wJOu>pG{1bLh_a;#e6TKh_zY54J$#VIcj%qoCKiSy~vZ`s7&Kt{g6CsQC_0kXZf^ zJ?5&lRLQ2E8?9YqZ+1bmhUw^cSsL_fm|t*<+eo?;Ci_hVly&;4MKH$g*O>PiGU~1J z6ZNySsEJt?&S$@azZ-=;sKj7$0-kPD7@lm)RVjIZ^Hb;iPhyX9OH)#}diRc;k~SG6 zV!)HXa5xJZ=_@IJWs_52C<*y*LrFOEPmbR4S5HsS;`FXN^ew-LlxxRSf%7!a*AG2J zX6>c+t~jo)Js%m}(;Iy$t;L>r=J=svWb71=8iAu>qpt-iuC(}3=mBpqJLS0__0m;` z2T|ksUd^AM_M}U-d&D{8UdxwN!i)RGgzApocF_#s>U51oJvai6=YAJ+ZOrEHDqc4j zDzi_r7GG|&S6Yi|5HG&rW%VK`xMkx}@Y8#(-Tt10N#d0GSG>xdB@Q`4^m=)}yAwPf z@^dt*-?qxGPww`DZ1%g0A9RIM7QR|WmtWw6H6U8aAF`t716-V8*@?MmdNy)Yt|;1C#sJDy&g^h2M|fh12KC;KX-@yl-q^N7sYE| z%5|3$e9_JW_TEnpb1_`XIcSgF9v`YM`ERYogU7#E+Gr^?eqB3qdSl>#U+f=mVnTk1 zaG8wiGZg_iHuD_QXTxpF0oDkoYUX>+y&PuY0rf3@4}C5xWWW+=|z_N$RAU zKKe`rUKC2ZThB*vQ%FPGipO##)!WF&R)k;@!|3A|=fJhG|~Gh9^L4R#-iW_VADhut6PKxBuLBQZO>E@z4}+wdI}qbglZt6z04Q|je7 zkft$yj3Vx3Nh#EiiCdcD!liR~3LF1^;KFB>VM;CK$Qzi6rcAs&7_&hK67Pr(cs&tH z0v8SApDOt0%1Vt9U0*@i&mWaRU+I*!jLB-1TmD!dkwcdX723;_o+jY*)}L{YO?aiQ zPQelxoxh~ge0V2wf}fVRZ~Fru2Cwxm5!&)L{srvq0FFR_`uGkZdGExEnQVYB8%7aP zuGvSAU$sAk(9Uk~QY6+tU5?wi>#?#z6rwNX!A7>>$Kn+SR&vC&Cz|LqLeV_RoPS;; z2)Q3X+U_`frcoC6)@%C2d!NvOZ!OuU{KyWgh@xHO!pD9T`q-kn)gqaN)0`A7l&H)= z`zvdh9j4}?v%Y5iv;Q*y30sX8e#5V2=gXfWKpIUzfxUe~f-5$!`OCk(0Ge;)Ga$!~ z=1-zc9p07?mH0Ktvk(TnVC{0e&hz@UxY8Y$VIFo7lamjfcD%Lcc`CMhZ&nk&bA9rdEXq8 zKBr1)vUgLWw>6P&Eq+PS|1&&+RKl_-jZcwdX~})r{*o(%IK{`ev(1rzLk+K)%G6B0|#gpcbQRUX2DS(DK5&#Lc)vfzhIy#`-4 zk>?@?*fD-bSv@|Pnwo_yN`vw{`Hf{!9PdP;49vj6%vU~R4a=Qz$~Yz#5}lFhyw7<{ z%aV9O+uOX}dhd!Cw?N$o4x@En?j7rc5UrHO9j;-Wq(7tv6Uor zYdQaTqj}L~Xgs2w$JDK_R5;O7FkV0zr#pO)pvc4F26H?OZ4N5Cv5B$rQA9Q7^xfug z`)H2ZH`+&OZt7P@`o)-yz}^}u;_kS1|Fj7uhK$Wdiuuh9l(B@ZU5VSn6z%SznwCjA zHGbDwvzJH@0K!y4`BUjA{Luv>mZ!X8%i!zQc>0T~>snr;XR@j_)pD436ug)d==Ex*2%c~%4TJbqQ=Dt-@otNE0je14BYEdF*WQ}hq)zsl` z>!OL|a(6V$`y+?nCI8P`r&HrVJJn23CX}tD2H7kNYbMqf zdQIb@Ri&7sGp&1Wy2G2@jehjunb|1U=^-zKBCa>0jXGJ+6yp6Jnz!|5w* zLRnYxpF>9-p<}s5PAlGmv83ooEsuf?KEWhJF{Q`QvhoiLKL*PrmUEpbm3u_>Eq~vX z{l|FG_~7kQYp)ri2!0a$O;z-M?4dJ^fdx#f+{p(`Bh%(?+_*#$e zU1lNVzG(k5!^BF6$-?L;U9(S-pRZG_go$IU#CzGCbFd6t4Ue&676;G)Uz)pCRz={p ziwWCG25BVKG_PbVCCgpwQp9An?VD=na>A(ZF;DC^=jdxLGG=gs(xO>mtv_azb;z$V zMzxK`?bdq*%JMf!iT52cYKDZ;HKdc zyD6uCS5*z-5I~klS0e}9wJoObC9wiaHzmsFeevufYf2tFTlZFTZBfZE!NKpT8&tn+ zS!KRr9Knk@qvU$xAakF>vQpVI|2wle{4S>7dT5WjthOmaVSk8_JkRXW4uTbqZ zYeKBX%HMC(G6!BDTUN(H-do1}II_}zdW`j9;op(`Tl!Bd4wuK&Z>@U- zvRI1Cdw6DGM6@7(k2?7}LywrW8@G<>mu>lJP7YFRBZQ(Z-QbRg3^|@tK-=U-h!x#h z?$4dn9GVMB9~7snzcYz^CQZFhV@ZTQS*YZDViFIFVa&lteDu`f3hKvCTp_o!bd2=VgoY;@bu2E>0?<=_k;ASq~*`RSF z6?E8VnYu1IkFX4C#{v?{#oV0LUXj*Xr75^xT+)-)*R1%MNQrC;svw(tq;1a5vXIAU z_Mq7yemoDWYw%Lqq}$@pq7^Jb{kK03qM&B2HE+B+NbhXo z_fYxd+xRq(d7m#6=S=tAJBP!Et;^d2NUcPC0X;l^(u+kfdZ@jzZ3~~Yod6D-hveuq zzOy}hH{qOj<%`Cj8%>LhrFiSY(4Vcmb$7ix3@0B&H3V*egzT*<_89Ng@yu)Io4I?5 zwq#+BO{BlRA0h81x{`l;0CGJb;4S!?{Y)jXPy0%her{c6ZR6+cOL3vBsB@8wn6b^J z4g>KEqWa794Q^faW@eYVRceb8du#0vaA+8Me6Ek@b6kbj^P}<{sOxJq z@|oV4QMF!(|2NvFeRL&s07VTP@ZS(!gyM-upaUffF>>q1>sCXLC zIv5=$Lt%$@6?+8*A(Kq`o}aY{q(#` zeDSJXYIT$zX_M@rJ<==11U$6TGb&XL2Z9U{H zhla(_V~#yjqv=#g4(9jnU7xUsfw`_cdqFPyuvdMlrrm1vEMcA|#7?0K>B02-4U^mR zI>s~w&@p)VIuo)h)|&^uMp@j~Ci@NU1S}y=v~w$4XOYN}M4?xBp(s><;K!@kr#V$Y zjSKwepbg7A;t@d>E?=#N?-MiOmU`OuF#Pe>gM$UYEy5C7zL?iC8xUYS&bKYSP?4Pe zMd!i%S@$V*-+B$xxAt={L&z`Z3ZIcjO4$7bp_Cv)|M}~4L*a}T`%l$dWNj_i=6!pj zxjXG!*4L2z#@c^=DUCW-vF~_~ekpGw$S-7OZ3zX>a++24j*#oEsXmo445aPwVT(}( z=W(7PA6Hdvj#n#{(mQMNd4qP^_1`$_GFH09N|{+_NWUM5RN66E`i->9DL0xEi@d5J z_@WoZa=eYq(<*ZDWO>UO>SMrym#*xJ;=4v@vd(I>1q3;F}k zCS63YqrfZnQJLkZi`$uYDtf}IlQV=!hIze}aUWE)d^`GdR%d9LWWNlKsjw$TxdL3H zeKGFhHB|kH0OYpZ>j8M`0jRO0Ebhgxe@Hp=p9?{}+3`i(s_$Y- zZp+^McUDY;DyV$G3pn}@xVx4gp>2|R!|zXt-yiv^-Y{I;#%JT*&oaI9pT~JB@#@g# zCA{7$ql|k6ery=uS&9qYvo(}s&Y|kzb+yL=*OSp=;(|*SzbzM7UDUv(yGM$6C{DER z9fHI8eYkpIzshZyf!A$(_c*((b|%3I$iXEKi|S=*{+yY

q)nuxPRJ-?qZtIdr47 zYSQx?qZn`N3(+^IiRv)dMU)Am!A7|LTY~((o#!5#OI#5VRH5ZJTii$_Xpg1SW2G2S9U8pYp`CYG*uFppurS~A%fwpc3#&hx&Q7@Kv2u3th5b-5E6}z0( zBtkxV(v%D>9{=&4Gzuxi*0CDe+CO6UqSL?ZOR9b&oGbkG@1W_b!EuKgPKG19>b<#L ziYD~P7CE*ha2`Z9w!ve(eUW?`SYs*7?C50C&b(TkVZ)Znu^{B9&Ps{}I}hBu$4ONB zO;U?yab~cPo73SU!o(_+XV~Az2alJihi`M~(2PLpJFvTpat+BPnaIAgA^ld&dK`MDc^oV+E8+7UdB4M{J zvr5r(51iJ2=(KumbXzcb_)6!bZ$nG-|%LtL#<$5A@RS)$x#I3$y9z!?t}cXd9g*I0#N6P{KkkNP`2k{E zUH?hH`6{|Br7Zd%EePoHBx!ojYv0H#JD`52ls<(6$`h@X`@ReabkI9brcmDCHY0jz zU)?2#_tsCuAR2G9O?s<@aX3oepEoSXu$;>`;ULUDn5&e;w$g!4Sk8CuqykF)minIsMQXpezM3i2#exaal+m>$y;J8%L@b^{8|JP1eZa!E<_?pA{oN<2G%$D^Y=yu$TUwk5U+Tf^eeNBc0G}fdw2p`vScrM{KB55M9%duHY&-;*TN4b)!NoViqAsNjvn?n zq2Y}{82O|*6yGp}aiC<{>-j?Mo&FP@7RUjlpd(?k?-B36+BcLuU#qgBvue3`nZ6?7 zUmwpiEp_C6u8jXs^uiHw&#=L3w$Pmk7ZB|}yY=KlRWxYq--#?wN! zUf!I%jXg%GD4;ugug(@yz(iIwvh^)9F-&cKX(MmF+#H$6m_lNk{qwd~!wwpjUU_8{ zTnt(uj(NNmg;S4Vy~mn8gp65|nJVE@ejk`>Eh%Gvgg5Ne7SgUdnSy7ANJUPg*Pi1j2B|SX$q=Y7g#0MT;^8N|404_`Yqyp>VL@x#mGNLDV#&c5v3WvU zW7R7!kiHtx)I%C)8umuSRQl=H^!{|L zPlDxJR^etZv?R#|GeUkUH}U0;y^m^5#U#zwPpu|m%n)o&u#3kk^EZtHh*g;m6lRxq zB6USb((K{M8>dqobD*nE=M1?B2>k^2u=F> zUB2q6Ru$=>7wd)PcV9TGY0X@u)`==WtTiSGlq|G9N6Eabw%s*REr-&K<`Ya3YXPDW z$I)5SdqxcvP@rC%WUi>nl^IpuQB$Go5m$CTzu|*rsz73tz)*ro(EP9EGSS7?D)&Dn z9f+CoU$40^&p)r}U|@~A%eY7tG@YzJ8+VT&n|q6{UC>l(7rD2j#6^|5u;qKY1(?q62Hwpqw=4CE zmPV%eNX;N$n#3-e;7lk@7qu|zK{Kv36+}dBDz-~UllI!!zA8rT%BbjmR9)zUCH5;3 z3Z1uxhaM#r?!BrtA->;`7=7$Sbz8=(H4?l*+2cX0_(d5!imYDO?SPe_y#||?2fsPt zJ$4A`RfN=;hG%}Qe8+r_UewK!gy5uh_+l-f$)j(SzU205JydZD7)xqeDHPx-UOHvXW0y4L=Z-8Nb92#cJ$1-_2i(~ltC z|HapFlh37fjeqt@0GVsnXek0>vn}ehrooMMHpPW0dw1d1jG^fUf=&v_AF&sZi0@T{ z2qemDq3c3Vh9Ef?)TYgg99+k+V}EMmWT1)r9Z+qH#4W#w`P#W{r+>ZD3DGX98qWTd zH1B4i2)#;OsKKtn4Kn6C}N`{ay1+3;-5U(KA-pP17QX~q&{&?{?6fvrvqRGPJ zE{~>+*7sG(J4-#hYVa+_=Mjz?Q5A(NzDSD1uG8ND&330N@K1VIE4B-gY{4i71b{y{ zE>${z=ol2gI4KB)WOD_ztE1~p1LDt+W%W}fWyOk1@1$i99bal(_~In_-2*>zkPLe`v>TxCF~O^Mgv&IpHaz6TA^%58a>0EW7zS2@Q7f9A_(W!)e-`r+F3 zoEx|Ju$Fu)jmz~8*CSK^j*y7m+-jjP*p7Z4H-nWZpd6q0v(v!P>MHMcIe z*`mKG0-id0_QX$#+Y?CK!5`N3ProeNW3;xV;JVLRm4c#3bwmeJKzm<6L>%Ki-AU%r zWMOE#^OAG78O(FAv<;gDFk6CCQN&gPLuCc6%FF2rfAIM0R7VjsE?9p zNQr}3m>#@l6b;6BWkGCGY#wX4L;6tEkj)u?rP5x;!LyiiBI{oao?enUK%Erwk4>)Y zpudxJ2mf*PEeAZ%IeI{R-Ta`&C*C>#&{ehlCme`?$gik)2=T4i?%?BA=C7(Z)VLi&(jo zqB^v6D-o+~pyDV{cT>ApM9&pm6RO%$jw|82l=c*nWJl*2M*Sk%9E^WRl9jq&oh;0C z7%1Jj4dAM0da{uC=IM!GtBEW-GKYlBVe=T?1nm};E{qAInM&<#CAsSM1st#I!kz4n z8Ig7iCwh>U(D`jUBsd)g{@&LBXOY zD5_iGBx*h^17!}ocD~AO=~}4jitkcInLR#hlQQh@((H7FmlP{$NR&CTro6rh`BBI> zv$*+7P5a@Z7a0Mtp!w{lOsh^tx=Q`0DS(xvWb*kR_D|aFn@^o#+2pKC0Y7J@TAM)j z1QEI_!QEvmmJdu@;E-)t$j~;`HKUPJ7UyhuCRV1vS-|E16m7^T`u0cT|HG^P`87oi}+wi&-crrHwU0|a%=!fem)t;zv z7w6;ZvSUq(hV}jj=8gJ>Gq#1=m@*Ht#KV~!2^zl( zW9=L*1NEQO@21q_T7#<@U2_~YB;&^poA4e*tyx6Qb0>TuiWjNrO(3?Pthwq~-70H( z32Al4Dox2{EXS_$>#mH9=8I?1=XG{{tq-w&w_7eVkXnVz_j0OATRk|U+Vz?nrx=5dqBS- zELX{MBrMZ(14Z8ui1KN4n|{kyt!m#IKQfW`?rVs2dyE{ zNJxUx#Tv*|g|OYHB!8KVLZxWya<-A%d{-D7-;@CUXp=oU40vBG-|M2(>_^1)a)&EJ zO=W1DiGs+rrM3>8e)-`#5+5Cw?!%GBu-iyBO1f0gnMvg#T~M!K9QD%d2Zq7H7pJ1$@^SWWgN9%j@o(l?Gzn*%TQ=aFaTD0ujMj=5o4?^jV_R zk5*6w!rr{Ay&((@NqNpFYlT%Q-9BUD?z3rQCXGG{I|MhG$-@SR>h;58>iJ27f*LBA zJzR3<#+ey7-~(5kmRI}d;pC^y8;@mgt|Dml+3$Y9lSW|6Vd;hNq$4qUGASmiXVHk(w_XcfNpcNWE#3a;*m7?CrQ>mgRRujV@u{k=`kg6a{b6Ie}k5VD2qDzzHR zl1?vlyS^7y>g}EvPa}&*5J%L5v1KB;pA*08?=uV^%<~gdv!%_c|4$%pJ8@Zj$-sn# zODo1P@Z2Hn{moT;hWXl(cJH=dqskd?9E@J`N`oKLcKRl3yf7W+tcwV^Z;_p5wGxV% zOt@@s>y*}{`eT2&K!J2JjfO9l5sN{;89R|uHbmO3mXCn1bn7JAlmRS=?LH!2(!x6O z&i!>Q^QpIG*hXQ{u7o-kV>rp%KDi!>!TH~ZaaZYfGQCIM=_EyXNiGr@FlCx>~rBzF@(pS%bKqEYN3wpz6IJqj|J~mC9zEgYgb3$rHXga z%W<<0!aN?cW=zFCJnDtn`E)R3KV8gEO5T=$i`PFL`S&rm;u1Iy&bch2LSad|eE!{l z;flvSAiAxzO4VMc+Qq12oxnyKC85U~5iDW>Ru^@)RK3r3%e|GleuZ3dc^0WpH}PN!#ae^j?#c-h|Uppqi_gZ%E==c9?eN!g193rkG+7k0r( z$p;GvX+qi9Tf!@~EAx7otNV2JaBmE~is$#R-Z#%mFaFn$nuvM70da-#!)j|;>)r)k zAJ|1U`yMJL5Rw&6T! zI$9$4_E?Q29nbhN)EC0$oXyYjEOO%-}DM+L> zTp9!zAoI$6-b943#vzZFlVl6<+VD`(i0}1+i_pC7-yy8?^!CBakrE)AV)Kxw4fcsH zmDleG_G5GC1&0HOwY+GrPI6G{A;Nv%eE;Q=c8&YD(oehBoUVYhNJXFH%lPXT^Xa!c zK%q#cH!lNQr5;naRFLGo%*qUu5WFBR)HJ(e-%H{2zy|JYZ1~whTYAL(4^k1m3qBUK zrF)kn_H$Yd+*t3fd1+B^V@nH860^G-5=T17%*wipB(5>=I-^t$z!)I&p`5JGiV7zYZDopq~q>6jY78f^2_T4R0iyj z7!@kU6J~tAbZq6jVqkZ>NZAu9I&m0iu#(lLJnGI5+`?rUon9tIRr$ zqCUNoTal`fvv9X5*s~Wo^<|sY!TP~it6|T-9fD84iHB}lhuH9yEEX|8pg#u+W=dt5 zc(8Q4HWwsUJRMc7-f|K2a>r8InF@sJJ$k+rL}hT;b59&Y&liWoyzaxL3`@C9qj8nR zxFl4BD5ovM^RzWD1)GGg*gLKxfw*JZTl%5AQ-1VWVp#)pa-zgV*n944ZB_AXjRfG| zAyF!baD+M71nK*Phrxfjpy;^9N99Jq{O@utU(y9 zYZH>76}b-rmE!j{tn+#OQBk7CI?3pwH}^}rlX&gTe&5-KkJJ~!8fC&G|7O!oRpmQc zvh6>Ixi7Wh{ZL1v*EHBvXbZGt(KYv1$(P^gMq+iXt+Io`%)z1s9hgd!2X;j-ePc`6 z^M@New%}0JrdQQYQ*~JsoMG-0S`xgPOTnm>jUT0dGVZiit(J-w_GSX1NW9>;Nx@dT zUFMJfam_X3o7pk#*BoRuq1J}^9K`=<5UlT1lEDvcnlr`*>U^+FvyC(s1@WWxeS$%i ztxluc6FWNNF%cOqHe#W&_&fPOgX+d)j;X*r&L`+dioM!gEJgb}s$PqXC6PTb@b8me0-lRd-?oo z87^#s4HkPSZje}npalKFcKh&*-6|^BQ&X8J?(&toU~P`V3F(iNU2vDB5z_Igt5g2U z|6v@UXV*0zr(i8#zo^D2ktRmTH7{`YS4Y>C6z!jzGEBXGAocp@65O zsHhf;QUNZ(dv>Q){P$szJ{xJ*CF2l=DOLGV48mR{$`_IlAS=o!SQ8EVv3eSUQ7qS= z=j8avO9rIvg1#12U0QnAPQQVl7L~3(XQL=sfO7dQE^7v z({`>Y_y#Wr>YqeL3Pi})V{E4+CgdWo!R0xG{MFXOs%v_f9Q#td z&pmG|ow0>SU|G!ei3F;7E_0k_P@>p4b(vgc>7%tYblvvGE>r5Y{# z&8a_agFDdIz%`JTqgoC#$VZ)Zc*S>L@af3BqTUsn%xVPl!I6hE-5$xa_2YATbqvMO zk{45nnl$4DqqS^>8hsymMQQi_nI4~*_!Zyu)b`t za94lvq6UzfzbO>3*$IUM-hE2T-}`v;{_}oEc zDDYu)L0L^^OKxkBdYxLASQr^;s`qqH`mNN1xRp0(n*b=JAeRwq9jF&5iE?sTl*4_Q@{RGPL;Z`wFIj1ZQI5x*2W?84E6aB7OK47x-L1hyR z;heFb5Q?7=rjA#N%?s&`=9tKG>VzAhVfto65@u(*tUx-LQ)rnswS-p|707?VW76N zmY!k;xw|@zH1q16YG0KvkA)@f05YjG1oV={Y1yi3tgfjxud`hvxmk(+*sD2|5G``y z477_ZtGfPf>v!BW93fn!nPJ@Lh<=z9%d4Xh;=j;^&woSthQttYSY* z$sWB$roT%>HJpNuTopgg2oF(5=xT8NE{D@VlomjRgMBYPN}{kKDTY_~{YmK0oUob9 zzPo3i9A2-adDexQ>q4H5zWs-zlr)&-enfmvQ`~P@cB_u_flQ{pcub()4*!fE4<9tV z&+hNRb0TqyOt$Z6X_@l;x7_izocvL2PyH@!?2(?EWDO&J2v#^&%WoO8X=wMRv`IsWq@{NvoMfAN=x2V=DReXX{@on{Fc_H6I^66@0K?U+lmoIIYySQV}ERPv= zz!x8XaJR-Cc5+;|_`-nrtK8=-czjHu^3xC_kA~o+iwhMk`_puA$z`!rj*MnHBx}w! zdHOzJ0M1Tq=M0%|1Oq|q*&Q|q;kfaAFYvE7QnQM12p3anv5fmggp@QYXUC__!7u3M zVZUnEoj#F&QEoRA?-;&`l3=(!w|vgkc*1+FCd;-Apy75g#j|huFflAc({jNmAEs(> zJNwFL2Sg(vdLlLe-$wLpA>R=!tG$eAOnIXNsC-u$$@_60dcKo6+*Q-PgR7I4#qV$n z?Ychu4I$%h5lZ4d?@hN8Wnb(35Tvc9lr+1Zzr!?hO7t4-aUzzczX|UaA{lg91U{Ax zBHccz<|y7WrLRRpyjuCJ1_tED-ui)8KPi0bPYOTd-xR(cw9X~fp1Sd3a}l&*ALM0O zV=WT|hD~k70t))EC{JCV?>l-LF7qDf>pwFQn+^SF5V%hAcNzS8q7Daw6f!4#a)xXW z_?k1?(C;4N8~}^gTtMfyW|($3bdB+Nu!c8!g$iZt)+7s3Gn0-lLlplI><&u{tmCpJ zpZ|=TRO;+<2ZrY~xJRXxY+D)mycs+B%cra+b1+Mn3CTGJOs`C7`2lbre?D?o$ggO` zolvYLu*Y(vlADrNjtx26|N9~;b5K0AG2U)WcmRDd;Be!T^S0xm0)kr1x4-bQJ~S@m z`CSei|A6ys!>L@EmV)^oz3heqSudoqB-aPh(($kXEig|#%@(=suYTgh7YL#zFH)m{7u_u*??MaAwP!hsN%m zJ`GwFJ;Zc3O{DqTtZN)0Aj>dXG5NOpcM$TB@pH;3Y#_}z7>x>_kkW~Uzvjd>~^2P*`1{y~9O97%sPFot*7n)P(5+|uwcHO`-IF%+-0 zwov_3-Eh=&I$zkOQB;0EQ8k3L_iV@aH9XgPiV?n@ROkb)+uW#_8yu;`!O0&cUK*Wh zJ+aVD`JP*Ez-x~^lu}FQ{mw62on~rc?S~-+h7mFA=I;O#Dj`<5koWj0BfG>>U9cCE zD;rN)ICuRD!4-hb0k1%e?aNy%dTlpE>f*&YxQsVnZ*|4-iw*5C;hA$;W7`ISd?*1+cYbVT zQ8UF@sH~39&fcO|c-I()bE}kF8carqCtZZ(+c;uZFkUEN3nAkqoQUP(k&>qq{Uv9# zK$6?czhN=qMyAdiZ${bf|JrcYxxKZdn6p=ktdp{EYwTl!EO&QFlPYo$Cf=-QGrSVN z_lZ~-%{Mp21Ff{vY9eWUsV%`g!0iM9k55HDW3M4li@w?s3AJ}HxaNt5Ux}YdlEm7O zC6WOos_cF+7WIGeCrZ9FKTHr55z|R_O6dE88_h1?-~p*)CH<(mR*2^leyW~#?`@@8 zB^=ut;XRL2hl=aLWvv7y;bnV;dq~K$HXu53`D3P4Hn>u5DKvg*zH$od*W+-Vf z@^pfl*S~-5^Cpz<1Bo9ATDQ-h{%!JMv~~vVIqFhrfJCsm+DEb`bF{PxZ9EIk({0P% z;ZzSLEp_spT@*DlUVDa5r17jcZd~UtFhBAB_6GpPQ?uVmBOvyccEB>(AFYa~bR>j6 zZD3i%03NGr$dwEk5zNgMLy|lk17E(MN2sXHI1#0a{Oe{www_W_Ift6*2FP9P&8=%W zpZ@VY>R$M*ySa()Vkp8az_xU3^QzJ$xu{YC1Z<}mYu{6ogIVi=rW>lUO%{~hhy5*H z!KSOlE_K-H+vFSTm5{@mzr7jgjv@vSa9n|To;sTpngR-sq_MByaftzOE+a}UJ9Q*R z?-a@K*G{tZ*2k6u;^3p#C737RIp+(raI-381Jn$RTzx*fZ>=9i87S~yU9P~pc1w#g{vx_=(QEgw+s1Ry#H&KYHFzG`Z?zjEx~3@7ELEiw-1#*ie+tc4+@DH0 zPIU-?hmz%IGRwHr59f-g*iM~4oYV?xx9I4bsY#Q^Vt>KbpLD8g$RNHh4OmJExBsz2 zz3ys>eO+BmUdHD)!VI{x;7V{Ne_yzs%rbW?7mRfndD5b>Pvg%E$|CgnFC;0py1RGX;-86Ncck?K{-d$O~D8y|Gr=>86pcpR^ywitWYTeJt1S z>J|pvjCZz7u&1UahqhH9;1EpIx!+-$_+73Y!D?OE_5E2TSY(m|Z!&Zhn5XakGZoNc z8i)KK9U$srs86A&qs&y~7^lBoGf2-Y+?wLOX`~3xF83h=>sr`D(j_gy%;xblR2`vN zxaCb7d3$EBu*V63x&^J}Uq^12lGj)Y(TnGUFN)E=`@kNUg)MAa0Y-iY3}iFDtOT>HdsjrQ&b=$_wio^Tn%&Mi{0w8=`b= zhY|`7IRoE-u4>bUGVC;Kep_7&S!>D1#*b*^2Kj2;Q@^O(sPIwy;+gNhQW8nWKR5nO z1T-xG9TZQP3L7CT?NS+j55MJ^xE_15J9e`}QYlx;-2EvtGkt^LRr>2M7m#yn*N)HJ zoz8tP8t5QS`RwcI2N=A0#$XI;;zjZ3y_6=GQuHGFGNw*&qdvK4(7B`g&oY}F{7uM+ za==+fmu}e4E}Oj%lc}3sHexOj0~2c0wZq;C7DE?&K%sgfrcTs}B!ARpGB&vUM920P zpQrcVgsczif_Oo};uj5w4ex<~ewguQoc)j{)3|ih7iA?#;K=%=YoWP!3F3t=OJ*0J zJWLBPa;bg30{Vx`J;97IH&Vsk+>NxV2EDz8auuN#cfqNF*WoB;$JaNZR@Nm^gKMcdTt)k z%3t!?r{C&X@Sd>B%zZEG1saQ9OU|K6>cq23)~1sluzltkvba8F7;@L7krih5{ebY> zn*oE#@h%6Gzs}k&7r=EDvmWii%kk>Zk{JkhUIy4nle^MSprZxG)OXji<54>ym3Icw zPg7JMw6_L(PG8%rE=B59wB~*~))jj!rCf-j><9_dDOvP2V2yM)N|MNvFpxITZpszv zNgkH69=$a!;`PVBoeHlm8=;n9{wL;d&;Nl-GRxXNfc@0%lHj5W0euc(JjSmjfJb^P zh4!ld4ING3SgjMO$9biIH_-c^xfW{EFiGb2P4%Bppj|OH^wo>L zPQ_~O*+t`bC3CWv;$ah>ot*Q1UMF-613R3j7gnp(VTB;fomTvp+vs*CxBPW_(7C^jSz*rKDnjgKG~LUWqY82 zwXc=uU%jM?i#IFW^fOclL;34k^zq#1Wx)LtQgA;TcDX-mgkDyTuqwYHHc)?_hCK0E zscno83l%87we6|U)NL96Ouz@+Ne8^OqsnwrcVnH)hzNP3L{YFFgcA-ZsmyJL6H@;S zC+rciIAAmWRM%77`5Ck6NO2>65o|G4@4>3af9=D_2$$A%mQ!A$7JgKv%09w=>3qsB z1hQI7W(-RoD?@#S3;2e4@}bN(sbr7As?>;eYlG%4YOcDEMb`z$xJWZ6M4Hfz;5p1` zkT;YHm>BI3tdaBYuG|fyg)2p0ZOnMB(TUNrb`5Ryz=2#cG_#owMfUj4j2#oq#J%$N z)b;H>tfc90?!9v18lA?tAC~o<(W|%`TlO4TtKISnzUj=w31w;mI~yMCv)7%z`SEFAO|iHaj9$letY+)@hq6C8zYFwiX& zi;dSTq$$O%AFcH1N54sawCfv$V#q=y);%AJyu!^pwvc{tGu^NY(sR}cIiIh~LCa~I z%n4+|_YyQlJBS)rxCM8fnFMyXDjM{fkhs>$$$Dwob|xHBdN1gKYS{xAcm;CCX5QUu zf^6e6{-#fQMnzh6JbvYDY`b&w^pUyhm$5%B4nh>l69vCj@MqCZVMK+zUxb;fa>|PY zulj|($tHSkEaZ4nK`Um4W&fBnHhEWF98t+aC&O3r2+kmxJ%Wb2;SS2p0$ylI>fH@)F&iMydaLY%Lp&9cVX_ zId?Wi5@MSZM0vDP&kc0i5Ojt2w!rm%EXN%TbSdiQE@X*MJ}DS_0A%(ajk4pPTA*L5 z1oi$ol6?5Bdw2b{9Tjp+`iZUEon~Ivnqa_vXd(eg=;@jqVcnt=^VScYIL}m#bbp5> zdO+ukp#qb_r#Cy{vbjF@}sWO3xoETG%CwYFtPkkTU@d+VY2b^-idu~Ok)r(%OOic z;ixtYG&vCgXcQ+>O~n5n%cI%1*R9)Xvt&&SG(h;5%f1&Ja*2oZj0(5JMO~TTzpO>R zPZw39H9ag{K1K4Ct;n}8bU74-kGvD!S#A=95a|7;>!0~cSx2WcrAW%URA~4pWU(~} zxp!nzsPm=w8~L7J5`KSVCotL}-}czT1Apc=d1Ye6Db2?B>>OP0{W2$?wjzXCu3^Xq z`v=23)4U(tddu4G{lLMz=P!df@SGUGH9eeJOFRAqC0in>-?9(H#%NC6aS#4YU{bff zExOEcrEeUmxS;C&piNA3n&dK4DnBvy;Tl7{(Cw%nrat|ZhZLsq;+|2p`AC9lRo;JH z+`~ocx71%W=>7ADY#(w?^Duk;!NHJ2b$b;S&&F!4gX+TWvftXZ?F=qVdVRjeT9SyW zx$CNxOeP}~oZM>k;MQF~3w!+a6Af$IAmZtyvpf9rCp41fi@&A9K@nQxC5o7b02$=h&wA#2Vlg7BIjp*lSd9~ee!Q`x zZ!cM*9aa4AE`U3`1T9{Nd7dV$XQf*6ECA;Nm4ehoxNJt6N4{MRd=s}@uMqFb8fx8 zNFid85|p{T^?P)5(Ho>MLU>^2#~yrnB^6f1QNu^!Oo6z~uYo-h61R`Sw9h~<>IHnM zMkkG)k*B7H&m6LuMNoy1LC1rjNxqd%_oXg!j_%?5SR}IpditsAb_a<)w=#=wP}K0o7kx)hjnH{53Rd);`&Iz!3ER?!upli-qz1QU z+}p^$m$kZ9m4s%i3vuLg1~ryA*!kj;lWh)5JPBL4(yv$qN6aGg3g-Yn>;N=LRF4imfEn=1zEeH{1WsQ3djaf-x9 zDUKKg@vSw^d}TTf3tHCSrx!P3hdbnv$L@S?DQT$Xa0e6sv0wT4_|L^GlNX1G4%f&rWrpSm)^dJVkXrNNwzsF7X32`USDI z+}H+XFL4jWXo_xeT+FCcA{a7_7Y@acj2CLooo=yF0>&AB8fL)r#k%!4KXOWEeieyf zh7-Lbx|HCR_<&Y!pi<828rj8&yFot!I{;r+XWyije)n~ztvpwfIm;6WXKX9 zA44BGQF2P)aF}JCLep-5P)SV3z8FCv^t+?)iNe3iQHXY>HY)6ulgZ`Q?yd4w)sl8^ zafga+nV4xJCto3yQYR`&&KuVFz5~+qk+Pt0T_zUMrT$@7MSDPKhegUD2*=*e)mgUO!wuI%E-V zxkY%(yr=Hi0AnPgvL8zn5o#>H>sE4iDB?NlQD=|H{Ca#a1OemlV$wGb_W8qMLv`!(@dIGV*NXn#>33RgnR>oIdumtu zxvyDHE?X0ccEP(o#XPhI!i>>Bg_%!}WaBq<6V{ShD4_-~0RjlF|5=qtwDRh>wfQyP zcy2W@WN_Cf_u#Q#U2%~YA#DnVYN;@8_z@DqLuvIe6T@O1Ibm~`luGec+rR;6kwLH=tMomQ51CdAQ_<-p_CV@ zKUxDzUonzI5CwDHK(pYq02nj3QK*KEAgc>~_qY(&=Y>V*>|k91P#Jqsz)~~DLmwTN?K&)U; zp^NOofcdHj-u+U#{q!T%z<*qkx47-g(qSPwH>NMX-mVz};z?j9h9i2*PF8=xEPZ7jq3naU=egJNVZ1)eFRSBd3%`Zr7ot1YBO1t3fsieh=4Ma9U`*Seiub&0`i_~~!tcfmDT?d6!O+ZbicA$-DQdwR98Brb(RxG@dX@LD@}jys2JKI~`pyc0 z?xJZ*HrdGVGQ6c!yxK3YWz$EA@WoD1)G_J=!ID~!iI8i*r)z&0Wr~2&vum(H_Uh59 zN!GStq;fzFR}eA|+$6D zrd%^PQAVALRVFCICMM0ixF2Xj}Qh+ z%G)epv~ER|{J%3+9@6qqw3gD%{)(_=rf0=^W-l^qB1~d4&@GRT5+>){hId9ag4PZV zK8V#BuYs=ku^C2F*jl{Se`mBTJzk1XnUpGFcd3sK=MHqY%69u;B_;_rG`JHA;u;#P zG%0Q{mS_{PCW{)%E6P9PZ7O zoG&HM3_?(VRmPZqm4sn1QgS&yLwCyr1`$H@aVO8cWuoU_S%r-z*DXQU@crMN*Ypix zv!Ua&OY-gV`l{C=|>#3O8mYu5T@SJhV0DM$F&z zeT9$PytglOH9>auN*h)>lojlRf-)|9h~$?0v^x8DYY)>ljDkFT1C^drzO+V|f7t$p ze8xY>2!j1qt$rscCA0Ul^9TSNzjc7V?PRD09Dc$BJX0vjt-%~UsQFhRI5k|Moe>WP zGcm*z%aB2@^)r~bww84r{?I(PPka~6Tl|On1yBU0-6*uB5Iwp(R^HRo(%I8{Ir|S(WDOL#47zGkY$`ou)#&0*cmz%TA)fLuQQp2G1GOM~ z(0E_SLiigi?UDbD)uM453&f;=v|>qQU2ghnlErIwi6i-`j?c`CQFRs6!$yTe`|oJq z;U#q%Is+*`ttYTf=p#EGcC;C;$(9^ie06-~(>RyA_j2A7H&ecaYSX{H&4)$4Jo29` zua^^6g#>yh$@K|I0+P|%^V@MHKZTJdw*zx3bB5;g10Gc5+oj~zzLy2PP#os1o^#J_ z*k~6NpqU=+g?R)B>TEy|O#&JWf2&gor3$hAynawKjyMbxF_Wo+re!>y=DzI1JX`-K4$JrEz zY3*pTssGt^5tBQ_CniJh>Mqu=wb!YYNk$6#D_s_t34g-@<6KPTa?R2jUMa?bx-aw3 z3MMi4`()VSbQlO6Bji6#vIuYoB+5`0B`$DFMdbZuv#;zGAv|Q`^?1p~ zrEznQE|aaK$A6E3i*G-eCCFKsVN*L9=T2Z89u9zV*c3 zhvHUe?va~ts`dgYG|cVCBNNEDbA)Ik>I6H8=9gXTfXN~5(i*bWdc zO$O?JbmXu^s?7ll55$VH&p^QHETy|pWtn3|Ltp*;~o z+(%V5`(0%*`+TqOpZ9;u&OQpsq{scVRpL^nMZ!dyru6z^KLn-*ENzX!8CvWbYIuyE z-(HFv_gA1SL}qrK5^^FSiJA&>$30di4g)&AwX1J3>N4PuI<_|!FRnQxtc9|Su@eKd zOWkk_s$i$EnGNih%DOT;;SEFqdYz=&zBZW&c6Hj!qOxazy3?AX4*{q5vorNas{;dSdqjw+sU74cx>8yCY@8sOAE&@XJR_THb|vCOIFAL+<*IswWqlGsv!f zI}1bS5oI~ldn}Z^@Y8T%Z0;lwe8}^#f}3=HVaF?JV-iQj>FBo)>b@me_~OLv(nX9> z|N40FeZz>MtGwO?~Lx{b0{N#O9nFs!|eY~`qq!4n57wB7!GMSge}G`L{GSR0jc z^Kx{tg1hUR#gb)f&iwqDHax|-Xlurp3#YBXg(rdprTY!1iWO`#7%M7?PBOB}X0XsV^=qW^Q2WWGCA?b3tAeJS3PY9^Z5z;fo@ z{1I#!ngSVI!dZ}Y&QBSNO-!l@OBnjj`%CVj?nQprH5Mbk-j%}HqB#)Q%{A|u7Sz52L zZfZ2^dj0XtZm!Cu(i>@i1;*~)s(`-hDMYGg!_RSui2LBh}|uUf$l9z z{onLQ4v51OE}|!WU9{j=Kd6k26{k#$G16i04}H>}-7D=nJ)|^ODoOcRbP@uJJi##w zS!jor{YUadP}98b@@lBb5dG*0p_+U&5ZBsMx5}9o}|xM zZ3@A6`Z&Q0i)yBUeLo(uN(t1sJz*+CUKyO_I_VQko3T5UlR6!>s1-?=#*a8M4T=>Skd6zD#e=@5ttAw#5#PpI1mh3`eyoD^Rp9sf;`tjE_ zQ0bOiKXzOOZS5SWf2_6-3Bp=Rkzhh){7Zk4t5&kENmrTB(S{@`^9P|>2!q%6sj-X~ zIM4SHv74bG!;)zQz<*I^)72H67nr&a>Z;|K*9uG(WZqLACLqoSPkm5WQ*oX9>+S4`+;5U;t7ROWhrvXpE!ot5p}ZY#VouJ|S_CEalZOrS` zgKW-c`rooP^|;oHju6#mjTyP9oRFTWG4hqb*yLbqoy41;T!bBeFrORnjCf_YPQ~CA-0G7nkaQS+-+an-^l{%}mYR?L^ORqFC z-dc7F7ys-ZvDNW2wvaL;^sINBO)jkQ{xNUX=JLv10QNSy6^}>vfbnHPxqT>W9r*AQ zJBA(HqJ0&5n)Q%PLXzTTQ0eJ|6pshI!SZn(n>XQNwRb^G?*G|~WwODm7wxIPEJoAv z9L|5vxMeEy`l|Me#EDp{3$x4G&ox(eIq|G^vO|T%+gmGyiro;;AG*aI$-Z3dW&6AW z$u=q#8mpu_Dg|x`m3b?^3-IKYl+h_c>}~5qPs_|v5^XX4W4DOW5i1TKXc20$hK_A8 z@Kw6K2n378XY)2_gToo9zHh$YC4X<&e6MAoCKOiqOIpAS`6A(VOC;s@|Btjck80{{ z`-NMr@+c}*WKe;$waO!-2nYxytyZa`P^%DxKoE+^Ob9a}si2}vsZt0-ASy-56hy`_ zMaIaK2nYcg0tqBQfDl5+KuEq#-|wvT`n>D=&RXZJ`!CkoEJ*gg?|ogr>7qaRZU;)z zu_4*o?XV!tk3=z-wUUb=GC-g5owkXc+jb6ApYwjS@C0krbq4#B@3vyOW#1n`^oW8e zlRtJTrG9_q$X?H{zuI@?d&~D(XYQo_`ZWJ--~5;l#mRyBw$$JZqKp5HZe;H<*i&Eo zEQ8$Vr*3B92j~AZ9dkC&Rr~q7yUE{vaq;Mn34nNI_U`F>KcG-5cN8mI=5mjam3S&? z>R_|ds(VE2O3SE15kMH({v8>`o7Ocld_JrvFFgEl7h>cg?(~2}2MKYxBLf>plTR^Y z_ipE_0*=6M)ZZwIIz4*SY4e<)zyVFsw2(!sz68cI4`k}Sl%4!Vg}r0L}I2<{1*gwCq9p?qvA-AM^@VY|P*{O6nMFSvKc^ zb=S8>t3R#{W{hZMTMODQ5J!~U2J~q-o1ugxp^H9FHZyaV-_b?W)Yme(BkhcHp6m~q z9UQ6pNu^Wx{xKKDX|>u5*boe&f~7;>)t6gfpJiBT$*5gX@ZT{ZFpLShM+oy3NsPN7 zQ-r5nHR~;yg_`oLai_3r0eyxjv{#)o{&Z@#=?pv04>lR_VAOkmNBKs_viTRwkx8) zx|8yC_C62bqxOSR1Lr$u;(D)5CBp6-4#`ihI&w7*;#8<04 zZo{mQLSd3~5LRjQe4kBse+vIsH-7Ot6z@D;>ufOg^2}sP>+c%zEq{f!Y{9GtMzFZQ z@-e^^sYP1T>@%d_wws_GYvetSANEE{?Zr;=60Ojzj|o;+PqcE{aOShMOyW&p{j9G; z(S+az|Ec|@_~YpM&dq?qKhrrs)vrGg@}7!jHw|KZ;LY<{ZZ)3bie|12a8rR?lP21u z6z+kvj^JS%&QWr2)kB_?+86QNX_S6(fZ+->cdi$S2x8C6dO7$K`H@!6<*0q2^m4(v zt?F)$jmXENyS95I{slL88VYMFGRBsq-l%S~KVKeRyS$I`kX$df~-) zYqg(*0ufx!5o+>SX!m>&|q>qx>a`!;`kl^28h@SL2~ zW78eFj(Q4>G)f}%4B@6>t(<~BzuC1W_H%TKF$Cgm+y5MPEH9!AKO$0rbwSgUGmxfN z>{;bXk6oOwIuwbnu+~y1Xn_8TwAY}3GTx`3A4Gj6d8(>QjionDNBGH3_#A42MI8DY zVeA3nWn5|Kb!>hcdi119{A$m3=9T%0$E*v6tuiEggc+CajBztUy0s@2k}NCdX~@Ub z8(Ret>zY%&5GRGYML=zLfPApfjvyYwwQk(j8eXrUljTC!f79(RV!7|twFiD}{{D9J z_Qy8KhB-xuI{rz`0Z*zZN`r6%Gb))IOMfD1^ND>jluAXF;KPy8?Hp?jTuka9RrpTj zP~6v&Ecq56&-CZRFtZuGNcgHObwq<_l>Qamj#K&6F<#1Ko;k6hi|kXX~FIe-K`CEPu3rPj4)i@}mo&U^{_TkQFhCb@gV zbZ?-~Y>l{cYKXx6x^jIJH3Vht&Xvx6e;OWqj3rC0=+5C~J0Bpw+3?|9&3kF@Xe}5gxA9F92%gGL)E!K<0ML)u`*kFPRzqkEn zDth$x0o!tvf9OJG{$^Kg|J2H>an`+5nm(nm$6&#RzWXA~Tl&@vIDA44xu~-Xg-OB& zlz+R&QF@-)g4uQiGZC>Ud4^8_zLGPm2M^#$RrN}1#VqN&#Wy=ACv9EhG3f$Pi21qQ z`G&QWtV2(%`rTvXFXjQpm(IUqzEb+P)nEU)ArF=9%1c@%t4T4;Z;)Enk%8O0J^%&3 zzpzaO9U1}1RTmHR5T4lA#r{%>x_-4v_GRjr)&$G3OD~??xPqT)IxqMG3%2Z@;hPq` zMT%{2h;6Tj9I~CRt13aY@NQ(@0)zWLREG9Wtk<(2>hP1XmAMwc2Q#ZM#)nAbBJ%=f zVVv9~+mrGWp_@Rv`*-y(Buuz3C-LmCbK_*;_Y2Sl=lzyy4DU|23z;DKb4h~(mK@YC zblW~9@X;B1h4}@wk?mXLCV9uBKPUH^s7;&}UCjlCn{o9Na)m%Kw z^?gzP!U#s`2{a3zJcx7hZZ`dNY?yLkuTGU!9p%TS_6@I!=7k!6v!Zl&QVe0D@KvP0gX9Yj4D}WTRcNh=uVl_LrFsMTGa6BHE&| zQA4*1RnqwmH3Lw*)q~8DoBxJr(cw?HwZ%QF$bma{^$Y*fSUNJ5k&8Zqa5N}@#Qgf3 z<)PYLEg`)xPwOy0-*bh#`t-h5zDG9J{NzJaF;p7W0a6x6cBFHSfZiX9kaeW+zx$xj z?ZkkI!tujr4ukwB_qS^{blV>nFD3pFkl6Q0Tt8pGG07N;JP^DbBU-_4i^d{a+10AH59@n)f|oRurf(i6p9LI_D5AKlj}%wstRoVMJKy)< z*S1hkoIU}kN+}lHoa!fOyTNbs;o6WvvUbj7i_2(bH&Q&eVfE69A2Cfz4<7t3c4P*1 zG9k9@Z&&*`-A0kVV4NH8_YkcTb?II0maL_Ca8*E})Gz#ukMsU=+XAlFv!H!%&qjy! zr@!BQzRtiNxSXZ04v{tJAn<#?$E#AU_gg$NM%XH935n=Ag&oz}eKNh% zAgK<8Y*rkw5pL=b^U)Qbzd)s1WvB8M3voOr`7&}UL%Mtx>NyNIE}#q=aB&ab4#S!T zSl0#gZj)=cho>;W90`cBS+^A^<||s&<4zq5ymLj}NRmYn+4tP}_bBBGUbV>d+dwSO zwE`>%?&4?Iu}E4C)H}Z_^n6ozq^ymen^USL1kC8(TYS^HcSU_Cgi<(oYAB3mJXwc)wt5uf z0K3od8oTsT52+VYy~v}hb&fpQ>&bxWp0kPG*W+!)Y7R_i&8x2N#ZWK zG|@s9mcjI6OyGej$2`5-{QP{uHb;l?%AIqe^>Wjeo%LV)7xGO0=hkw55PctQ4^!B@ z7GjwfK3o<6T9qgvAB#Z&at>%kE4QhYTOwXl)SskayD~KfByWzsoa#(p$qSqdQr@wZ-}kAf+(B5)^m=u2fIjb#6E2zaeA?e zN?N}NmLA0C)2fD$H+U(IFr=4<*k|M+KU;c7SI`w;PWQiS6+dl@VaUD zHQH7tdS2BoxA7d@TNDGi$jwHr&EG<5@$=s|SLW~xRvGamo|U^kYhBX=dr7`OQ6*1U zR`up%C6h$k8X9teVimAXUK&@@aDU+)uEmU)!fMA=rIIk+!R{JbV9LDQw}WrZl2(b8 zpR*X-Q;Z6Yz{(v!W(3;0uC}tKF0Vjrrz|J}VVpkxwK}n5D%z^J3pLPE|8F8L*#m?` z+rcg@`P5wc`yC$i_R`PR-`o91NAIfkB#FVpj$tVg9?I2eaFCn_IL9(0^Dvw!G-oL- z1jX{bXxG&5W_*08c%QBD`j?Lo4WkFid#xUa9K`eYfODNZyq*ghx^s*{6&ky5jh~rD zvz#16KJjTI;XMD;MHXD?mKMB^4f9}VWjtnn3c5<&e-c)C17Wi&_;Hveo^tjHFTlMZj#xMj{FQ$uIW9a3HBqNdXU-nR)IG& z2FBVCD9PFmKW>g&gKvGJ>%`4GP%22T9)N#L$RmG$yJ^4zc+A2ybjB~r-Q@*y!=jJO zQ#n&FS#H9KJ$6dXf!&-cK^U2-JiOi^iq535LbJxs$noMK)Qn*JkCX zIyni-9WZU2dav6Jk@yFgUCr9`u7is8{i)iVzJT+ZpVu`>zdndQyYm>3zm==}v!4O1 z`L_tcfCbla01A??CBdKUX~1Y&$*;gFE(`uuaRPMS>_d`P?$-RttnHa%15^zxDcc|( z>l<`d9KRgTG}JeUIj2Hyuwuu~#Affus2HXAfY3} zopWSjBZ_bJqwlhS2NW-l-F3sZTR+`#48abJ=@vuziK!@UVhi@`$0& zx?o{cTX0$iR7z1txs^j7iVmIxC36d7F>OFwVZ$yZhYb>uD`2`&_$s6^E_an@h?qJ` zI3?cGt@BPZ5c)v2yCJ{VGi`tBXDiVCLG-(kSK}BhIwRShb6Lkld1YiL1!v^hNjqnd z_??n-2wIRw)?$L5a$i3EKK3lV`W56w6PEMd8MdBd46h`iyJK{`7OYi3nt@%q&Ueh7 zS~0v=mGqUnD=2aCW`dUADoUb_lPEBYfCO)c)G6w$HCUt%2EVx_X}gPCn{9Z+8{I0+ z$VHi9S^7b)mZB;4rwIA0mGf}pkM76;^AIpFy3NBad4=a&@hxdfU_Z%I1=VTnW@TOI zp)(Wwy4>=+0oy3l$lG1N2&3}6ZoL08gPHXX;z1!A9^;>)Y z)M!$RVysMwx0l+sa(o=b?@hXtEGUhU_8O^fynq6KL%BmZ56aPRZ%ODy$j0#cf;Ok~ zNNrY(Tdr+uz#u(_gQIk9S>heRcWV)sd?4^bp zteyXuTNL?AgGzkzl&gA;s=zFY~6 z2Lf+LDK!iC)wKs-?b&eo+gewhD%4$@E}hJzSxs!j<)X19IWkNr*2yc(G})R>DI0Cl zJ!}0wzjCYR%%f|=LL@^VWaq}D#-XqeXpxI3Q?mJ$`Y1mNFlc|# z`=-oNnZplR|4F9UxNL|o3sUc=BXdd7#K{5+Mj0jBw+?wWhs6@2rtWTgTz^wy`Rhyr z!~jvF2Qe9U*1B$NbbZ9kBHATXrvqmw%GyR!Y~{D*I&?wdN%*RDdUPL-n}MjPl9NYV zCw;(-1O0;y;o-_@*@0z3FT+D z6I5DH)ln+FwsOkY5nszriR>K4orB^XGS5fc=j&5ppik+%0gCrTzwdJpfiEU$@ z_heTWWknHwTvoL+sGv8a@ zI{sJAyRnyz=ows^#_z3~)^owrb3>N|w^_SWSnEj#y*zExX(k(-u~R5o%6V`B!u-mx zq1Z}&Ks}O-p!=kcbG)Ta)BTla*Yukn!u?nRDKuu1V>Js!gdR(T zMgwh6zs|P*Anf#yza#T9It0&m!wWR{L4n4EjVHtK+(fJT=vxSm z1h&RYVz8V|P)ZU3Exx9l^B1Gt8O`~dHrW=dMKBn1o~%M{-A~~8K}}GTyS+E`^!vY; z1LK$CWN-x+vwhv*MZA3z)w>GDQywG=gvu9dqjfGcNq~HQQ=I#u^xs4$9K)JAu0g^6 z-+Dg!@rB0j#K&fXkz9oI?X(uwK@AtOia*DokRU}?YCs>NUw}$-!qD7CZt|z`*?Dee zaq2dJt1081702{2-6WxT>>TA~;Y4y`z<9DQ!TG&#l>pJ9FPTlm6AxNKDI=d|K`$fX zF0?L*vwSUBckkVPr?^Y~UFH4fo&DeM>eQa>LE4VVH4xiH4K*y;4-*|KkY;JWFSr`e zYLq$iqAAuoDM~Etl>}>+fBY~0^EA*kJR{{L&O{s+dB`r?dBT`HbU7oNQ_QRVGATdt zOKw)P8d>AgZXK4@d9E|QU{$L%Ab~=O*0bvlm}I_K)RH0%8s)ZEs*_({P304XkC290 z`rqi2(|yLrgoh1d`JT(?$=^rjk?)=S@G&jAfd2TcapLLk3U*$S);_b*L8iWkP9x3k z1+VE}-yE3T*kG?A9YDtOiMT5v9tFG0>62TYgIDM#Et;~Rz|jh`Y)5^zp!}>Y+yWz; zu-OD!E7^Smd?hx3--V=FV!PI-Bm*v%N)vg=M?HdNe%V%jhi(YFUUrOrTqKV1$b2kl zQ|8E%p^}-6CFtGvZe67|;}%_Z76P-?ELE&lRt4Klj;w+96Om8#FSiR)G-m4B8 z|9cfH!RRY>i|6)>Rn~h3XOI0iI%tO)vixIzXUB5Xqdy{ZxYq@{gQUnIW7Mp2S)m=4 zxWo1njT#qTxt)BVJ|MjK4cOD5XP@uVrF{+MX_#a}OzNy@R;G$=pqf&i_i?BVC59m& zF}6JC3XRL`gRZt}cT?%fSo9+#L8=Dvj`bF&e@mXwGlF+T1&;6*ouef)(S*rP&3ZFE z2)={|YAC-ct^N0EP_-vf3*a1d6zOzjwlv_d;VS}QSga%i^HOT#4%o62BdqR@x;_?( z>*B+pGJJI|w5ua2l3goXd%gT4-&RGG?38M=A-bi=BGSGUnd;I_Sb}VcuSXw)>8n6f z=AyJ$M}pLFl}ziprTXxwD!yVYNhfZ(iW777Z*^Mj55z(@01mxlz! z%QsqT#hD|BB;KCx$M;P#m0Cw4ZP)hasJj-zdR)`M6`1_z}=mh ziv5=^=HLEz+nlUsU-W3^aT3%Kfhms7KKdTiab_=^9~W)uWM~u8>gcsr9QJk6|6=)K zJkfZ>PCpDZGgrVn=)Z3VS48g0WhbnfXF_MC(50C|0 z=ZsmdtR?V=h#R~n=ae1#lfR)bH(Xkp(r$Up`l)6MU+DJk*RpFTuKUEl1#GPZgZNv`7pcrROj12DE@urbCMR=lMnZIzLJO@ zEmN4%illGI(j_RlQQ8Y_ecQ8@6j+cGRvX1dj5jbFSv~k)$HMC;08h5^Sh(va zu_=1Bp^IQzsSYJQHLQ5la7&AQ+8*BAK`qgW37)$hm^aFViZX?6lc@n|rsUon9@KS4 zua&80Cog?jU7#TB@$7QR)h#8hx8V-ZB$!zH}H#S$JAna}gTZh+s?YOuH?O)hjA zX=o?0Z<7JuPf*_jMU=*U3#HoPREz|J`ERM0?6pL`X{3gJ@6<@55;}A&@qIDOzeUUX zNq(gh)do)CfMf6(TNfHHTQ~VRIjkga7P>vGs2Th_ut*;d#CU~|h+Zo+6fQ7~3zZ5q z0ZxmAlsyZ&kF1?sWflPdOd9)RS$as0z~Qf3^P3)7F$+pQ{{tx94HT1qEhWB#r*Iv+ zBW7rBu}^2Tqb6T=S**lL?k&e|!B5g4X?-U^N5$X#0r|$VZppXR+tozYK7`AknE96@ zL$b<3uiZdA=`-@1(S@I}Gk# zg0-Hlr3RtQFzMOyT%Iz=)j-3u`aY3$XH1dq>g*QLTb}Twr8grKH^sd1E!n z(tG)kw*uaC6}>Fg@%ll2D(Ay8g5w$HU0_zCr(g%pU z&9f~onIS|K_u0k1p-H>^wSAWuR-ta{2C-vDFhC|Rm^0v4Z-M}JHN~keCu(?GI@}eoBT2<)A8V;?b_kihAdK(yII_1DnDl4 z#Uf`Ln_i`Vh75{LdRdtzY(d4a!6hKRQx`qr0C^o-9Q6W47s-_z1vz zLIiB+jg?)A74nB04;o5Uc7@`=vi&^TQ#JB>OzSl2U9EwnOzT$FHP!qe&R2}uoFvpn zo5@}*f&XWI2hXpacQ+Qfz^_ZYG0%+;DaEhzO|OyL&xG_ba#dqH^}((F(`$51xEbyn zW%h}t^(i+0ySLRlNs|^Zv}B%>VH0SKYl}pzT0a3x+*9KI+Dl0tcT3aHWGlCc&*>xwx+V8YgG9|AB0w%T{IiwBmAom|6iQoZAHaV-)pL^ z+>V@%D4lH`hWA28$GPHB+Xn%6#7_7fPOz+I?vk%RapvtI`583Z|xR`5O&46|0@gNW_f49D&Y@trvS-pps>j^udWnv&tR(bvQzAqS!2^{eDk)pzJ7mdNhiqa{6WQ#w1ZaHd&e*FBxckv?H_6| zkv;`pE{3x(=2jb0PHe_kkcEIfFq7%A_$ZzI+QiCM6ts5R)!mS7}`t00Y1B2}w zQFS?m1Ka0{lP~qFCIWE#?d|?P&5gGN{!tLDjw;w{Ge%LTQhc`kZIT=v2&%3~v1gT9 zanV6LM2p#NOjQr+32DT%@_b73*H9IXmbAaG!Yg$#(YKs5$OwmG{(S+XOSH%jZlcjG z&MCy|D;s2E^$+AT)Aa!?rI`t#oD%=}Mq6&$Rdrv^d;A2bOJ6G9xi$Y87{RTmCr)p? zwy2mE6o|BJx#iX1BUfA1HE2MZicNo;c(P38NTwq)6u>&eCXv7gh&o^*`5>~C>-j1Z zBozoYEl1fkCx!fW!RyfjxMaO0;X%efa5h>kLnR)|g69sK$2J}-w(&QlI)rn$TGzWp z8-sl!Jq3}bF>s2SAnBF{3rxN0B{@~Yva~7|z!(l{q&=?dcG6M=qn{{wB3rGHi$#|! z&FMkH*&B=X>?}$8$$z*=Mq@D`;xL>_%{RsM^G#x0krf;I@c$wT+hlnA>#cg}7zomT zah1vf!b0Qaw+PaYmk>XFNylY_6YN`%7F_|(6*&AGmF_y+afs2EoR`tLh+YOrq}yly;b zRq#D-VU_NZ7Ogh%qk$sV9JyU8elE))_*$ybqSIzSRGzhEXtkatwUv1tb4%M%p#j~= zdV{gR_BER8fv-37r9PwF=g15pDCS%H6Zp%bFhIM7u|*FGE093sN<(@;6;SECS6{KQ zi<&@Ei&y>hrb{nj?XJUweufbKnF&@#u@eTXui|ZXtX^C}@KyD6!b!X9h_Jh~z_?a0SKX#$p5!qia1;{_LWlPYCd4meoN%Fa{?Ay6Ur4)> z8cRw1V&gIO^V7Bd@*d`o0&I8M5{j>^!g?%R(*{xLL;PJIbeXhv%(=bfn{&*&4A269 z->N*pqj6^8&a>9tgSuG=Lvq0F?KAF{3#Q%o!02&xipj>{U4sc`q7blu(Q1*P3K%qW zA+ZD7#b74(o#$R4WLqu(rzgt)dipi;`qfJ2%t>&j1*K6W6(A`%0yMu3rs$l_K*2(2g+v~5G^ zr}0bp=Vd{bU~IB6!IdYsWp8VKzdf3QduGMzbnZKtva2Znr8WJ}#0aP;t>>9yVO@qKf4(u_hFJoQM zC3?i!B#63gWq@VFKUrAEBIm9mC;L9Xkq>TvqhnB+%7s51QyitgG{^;6h5aThBTLK5 zfHB+QLR*HwHVSA(RP2Z}HH$w$8xIy9z|+Lk`*J8>^5OTav7uW?Lif7r@R;N{&97fg zdp#w^F$-<3#EEu5oSSBmRI*@Wsh2D$`Hm1|oHru;rHV6aS)duuVdcGD=q-H)kHQ6g-#Vq=3Y0@GAvz~VvZ|+@NyZ&r@#|W-mIF?`dz($L`4C})(FR%`f0$h zJ^@3MSbj=V^sPN!a)$UA)Wn)%Kx=+0yD+0vZ*~HxjVs}q8nC|L4pAJUHS8?pjx@%D z8Zw~2HTawWKJQ(|KX2up1at91E6{|QN!>$e@q~-t&l-k2Rz?wgpv?-&{ypo>MwL6d z+50DjGqfr+{EBQ>U|Jf6664^W_AfoCxvyl6Hi$Rp+-OxF-7bLKkMrLhOl|ITQdP1+ z$y|1p`1tULh(myGs!Oz0xqfejBzY8YHz%dWmfRg0i<)&Es2%+Ekd!${Y0N@>e3@)L zy5*TqV8!SpBNeV+WByIFV_wv6)HSd0^N*5#4EFP@3C}(`%GqO=1s48`9z4w420h_A zb_q9t*%2+$wIoP$tavsF3Q~wEP{6if_Kt_8a#+YtUK^rxOiUYBHPHzAK!OmbpBa=2 z<5)V=$LaN5xnaVC*yE|^_0E2_W&rB=lC8z|(+1$69zCR4Y_Q7R^MbIw>Q)d^a`lpJ{c|qN=4E=yc zcw;Ju{e`i+dAD_8e&uSPM4J3#iWu{R>VVfO^|=al&ixu-l1H0J~bK$8BFBsNNIC?rt1fo8o9VF_v@ za+25@#owLFn>fda$vh;bc5q-qeRQ{2^9G74%HC@0O+aw@9-sk~@tpv@>AqPL`ateX zwyJkMQk+iPPR6P%-v%1eZN#ByefYI!-pMM#=@BbgMw<20bej=ZS^mOwB^CNGZciplTxA7iCzb`WFLVp) z%;He=SJ>Cs7Kjr>TmaQ-fi4_G2*sbyYOCx-yY=kC`xs(%pnr9jp$0jCDKGMPCGEe# z*`c8Jm%wWZjZLg`+t345Sw$X#XFKP0@DKpx;ItZq+>D;+k~X+9rK(BKHua?pGqUO%g`;lR z?u0RAAT99niY0I5f}=Gxb3(w56KV?jBLT!7Wq=0gLFVuc zS(+}kPJ==J4x^ceKUuu8}M&nw-+T_wA!UThOXw-X!CZu_;z)&POI8}A(5VR$E{TT}oP zgP?uULQ#xX3Rjw^Q8uHEAbRh1JRcOh@X~j+SwOX` zW!ZQfYV@!n@Sp#(T4m1gcSz4?a^m_~I)rQ_3cN~~;PGwQqJ>ZC2(mPJ&=tjW+2J|M z&fY?;|Hf@h7S@WWC5JkJ*UJ0x=#vh+)437F{C@^Vx9tXP zz6Zksw``M)-3iJuHtDn~V30Ux6VN3^0&0W53JO%^lM*6R<1R%pLY6|gQ<;d{ef2eE zs1$cj3+fg!H@UtBU=2SyH1ALJFy6cOAo_f@&@!IGEQ_8&QIVXlG~z)V`Je3DHe3@R zaZuZN+tygvnY1$Sltg+&uf8SLE9TZR*8>J+Lk+UZTD(2nMSE)fK>C|ZA}YyU5pa@1 z>lRM1T&DnqV%ZMmR6GL6zOBK!`5<;~!-jIIN1WbHCqmL$2!A3`>0Ug`Frj>|PQ6t2 zgUtc-H=VV8GTWrgxv?s5uEy_R;m2ELJ8(O;`|v@?VN&bRdwSd-A{XJeKRg$^f&M)1 z7p3uw9yq2bY)<8jmAfHg8%Pa)DO0KrO`>{830^S3NOuTRD%#{fh{gQh)Bx#NQ|7CrfPd>w^eZ zZ6X=q&>K6WTx`Ly%GOgsCc^K&4LMX?Y>`AjN~6z!n$2Pb>sp>I>}jQx^Ns0?T{9ux z)xkw=C|47L?~Z(RE($Cj0cMejT(rn*M|X6?B;EyV*M_ZNT5CL^(t@-9(zG615Fq5N z4N{LAVgPfJExG_&G>ckmCy|*>V9R1xz{(gxbqY)mxz+?#UKEL)(6dEXk*$)r0|eE@s?~0(SfBhUjRd_n<1s|{QtlK73PW^} zuKb`9@N$X=F)8<65P5mBUHxvRpa`9RU3OU3ihnayq=LnZk-?$1Zi}01bM5!ax%-CO zYh`yT%?tW8(i`8k)z!=^B?`B~3buNNnbsi_U_skGZNTox67YL>H-&6_V5x^Bq;n+u8o+| zA&0ufFI)n-b~QOT*H4D^EtSEyOC!VW?d=9-f&~Q%mb-Ok#Otu^C)fqo^=iao+z0>C zOsXCE%<3iIVM10=kAd+oq^{L78Q>)>IKbvk;Skew0D0jRsd(W*Q63gXaVJ zU5mBJx^R8R(NgiT49Y?u4((Vd*pJr(^FYy~q@1y$Ftzr{({ zmlw#Y?$_C+RH^rsO|b#cZ8Hjn*%qRngjaOPBn(r^p2VIl_=`OsdB@;=&Js5lS!kBb z;GC}CJ3CtZ9aSB?R#aLk84#B1O%;SBJHn1H4X-tws)MJz4!6;5%v9OY4*VBGncS45 zN-?zASSZATX+*&^!tlt%@=h7!b>-b=?7KlPN9ERpmGD>Vd6aSV;}IXVszB zF9_XLRrmeJdP`i&z{x__q7v3Uxu8Mr1*^1jk0NkivyjvsCNfH!v0ffsY(H!f{~x4Q zNYnn#O9j-+fCvhrO@FzqHf>6?sYZYKx7@~BeEfsfm)B}S2@ zYD(AZ?)MOcTJ{D3tf=K3$00eaM0nQvNd~#SM__wQ^4#~oe2Kjqz9z^O7 z0{oop`Q|JL4dfsc{844!y>O3;kEw0AQ)WJ$rC??Nqe5gm;>0)V)QGMaPF#Ax&GrE= z$%Xm?rE)|FppLxNWV4D6zT3$mGn--pz;m3Im7{QLD}8u>7Nn z?k|>>1wwdpBo(Z9^iDSJ5Nw!8t?(samy)buIm5A=us zAd|&)r9aqAZo45mVt;Oto(;h#F`}AT+T>%(KIE@SXrC0+$nL25z9G-wMoLvQt)EE) z*w&?L9mWRnYa97I@TwByXi~%S^DF4}r}hqBnI7Gi;JFfXZuG^s#pX1xx zJKA-NyXQ(#Gu4kWB2102JvaHH&Y@S5*fyKa4X+QTK+`V0uMW4wPW{bz`AC5O1>a!i zXfB^j8Dg%2E_Eeqq1kj*W2Xp`)gh`e5R%=U_+O+Blg_;oFxvqSrI*nB&Z`RCkVX zce~_v0m>MtiEN5X5GhzVYR69~K|O)0r+aNwzxGKR))$1%Pa>iUl03&OD4_ zi+tSLUJ*PuOjWmy3lfC7Am&(i($SBU$C&tqr)AEI&aK+v+b6 zY^6$Fc36@#a6-z^hW{|4L17{@&O(J`r|?#V%hz#)Ckh4#i%V>^1iA=yS`k5Ddb+-w zWc51P7o{VzybsOxFyMHmI&jJGTe*Pq{t;_?KSzrv66;)IkX8exZgq1IA;h^#fT^ao zY37%Z5`ecOq)Ullh!O#Xv$=FellM~;bEC>L4motOhB`X>U2Nr5`zC_K{+IQP4pK`t zs~PJMLTpcrgKt38=?BB6ku=*ffZq++=>#i?Et{X549@mdY$_x2-!{?A+Xj4zWrfy4 z+YeQSQIr;2)y+Qxo17r0d@W9!e+I0D{s4e54GfK6F%YAbi&i!296S+wFQ(6JI!xxy zi=``$sU#@Af6gy{aZ7~?Hr9ES&x(Ijp%f#Y$@-+u5J*sK8O1xCWHkLN)~A^#cljZG zc1kHa-s4$y-V0Ea7cvkqc?;fMQ-ORk1oH#inoeud_u3r*e1(Z62A^`UfU*&(9eS)| ztjb<`OBONhHHeB=%o@|qWB1e|nWsEQ2+uMqOBomF_tt0DTV^W7$E)hXLKyebb&GG)8Q?6ug?qtCH*N#1kHsG&TO z%=9hC4o+J@BJ(j^Ao?GCT+vMi5^?}9vbUQZ z8RlnWZfqGGhw@rDrzP39V8mdgj5%4L~5i0nG4_@ZU#~=jYnSU@46`l_s<>E9ZT*Hp|MP zN|en)$DT{AT1xb{IXuh%d&^^`u;vE`wDfLX(*R?$uHOB)a)58#tB<%<;=Plnqqyi; z+4uGLvjxwJEpQ&YHa3x!nP5TgP-VkpADaEApnknZ*59N?anwoUgw0&=-QgYGP_){= z9Mb_>Q6j58pPfvo8i_W-+QhMsSYHA?-CPE2#0k;e>~cW~-bst`Tna@}0Y7tG+LINM zuTr>_h(lf&K-enK?C+)kZ%spZtmsuk{WZY)_?~^`x?Hb-|38UJQ(p%do`f7!z66}8 z?h7ri3*9!DA2jxV_=w-%tD|AQFmUWZCqrF(1x$8Gr>+VxnzIm9Woq%Dr!)eYlnBCw-mvIr6<$3MhI0-hSCoMM&i`JDS^y3FufgC3jPa?}Ku=Z1%y~Qo9o`l{Nse%~ zG8K|-WyLkJuJC?9=Eyz61oqNh{36FeXJSO`aJo;BU;KqO#?sXBU_o|*nz5B0yu&Gm zY;SLFA9)HD?DSg0YvWG+KL;S)|C<2hfrd;nx}C7pABs@ED}c)XFz5i#)^rtfBjkj$ zxL|&c>nP(&`)Uf@+~K?{ssL~~U>=7RYfKcFN7E=Zm|)+rlG+~*%me18x9NGW7FDk3 z8}R?MlK#4j%5=Gu8gqP>?q@4QJ6lu==E7Io&RVvpZ&ey_130&9s;*L8zU(SF=(ej? z;Dr;Ez6UohTcB3o)bvSCOanB`N4}Re0BGf00M4rC?gPM(tcD&`h#sS1L%Ob0ql9Az zTwczcjV0%2-K^Ik0jaa{{ER1;Jz_)dskSjps1LpPP!AnkJh*G z`7<}uCHBc;J89?%ljfv#7uMU_3lI6g)owoE>aT_->eMn|?W|&>HpfR9wN@zsb2*)Z zo*i;UhOK5U*ivj{v;{rA37Oc>ypy4Jvjk}@vrX#k$Z~PvUjD7UqCj3__e0i z8zE-IFkiy!)yX3)On!@$f5%NQb(;JGl>#uoxZI+Z0`B$mMjs%VJG#v1YrDb5(Sd8zrSa%2FGGQ9A3LHUaYD2?3sdmt;nCQpLuniW06}J%SIt4Z8zoFSaQY{4mBCKbUBhE zoF`+bG>g=gOAYUJ9%~%ggW>fZ>U&4T$dVRY=MdG)BACp9x&E!DGkj6fpMTxqo>z?;Lgo@v2%G!$s44Ur&gf+RC&W;T9cL400GQ?V6HB|HfeUJG05M7Q@fU8`W24@_xKG0 z9GSX?W#(vsNgZ0?R6}8{$ zy4T~=TD3J+s5Nm8=Dh9iNe$51&x0FRifS~H&Xq)z@yuh@QC-N3RMYN^)n*{dIQH&i zI1yq+JaSNp`~N4*$P)9u1CJ}iJJnxg&X-1&{he2l zHdi@yt3J~aR6q9W;CO;{7)es&oOo$7#n(j0JjfyO_vTWgzE)NCFos~^q@wjw3=EcHGB-?@|UQ&)8 zYFPz)Puz$7Gyk{_V(J18d=apAL^J zn%UrM)l0Rs#faup#av zJQI21CF@Jew)wxCy~yQ&+PoLSUHJ`8aI%{H4mcI3oCapOm&R7sok50z&mWp5opmIT z5(BCiA8^$dGa5G!3b7?mwOeLWU)24PEP_(ZCh{i<-u3{-^t2%^p( z_>&%!UGbZV_Ia_;4*=RQY=ta60QSDniZxy8M2pdWqBlCboapjZTV;t=_BH#k%AgWK z&D9j`e0|Aulb?S|kcS<_dR;HADb(PVz4eomdNj5I{73{HF7Qub=>;zJ%55v&9xcsH zw3cCo38Rv(wE-S;={=DDr1a5bu{-8dF7i}K@6YMr;}M6ix+re6%eDg~P`fj^)_ZF^ zBSEYW_nbTO_(E(DU<$J`9Ri65N-@__;`nyYQZ_$nZgmECtj6azFwryzeGXdl_B<`b zIoz#+6Jx2qpnkvXDNm4KhL5n#GXq4e+=dzBpZ(z-s52LmC-MSD6Q=#70qwHKNxB|v zp2#?UPKCej2y{&zS89b^SD$kEYoX^rhIc7m$Z~$sAN?bTX_NQ&kSjSu|IRU4HK&baEGP27}hei*@Hyz9xpKolS+Spch*`d^?$aBDjRja9iEi? zit1Fo8*}T}5&nJgwKvSRF({k|_FUbs3wkjOq^sO6127D(#7ftdljlhbws%Pk*j&owznsD0OJM>lLtm;C!8Us>$7^}Y*6`v zsT=EYkglSY=Cc8)gAFwYy?Ta5&op8-BdUf1mbk_WrKbuD=aPsxhQvW&iJ-xN*?t4& zkZJYQDQNI}%HgbxcDPIJE#GLan!2_TCBN#5^_V-#9Et%+Gw9jc@A>+<06WYwGGa+J zII>igPV?4;=9DlQp&E@#1)phLEKxQbukZf8Pv~PqMH9Jc zUa~j-m=6P%%#i(1sFKJ@{Cu!NpO6Ol1T1J(SPDQ8sJzy(o;t@*Kh30IfpXdt#y#Iz zatq6<8D+Z_Q)p61V%6lOCi>!?_A&@we~=5erzVVY8P=Q#)6xMo zne0jcwEbNvRcNeC>MO>>Efl&pNRyNms%Ei()MDL@2Xf{gd)MoiD(QekHS53&X2gn@ zPdIfHgBeTNdT@nJB0xqmpLB$pD!719X@VRkg+zL=FIYlR2gn8^GOw(CP)vDrAUkg0 zL9q>{*q56rbLvgxSU`JK(6Omp^Dykv6P2%8 z1A${=lCCVsMvEW0_=Y!Op;0ePQX9PuR(}nMU9r3(NWZ#tw{_JL>Pr$PNNjMBk2y-= z4xbRa;ibtxLN1(l5w5m$-Thz8TC!YiXAkqJ2K1O*0C;8U{fb7q&~?(1161|Ofb)9I zBEZ7l7Up4=$>U03J5w8Lt(biTZIDwnztwz;U{N%4Bcvm>A~)G-M0A7TvSL!5JSLNv z$}ae!GDa(iq9;_FhB7qHD#DovGq`Lq_nr}N*Qj_=Y{c9xUnI}Jap4?Rp`Hv@eB@#= z#m>Yle%2J^hCl(po~-jcWJ$S?z2xDEiYhOST{!79X0h3^!N|z&Nm5k+sV7rD85>np zgF}n{R6#pd_q7+s_JzQu<4z@N>_`zYSuxo>H1xRtzf@7rS^!^Y5ol-qnXd1fjjpsL0})n|#IR4uSi`=Ob^&VWHJ?{==waCes==OCD0*fd)e1zx z7;+oun*5}H^KM1F^*JpQVF};vQ6tz-bH7a-AeumG)gMA#iZkb&4V>Bu2ks5)`N&VV zI>&xOX}SiG)ISps{Dl%lo7C8H!6WA3FsBfBT`%?3x1mqV5O~x%*b!g^gm!=7!2d?LN)3$xb9r&gXq zCqLuLux+cS3l5M+$fDCl&TU)px85+pWXcE#-!UzGikt7AYHvkflV@X14-8B><{Kuk z(%Ng&H_0xtaTNW0QO}Iwpo7#VX|pxo_zT`YcS-$)kz!FUPgfF zU_Wf>gtV*OISpI(6*YccOPvIkv+DUG>vq++C-B=1OZaB75zdoC-Yhm3ze-r{uECXM zkZGkrXfOra(PgP`T1qx$4Vv&#hU`&Ei#%}xm;M2Yh{UBZO{k?}(e}-C_!YR8ntCKN-7au2<3Ks5C9fZkRdjhzbA*qcQ+!5ZH z1NU%FskwB0Q($HaUAJ*9w#*wJ#aDa5naPs(Mf{%9`GrO)l#yf;cJUP60m~!+ns|IZ zV*&ZdS(EcljJs)SEUo*M4<>iCoe*Fx_rKXiKk}WOvw7)@^zIjG;fTm=F)iS{G88Vd`n6eH}!ME~anm;$S*b*`0vNJQt*Uvs; z$h@!2GVl!Gg)3z`5DwC)cf`Thf#LgK_(-T?CCYgju6RDG%n08E7|(RD?)3>5REeT* z>=Il4(}8<0s%n^E%p(}^?q!Ovq^|*;yuQO%2d@-s1CE^su^XmfEs5{>KmX+Xa*u+N zc!^!46`~5jvExbwZ+LI-SMJBRjN7OeoPdX}ExLmYt~KBmQ1n*cx>|9C@in73=jwG> zD{T7I3Yc7E000}zZ7y2B`4Z4YtL?_Na%I_A`n)YvY|CO`{A_Cf zWTm9B453O#fOm#&1~veeG%fty4nV2-PAzTkI^ZbA9g(zT%4SpAb|G#86YXC;8{r1)0vz7QSh%(9<|qe&9KvJKqjnN~HjbV50NrFdfg{ zaNp8@Ar!*d22cr&>z?oht#tS$NSlseoDPs(VaJ){4_eQJl`lR$l)3hMi;A3a7|(-u zhf62;uvJmpw<21kH{T^fAAzy(KteCbPr(U#w00UeMf*D2Pnq-a(VXyRJ-O9}5GP=C1ih zB)watWFh8F%d;i@mWI*ys5> zUo;kSH(K@yhg|UoH}zD2S33s5>Ms`$puqo7K<%1;cFOfA4QxH7$mFxeF$Vyd#nQ;q13_FE& z7JCy&w|xF6Cs$Y!c2pBzwBikwAn)2)kf{-X|wozp|J50 z>*|0Z?@&y2%6U?b4U`TN@2PkwgX?~QN?T8f`bZlqOJt1?NhW>5g+i~D+@F^%KuTX; z$@}>%YDk<7XM!nPi2urMXqkd=t*+l~)t_u_a)MJer8Eeis@nskMdwE^Y|eNO6613F zHTO}|pFgGpomRCZWm{}e7E;h{>qDP@-M%b{voq*4H;34=n#TOYj8VOq4?jkdK6?(wJ6#WE9sJ`vE zGIgCEWkD5IH~3uqW1Yboq7&BDf7N5Y;(W2DZ7U8yH}!*80Kk+<{@WBfXYlattLF+P z114^oLDc%h*!1d&qv6IRwlr{fip~-N+3Z{-KL09N9BW{i%>j5MLe_3WYIL7pT;Y2w zdiq|~n;cAP0UqDDyFXsnB2eY;vWDKaq%^tjozBYKsQKL_8=|TDOOSn#xHx6H-4rtE zKkW^jU#=XdN4m4C-VFDU^LP{DhJDnPadT3$tlj2nZepNmZ+U+-?enM!KfdJr)?7kB zoyKl!WR>7ce0M~y_RVxQ$HrW}Hj z#zI*wAGO)1w#~Iho2%-&&RyrjLa1CV7Ytxu?Y|Lo;vj7c(a2z}3K#W!$|mE= zMW@?%w)tUBm2$yWw`6fXZ&;wmHK<44KwXJwey+5DX1#r!t5UMx*zh)F+N1)DJZlnp zeJBTToJ_O6E&pK0qoFM+z!AEjecF~^gin4$-xLF-5_a;{jV@Liv zJC^Xj6A+DmwgMnNpgUa6obMvG?G)t#o9;3ZeZq#qTGx?f9rh!z5T*z_2ZbaTCVs35If!Wmk`S^IQ=?PNXc7I>)&~k$mB?UzyUyLB+Zu40q=YZUr9e^ zXt8ptWu?t*fWqVd5kbb@j0mLUj62P|Em1DFZ;8pRPDf z47AQdR%1Sx#J2+`-@M_;<%Tr_ger@9a6M{*X7`@#~9$g4vZ{$USze=^ba zRF#)IbP+;iMZ*BeCZKjltMi)&LeG$e7r5dOV1|HK>%Wbrh%7AWP4Z zK}N)NLE#-lbi)Te7oJ6+9qTxvZ^(?XrWN4rMQvL5CDm*$I4q(=579(g!IF0OxExw7lcFZWeL zDTggq(`x#hrVv}|xL!$0ICvehK00j5d*#Wgo`1D>_21UwpsKH$6Vk3Cao^Jjl8K*p zs=N{E?o4k0`N2(D#|woq)HB7EzVt*_lf9U%3Dq4fHxjZawYT8h0leQlO)T|xL7vC! zn;T*n=8@wznzywX97uSd*&bYq#Gkpk29YEvCw^cH4yx#hCcc@IG`45>m7ft&LWke@1=$meAe z0E_1O7}6>L%J#%H2D1lYb#0hm_NrCTNDU}FZ5>S#HrB{pnrwSp7f!|R7IT_Du6y4?nQWL2 zwNZnERMFq(bm&Nohi}YjU++0?Obkn!tKFK}z6C);v`nD-+HfR<{x~&F%>Uzc@dX8A z&Tm&a5Igfj$+L-980H3CYS{I?r!Al>e~(UR1zq=T?%OruvXhsi1F!%3o%Rpw6;!&KpRzB$xoQpSo zb+KK46{rAFfV>F58tVLaN^a4Sil6?A1@Ql(>h_U+zsVdfT?2N(Kme=n@(OU!1WwW$ zfD5tp$enxWOqLY3V{!{$+B{w?P-adpf*LeuCdPsIiKa?X{?7m^oc_NOKn;IIZO8mi zS>Bq=LDc6u01rIEy{?0&Fw~wdT^2$6YK+{+UWOD*IzM#-HGmBO_fi9v$o!%4i4EH=j>J>GUVU`${cYyqX8Q|}tZl_gTduA(S3-&yb|v8F;ex$l^OqIH9EPPADb)R9p1Tg}*mjvBqV)YXX2@!& z|A2{^56$&2c&!iNVghT64zK zDa-viaIFs*VXY;7EtoRk-eL|WOQha>j0(?|I_%^f7XiV+YEbU5$bSWJWSoXt0`!!I zW)T+%u7PxwJYn3yIheiw5&T{wU8ldB-u40lUxq|?%#`G&Yn?a(jC8Bia>Sav7bw1z zuK=9}N*NFzhvh$U{#xohu6uVb;WjL!rg{ELq2rnhR`Tf!vDdI7-tpe$4L=?E{^lR4 zR;R8>Z@Hx*?<7oYpFal*2|aY8Kzf$!k)NdJgc^+PesOW;Y<7OwmFgYUDEMGa&w$5$ zkNACuukZM#{F99>21m@S^nHGrB6b>o?N}gQV@f2DweX9xs~<$GO!VE@r8XI@lBWi` zmuBOe$5cxgrbu41tdCG#x^`?=Dn~yA$j}|)18Mf|&j#P_>jWZqwEdFugWcYW+gHIV1nq;(&O9BK7Zc4b8s z^dWk$j%;VmoHK-iroAALM}T}VB>Mqpql#Y_c!eS=fyp$Aveq=t?nP|df1{!N7#;be z89gaZYgOiI+M3;IK3A2AhA&|UD6-1mTSKOrx~?vXwI8~Y2IpOiKJntLKJOEAL>Wtu=R!ov55DxAnnssiS(LAPrh8DanjhZJ z9)E*qDc{(tbHM5OhnIi7h?sKvT5FPb^VtYM3)cy(|29_ApqOLd55yV*C7+>!&XrI> z;_s{ePxwa3Z?@#&ChTI0V_WumZxKB@y19N5eVhbv{DH`4-Mg50UU0ZSrZ?F7xVRQS z8EYIl`OlKXomLz_3$GPg&`->I~N=5M43zi~H*2XsIir;}tJY>kg`w;s4X zATP7nfi?`Vb||l)kw4A3Y44 zA9xur4PcrNv5vTG#={6XDXb$zfd3?^zs0M(tkW(p%IJN1RMy_8Dk@0hW=B%Hy)H*N zAV5)LB4<=TI2v$@3$cN5-yMFdbtE{juGi40daf9jWwr$57MLG6GBxH}TZuc=9r(A(OQ-ft4ojyJb&Fg;B+FOKyrd z*z$Dn&@L5s!F1@etG`(P&-eP{n=ZThjZT|<{MN_=g)ORdIksWMEW2kb ziH-EbTQEOaOncOnb|#wtYRlQG{c|?$j7P_`0w;_bjBwBMs=9BAA?M?{*Qp_{%Djg5 zLW={nm=m;(dpL&@qibmB{FNe|b>SHd_-p~;Ij`Z|$h-Oi?dqn~#gDw++!c`{TXNA6 z0BwNnd@i#?O}rB)G%pxB9o#z!rD%ciL+*fiIpxDCLf)%v?fxsznogBjo^dTGCO=Ko~^k_xyAV8FyoLcGwMCapi zSDiJq`dsDuJzdf;TQz8s%5pN{jolwXcUS~O{l)|z;4f`Q&z!Aek2jCPSNf(VnjgH) z(k4RJ(UiTt~UzH5ky z^rME_M6$p|pXZY5me{UVU6PoYs$S0wi-0b`*&ye;rO#XL1OL0^fIkn4k8kao-G2=J zA0K5Sr>~Eg#r;0E1=X-{aPhdE36MAK^_)cM#b9w8rnrF-ji1MTbtA{6+KSU2T-7vg zgch~N%x-m`B(*ghZ?VWs6i$DcQ`S4ADyoPYa_g0S!YueJ>?LUc zph1hhj4pXI;H@HBaV#77G0Fx|*4xQiq7>dsdQL>mJ>v`4|3<}>(Nm0)33O~TpekHT zpPc}Sm?qx{dM))4HtJ5p-$x7#`LDLmU2?envENAkk8nQdbAmlBv-tT)JYJY~WNtb= zi`^q4nBjGn1IH+v%`~;WJIxXN?>Y}<82es5-GBX@)<0hy?Y~~L0c>$oQ&FQq!P_}c zbe?7<;ecUGui-V5H1oD_Wq!DN&+4T|x~z+fSn7U{5{{NxaU+PJ|3Y^m%n~x~A^np# zx+wsCOC=ISL#z`+owM8risA=eKLDA94R!FFh}>POks>+TSu3dAb< zD~l@v^18vyH7{cl=7iGA1m5zsp}EN4hR0Vs2YUPfdyq)?sr(a`Lj?q37)y|Bv1rl1 zS#qqb$n<&o=aOZgi!}BA&&VXi%k#IM@w?5eyA1MuB9d*>W3EVUDSuQ#!qUwq3HZgX zazR^Ts4+bWke?aodP4__`5x`6^q3FNNPCo&tLbKkLtPs7;ATkgbCnV-e|heXk11}S z4%?JOh;_>MsoG9Qo{T4OF}++X2t7*M2H~c?@yZLU?DVI{CEQ}R3>pX2U^!J16DCFP z&Xq>QRbs))^7Q`?yi^ z11Oti_m9OtRlx3hc<;jkBHGuh;~-`q{?5 z(pZ`pZ=JX)`T^;$WUd*G_Zcizbt)~DSI_>j2dsoW$4AU1P6DT<-bU5rCxH^Bvu)5| zxgrfHVB-=cu-C90x9VQ5-X;HQLD-=}@>)!Aw^QBX&1*abnbYXu=g>fLJ?Lc|2PAbP zFW>Cx*)=B0hEiL#tkZ%JK^sdXjDNy_K`VjlFyN_zbQ#pb-TLtFfby&_mQRpNO%dDF zztvkSO$amOSF(1!N%g(Xyj?efzC5;N<`A`Raw~LT5P!tOf`Tf=kf_T=c4XZk2a-?y z{!Ind1pV8!UbLe7A)dG>TbL|})+F);zUM8x9lK%>wA>m2mH#Po@Fgu%w>mpe&|$6N zQgpq*v*K-9b8K{q$-%c~Jf0I*RqFQ~Eza{>-&S{16w2M-Dv_x8l$+FFVN@hUT2T_T z&U#u7vME9s`~Lev`&_2eeBw5~T3K*(G#-`v;;3w$DBk(@JzBlTYetb3`4+(x)e-NoUZA3rw(FN&)o{u;eA8U*|0HQj@G#4?TqUdS5 z)6>eB+)Jz!MJK~HTb9gp0vXp-Z9Xm*ckg?-Beul>?U9f?)CDFirsd{H zna8;; zAhguMsD$2%F)8p!k<LC7sL^As2}l-<5!!0ZP8Il_7RxldoBDDs3ubFSNFF__1N zI>f&Bt{1$z%jVWxqU{6@ki1Y~9DwQh!G~Xu@q*)~Yn0H1*(MwIQM@rFLnNxp--<2UnDU3u8`@`Dk}>Y;_#>y^=nl$gzH zW5<72*w+RKH7)T)w7JQ{Mhjl8bXHCb^4IG-W25AS_qer7T?ITN|GxF4@e2dR~#Np zWF+|8Jr&w_l?I<)c64E3xZs0H*wpp_#Dva7>uZRk}BqV#C2sWZd$c2J5h%=BTEc zUIBNZg3D|k_hcsfX-pz=e4wL?>sVjATj)J5*hr>##qWK0m+eCnyh0Tdx_T7;t7qZG zR4sXfXWYx_b@^+gk{48G2ty^TrA272wy}N~eREn!7s#qCVh`EXFV_6mwfN&zsQ|Af z*d(aSO94_$Ie$)+nv7tV?=kY*q7LBZyV&w~l!8!aq~~0z4?;xmwi}ojK<(`dy!AIyEy*Qy zY*iyh*;E=d{CFdpa+r62(iz3X43JH)Ry&T3Gqde;&uX?)>jP9f-!;+lwAP+v{Q1m_ zJ$dQ|DTr;{c-92OmSXKE7Xm8=Lb;){ePm51kOcK0ep##LQn&dSy=DY?=ChAVaHMS*czf^1e#BwbXUH2#xQ8PCOh zAwBje0KXghH4^9_{uGfhR@N1N!)(h+Ng*iCmu)vXO24r*=5H`pdts?&hcJEuUY)gj z9c26(NwjXA_hkdK$_}jrXq+$CBLAe6_h8BVpNjSr*QS9iESJ>Rdz^VwCy~FYYqyV+ zB^Lk(yq2d&7x%;5Ye{Ums%G(RX4e=_wbSczE?D#BCXY%4rwb`bKZCcYA?9i zIMm#g$RD48zw|khTuw?jd1608C(0POZ z>RRb#l1n;rdLO=giE1)^ZVsCIF;r|6SA3aNjiePFyf^BRZXk5E6aJ+! z*`f*~fJ@d_X!TE>W;q4z+_ZvrdCZw`cX^MXDz*eU!$L$@t_BLztr~vSV>MM?YARGx z%=q1ff_c%R&=I1cfqCI7wEC&;#W7O@Q;51Gs@O=G;6LMIpC4KGZtfy+YPJc1nq#d2 z)ydUUa|_mA$_qNYhIF{A(U$MF|3fp>C43loCXV5)JM}`N$?gWKp(D1xqDOR~Og-2N z5JnVNQkkF1l?Bn?0l{K8tr3)47}VJKY8zFMz%^iU^zTzPK^-Q=msj~m-oN_rMqC*+ zou-b6Gq~*LIg}!-eg5q|RgBggb5qq(vY>-}-7o~R3W z?8!fO{lH=fH+k6zN}0L|^s4-s?WHkCN1T2@Y{d7n=I5ui)3yf8nmY6Hv?d~lL=jl; zSkVjI#aNva!6SOWG+@YP&W)5(gB1*@=J>RSJ7FiPqe_^5|&cX%1tI@ z4W?LY^@<-Z^0+hFKgm0P7{YoXy{M^$&JHEQ_)-(YKGB>A1mGHwVDEvqCpUu7oO_;| zS?rh~Zh?-$m3D?dPEvR4jTD|(&(W7Lmcd$tx8(>+kiCD6H||%ijCLIsSTg_iV#iZo z`Bn1m*q4U+1FlNH zjinjAhEz=fYIPYE@Bh$(ULR?V#}C#4bva8wRl;pZLnPW(6ZxLhj6k{kV>GJj^84u_ zVfWzQPGRK7#&>q@jMr0h+44N|iqC-$FjX^6ozeb5lE(XPCAi*P5^|CXfV&VlE52~( zi*26EM6L{sLv>|RwW5y;ckr@9hlkK9uFkTg>dQ|N?1i9fkAga?XSQ+ycJ25)BvJP^ zP^8Ldd&jLP($Ri|{gT)-{S_rJk663L#~bp~|B5I_CO?v31dM{z>2_>w$FAw!!g!|R zcEvTFjw7&adL-&jbUp>jv+!ShfpNa5X>)KO;qPUW`l@37e&62 z$zB+N)^y=hF>sk!Ayc!%c^{FxHbMOh?2gQvb58Dq^B#;aT$5 z>F_d9BLCpPdyQ&;ns*m1zOaT)cDd(sYs5cNEB*Xr!rk@+GC)xh%5XQ=xyjB7viKBQ zWC1f?Y1{E8#kL@G--)=37m4#SN1PS&xEli8@Tmtq4D716E5h=HBG!FzSB+x{WhYSV zW%p%FPw&oN((=KHRa zC~d|-bX;o*2y#?IG;C|U6t>QqrzRhjk&efQEi7yar6kBQ^v!_ev<{8q;MenG{liN6tA491)BWI9ODCTWC+;WOTXZ>jEe`qOD>#ze2DWJMQH~KT#WjCMvfh zb{6}*C?U6VCci}MbjrV;y1S0a9lt0WN^GsdNh+KE$UH1YfmD}`ZFw=4s-nQsE%5Z5 zqBn7I4vSc$$i+ACrH24Hkzex0IY6|u5{T)(iT!Q~F)&qZAkL)U6^WV@?l$)Z5=t#=vxuoh8Z&b42B!8ksYXxw9{N8bZmIqgEpDm2rlXxM)s zdOzJr#RN_yos8SYs(z72dZtaWNiPQVRZLLyI4Q)ChFxO1(FmS{KlU;!79 zB}P^jRfO%+Ifq?hzKR=21E;vmW+Qg`|7~LSihsQZ#jrcIh5`EQ=X;lvkMMC7z&yKA z`DrJDFztp=cl@y2kQ~;W1yl8=jcj*qzkX4A>!j|uz2dG4T!0}-lpnZ-znFGkkd`yK zV=v;4v2G#R4aX;7(@j58!G~o@tyK=hM%P5fcC6Z? ztGPo!tXUJ84xGpeRaPs34kMgo0)V(2))$_M|K&ox1diBVtB(8)cn#+OWNpw`mGBc- zu3Jb^=%x1IwJU^Mwok#mhARgkl^MXkoeV4OQ+FA$uXDWZ(_5w9tEoq;LtW!$r-}2f zGokKY=ofu^!=B_HWMqzLLfZ>fKhqgZ&5yI?HH*(>+Yzu_@iZE8D`<-noQd2I+w6kQ zpX|^o=D%B3)!_fUMuC#3ilz0s?*_p1an;(y?jIV5x- z4V{rbO@KlN`TJlPIznF2u2=zLU0Ed0;cqc7^lDa5OIm-92AFsec@m78I8D z%%vb!tDWaXa;;!a?)0zQgvJSq&%V_|_QP8hM?_B^)dzk1Lp#vk8t#sAmaIOU#sr7u zU|bw{j~GAK=ifStj^B5o{_%u6FAZ$67r%r4%H{ zhJ287@l{J)#%OW$d8Vu!A-#2xJ%(i#i7*c658DafyHuMf>rF1*&Gd3l0HN835M_NA zq^@ggd4lRom?4Z8ixOj^`Pt;dopcj3g|PC^o=+r<=*iJ#5^(&0E|o;YMr*JB(dwNz zsWy4$diYC;6W!-)Zus8iwo`c18e3GZM0?1Z{nUPT+C<#4EBu|p=|cmMjN_;9y!Mr# zLg56nxdwcwz0($GhEFAV6X6Rt?SFX$$TP-wHp;^9i24681&D0FK|BGqG(6re z><>+^I7m@T*q%6va9@6uV|6=BQxgetui6n~guC=}s}{N>a>(w63{;k(-?tn?=3ui& z-8frj3WL; z7JKCe#gU&9lS4I3oXm4Ma#GhVXSG)FDZJ*Jai~ zn8M@UpPF2z=y4A#Mx7%U_ls5gO39(bFp9_lQyoP3OafQ^R|71`BBpa}U?Gr7KEM>A zuN(wZL_0X39BHWvULRGzW-Itoh8B4J7CNo{lj`1Y*B5`=fG{dzY*7|L`~hk)?)$E9 zh+Y&Bj_pjxgaZezg(R=5Pju>obOARy1X`0SjRnq_ZMTFsBw$r@S@I)YpFUaB;_*ps z3n;1v*g0vKj`gr~DHJl&^I4`%X>6~S&BcgD1&CQ9D%=8mb4T$?o7PchE=1$|y?n+1 zZ?yn&26UOoV{q=kXE(3Nr=^rVH74ghX%|P|GQqUW=BEX3<)rIadR%Yu5)G)rYlvwO z2V$wpX7k0k{ZAKjxGZB$cr!b0yUV$RW90Hp8BPE4pd4_Dn7R5**w0bc^E`o?QB$?{ zj&R7a`}(^?=;EV>0Kgh01C9hKYkt6`jlY-fv`2nwxMXV{ghfJ)yb<&yUiP9I)eN~v zGd@bKp9`zJij#euNo8xvHqP{{HNR`q{cSNNyl(-0_|El4Z(L;hvHN5hM1*=?etIa5 zDaw1myH}aN(6Ez&9xnNkNXe=*23lm7^{Gbh3)Q2~PcTi%KCm2dCpkf;bXq7;-Ux7u#aT50$bz=kVcpqZJCi<0MQvTe}{)(Q=u; zu8aE-M&?}a7RIR$1r09LP^|dQ(KMf`k`b(l?oM*qD^JloU>H+ORxrn6FBAU~wvVUn zgVt;n4_F2s3>)^L?zGf6)~)rZ-ahyK4GaV2Ape<_t`GZ|mB!h{&uQLi8WpuBIRekt zQkgy%*{*7nW7u2_b=lF`iZAZgvw5B^_Cj%!kmIIO`8x&$D(bZi;#WdU=4U?b7)v3ua-~KotURk)-7d0T;O-PQO zYnJ1Rd-Qj;a(~3#i?ww7V2z z63asJ5J$%zcXppw%6SMvu}(YKfhYD~B+4AVcgf&K(|qkZ2hG$-Aeo+*sTaDRWaXf4 zzUNw;eEPu^qSWN86Hlc@gWkz`?;D>G$ z2aiwsM)`vvCp4^Px#5QSIoZcKdeB{w1iF@aU6thUgUfCSRHSAW6lwWsDP_-n^booOGbK>N&G+;7v>bbvS)iz3^c~v<+f|d}uRaifh8q3Sqp?SlyWiM1fvY{i{ zx^!p!0NLcM7h!ImVjE+}@wZ)jCb{LTLG-r)3SG9|HXsB{}*d-9*}gtxBZ_PPdR1jH06@H%uI_X&27vC1*~bxnXzQb z+)+w1OUsR1K-9|2(v)dY(-bN*#tmF@O(7S=om^3KMFo`-5m7+I-^cFz{@rKJ^XK#Y zTd4R2`My8z>$+aoBQK3TOQq_!%bDpex0+Gb$X$y zojQIoA7Iv{%g=leOe(-df%YO07Ww`8GeN8q)5mLfOsaCac@v|xI@;X!sLRjFJnJJa zCNpFN6<`Exd(K<*Q5E7OKp6s4hb3Z zX2~t7Zhy?Tn^v~_-AWi-UZELg(JfB(uJ>mDg&k)4`(DX=|v+Z@jB7k&zc!%`EWYw zWpMmgW9_$3#BBhoG>nFM-~{ze1REQ5LBifTAPDN zo#2wxPPzX=turlgcLDBv;P09-?ann<8}iKdL(PEdEuixXaMPo&Hadcr=QTEh?x89O zrzb=q(Uu4Qnu9~{)-v4@a2zcWJGO4`y_6JEN1T{jUY52T>Rt6t|95}F#BViU~U#!?6++(Pmay3t#7vqan!L?>Q25p6zSbT_P<=qHCD~E)*4UfJyHF&^cqIBbIS5OdbL557A#(N ze2?Ea^<29s1_#4^4k3qP);@`Ibl|r|GNK5wNuFklzIl^>G6n`C>i$U9qtD+ie~h8=V5-h(RjXU5ZP3b@N(t0U znCCWg+8gY3#bVJ2W=dOHy>NA6c}$eRdF560F*;2U7Zbe!rzasjujdNW_e*RUVJ{z( z+k1J#cYXiO1_<;H$4F)1_M0hz!F?5vpVXbvb&g()(}!u(ad;6pHur2;(xBOB&1t=+ zAYv&sT(onasP{HCCi=qq6J`62Cc7ge+n)!#QcJ)xJ~K{BCrUMhaRdLAuU<+#M}mnq z^VNXV-%)=x1ytYqIMiACth))jslj?r&_athRtW;F`FBN2iB5Q?a}2Vw!DuTp+W(11 zC$Iu~=;~%g5J9M(+(}XgZj-XSl9`>>%VyuietkrgAsXL3@Sx#el&@moHiLdhBX*%| z-pS4eh*-olo@x@wa;|KcSE~tB_6QKEUQh1Z{iYmQ6gjXZeM&jor6#ci0meG2D`?!E zX(TnqpX|)1=4+HZj%Dgbz;w`AF_o&FVUd(L3>-^?LeOGOVO6;Yz0`McaU=j6jjt@w z*84`E_VJ(B9J+mCiyda?8X{`(kcGCYynBuEu)T*wa8TdlocVtz}b@c>-dPT#_ zNevx-{gsCt?Fn|-6u2~Re9O|NT6{;HN2-_VXCf^%)5MR0gawfQ31OEwTyOrMAGy?F zL^Mm}s~ltXUcNY@`RpC%F@^n0Z2s7VZR{-`j22&`LWTK6I!A_hOqR`IjwQxu{Kx(E zk?ws`-pyH&8b@Zzu@+r6<&Q-PfSU-Rg$@*RUFfoYI$8f8ISKfa&B>X=jXcHcnr>@P z3D#!La@A!r^!nu#iVx;2%NGDE&k%E{RU#lTqd;ed`=$HUX&cffOq_nx!dm=d&^Lx|^SLK@#T1SBiYEp;r;v z{D~3zfuo8<>->l;{vvFl2o=$`T7xCE{B|-%&*_K{PNYGq!7MpudFi)xg8931GRm~; zW7viTOB@wbt~yy~(CHyFra|h?2}3(~w?=&S@(gXL#5q&SZQI1Ba}UG9S}T`ZEB$9D zP|C9$C*>IrI(lAC%+hvdK;Kl^;=xd z!3mNH9@p{l`4sJRXyHLj0hW;`>HCVHAxcy_a)N#}} zZ+6Dgdg~1{C(`s!)J#_1;h2GY=xc-~ce%f(8PyAnjd>5gMo^L`GRc(8gz=Ta6sarG^X z=dPzO_KbK zEF?w!wKi4hwcI2ndi8UV*_dET{HNeZ+N&GKe%O$f54_jTe)s5VX5te*6w20{0fmk1 z1u1C4jU@Of{$(P1mXp022Z4OL)aPiN?3HZkz3$fEv2Kl6>kCO)o2b9$)&EbPhC?n7 zB2NqC=4>+3pO8wyz2O~aItJr8T8Yw2_hLaUm*>-LI3S#NGa_#;>?d@MwjSDU9?6_U z@A?2_W6M7{0%qOwz?y4<`2y-#RK1E!nR9Kv zwLK2sPazQw1>Wbs*3YzEYS|wJCjIrskYGhcWSd-{@lr~@ezMBk@&3La-Ao8^qhmWy zJ$^Pd(T3Cc^ner8b|c_C`nK~~PD)sITf$UL;a(WdmC)#-O2W6_;fKI@VGnX{-{@}> z>Y?4eRBjM{BS40yA6OWSmvz-^>g{w}O;sXC&ZzY6x;$8|=49` z_N+8R&DpXpVe{2E)mTLQ ze&Y;E4QD33I(tL{7N<|G8~GOyU>%u*Zzt2thNzIrtq#=dQeo9{%t{>(F2F`@8p_5r zX^Zi7fbnxlP_JCszOJ@E+EHFE(Y$NZF`2CUX5m%&-%e5nSY^)X6C2vp*i`!bfpo9b z-rfHYZg~;m1;8@&UFd(v40bKA?FdZS^F-h**YTlbHP1DpBg9QeS;t;Zq0JZFnyeM| z5Ixxhv`kj?@_i?{Ay?wbHr)9|EMA__$o7o7L$dT(LlPzc8?!Ctzo^*xCM9}7Y@OlM z?D@+4ZFV>b@;ze`%%z^TN77m8x4oyXiIS!!P{;tG-#Y^Ry9~wE6^j!$gs$wqSo*}F zwhjlEnq@;4nK~;Z(*j1scEpG2jOZwnZZwxm^j5|1 zSpj|ya9*W6(NTzrUY@WZ1$f}8y!CH^X%C6;Sfp%gF0X&o_}zFaK~)3JEj7NuoB$1s z`zshOS%~7E{VCypdl*%6(J(2TyBk=5QOc-hosT-1K_%AzV!sv#iXw;Q*EYLBPVM^| z=b_l)r)iSqzwy*VtfzqrOo(K#1|MOaHUrt~yKY>16ZvlbT&yOos?O4Iyyu`70A%k3 zfb5v0DPhMdibdj-5Yw9X&=~=YJeMMpJ7@E%0|Jjs=d)w$YRn>GGpjxfWs?rtZq*j=It<4HNa%RQ76O)%2js>nNxh9JGbz9D?sk5A4Dk2g4su z2`vZ^@Cy$)2rY=!BG-b@CSkpWrbg_P>T}|;9~-VlBKg14t;~j;Ej>1m&+8YUOQ~Ke z$Sm4OjUFPBYv8{D{P3BBNrt@W8Z|rgt;LZlcWR(ewuB8+!Lzfba*R^ejFTS(1Xz0JYqDy~-=*JHn-&jt_-j`tITSgHe zyPVwjYw?_9PDjQ&;(%ZsmE6X{Gyinl5zX37^{-gW7|--m{AzmD*F@O%DhU)XskaAg zQ8M5aWa_oc4ar(Eq5-1vO~CR^3x}|yzo+PDO^JTj(0wI(3SBv6it9cojL@>ZSgLk* z-D$=k=DkrA?nn8yM|z~JUyY;9isZYut8V=-q5Adztx%1m98^$-qd@;&n8zS>b`fkt z*!5VQOe#(5=z@|9Tump-#Zu&T+wIz$Q-6N+?WCj!;Px`bK7vc%RUwP z8dZcCc6KPo(E`5c+7(N7l8Zp&!?2u+bTG8gzIy7SV=O?s%=zXYs(X9XPJ-1%_^G+e z`XW>jC@!YZtMwJT1lId&UHOQ9mCe*r=EC!iBUbEbR>Xw^BI?dpw06GJH(4!YR{4YW zzuWi?hE$taziBeXvA=xW2tpYEGmkAfdK$Q=ey?T8eS~+VteElD=y8wUm(_y50>i5& zTdf{qRTpk@3#`O*anNHtS9aFEQ~$qAEq-b~<~L)biKyvERihe(PCE&p4W#=|fR<^y zX2uH7_T(`->mE@H16qTG^}aVagZZb`F}fkyR8$ZpOOz{!>@4_d>vQv_JeH1*=z8mF zAq1|6?e7YBVlon44bd{7%`m^}oA=Y#&BWYFfdj%XDKLTC@;JemL zZ!9|{iQCyNqOhB*$o~9+6KZ`v4hO+^0c||tlP|Yb&hInXj+_j|L&jD4^9uaYW6GZxGmEo{gnua@i71u}>EbAw)9 zmQh&tBlKjpDZNrv($#9250z+;@D)Ah&!kr^Z#DV3^Q$);n{8Rl5wM*u(_^m657)kR z^T|~jkNPVZx>fH6cjB4PgLcC=_9)4u1Mmpw6Zk7t3ns1;C=WUV?~B5pz{MYay%IkW z`5_>(w!yiigAVfkZLC8b|iO2cIH2iPoQion}5PPEVe!Ie& zs+qp!%3Mv&KSg>MNeF(;@vMoJiwv6tdW#Hs#R~X#^?tSl?2Y7#?(1ixJpH}j|g!6kM zy+s|CzH5G;`Qxwe?WpUTaS3?&J+!miAYn^yTii!R#Zfi)GLB=wf}(`--+FakLMNV+ z6RxQ+(Gie2MsK=3=)4iMMZ{W1-P@aUrY^0U78F6lc>GlK1w7;EazvlYCU<{SW7UoD zrGC=Amg0*}MO4TcAZZgbU1?v6D% zRjA7R!)H<|=lxIvRPO$|m78`FCr|Ii44;C`iyr(4iu|xnl;AK9 z+C+9O*m88Y7wr=B_6S}`YvzSl2iT~S0qlz@NPOxUthe#=0I7nTb@VB^&M#uW>!o9P zZ!$QMV{0cqh?-V7A9P|<*;yxnQ*`yDC<*uvz8Hl~Ze6bEtCT-AQq0cw=ZE$y2m{&- z?C9jWzPj2-pCWR7Z>h(u4$Y_Bd8bS?Vr?N1=tG8H6+p^=0xO#|N^tW3umI>P5wEWd z_&Ffo4a5sHZX8{wS7z-7=rk8CMwC*DS>NYLjH% zBJsSHU|BS6!C8tNxJ_kNgx#WSc!lqsz1Y22y*6DkT@0mEhvF7bfR{Y3YWc0426Bp@ zd`&+l2};hno&*BMa}cK8D7>PiFF&#KxMs`W&1U(!_fLxG-<5B;q53DgwgnlDeO0Te z%v~MD@r$e!L$+&vvHWUQG=+HlLvrHQ)!id~7gLp{AX4pV;zK+RO})I{S~FVO<)7U3 zS=#q_E25^9QdF(R^rKC=(?k|;QXOmAjsvY2iE;E~L6*opAnXj~W2U1~0Irt3yCwq( z^T2_^U|>M{^e=sU#iEC-!3D}oru2hsUSIyv$xr-N)vn5f*^uCv0~}^PxpQiio8BDY z9yttKZK};jb{WIFD|x5oyJB)bgLt&v+Afp-cPVP8u=}?K>(U}K(Ds1Ft-c$NcG3BB z&5?(bp#)I$T>Pk>f0$}lp0Ry2VHatbu3-f-g^|WLSkQa!dM7ngxDzdB-4=WLFVcub zw(zvg47I1x+G0T@CDlB$Qlfs0X-M(zV>s73oA_in8i`;gM=+64K+Hw4^W++KLR5e% zy@BiM^pTH?=JdR$N~*VFiYX7$Xy2?4?fV`QdGQ(l+Fg$+*-y872V?A)SMF7L{Z2>_ z0%0Tg@4`lK=E8BEXXw2}>!Bzr+{t(>jO~fDY&RALG|=~fzjR`x;EM<3#2pjq^26@u2w>h9 zi#H9!-T#yP(yAm1q*uA+my7c7)O$RXRluDb18$%ls161crLE!litT<0Tq6YX8UKS0 zIEL$EryuPXz6ItXbc}Sx{6J!SF3rO}eL<&C1tPfciN1OVi9|42&V$g#FO9)?CsWLq z*mOId=@k6}Jb|w4CA9{sOuNVcl_Y?_33^d0(J+`}*aVH;(jEgzCCr;D2Am^@6hzcY+#k8FC6 z6xJuZvIFNpF)~f|C6v8R>TYa{Zbf>~RGU2p<$(%XNDtSeX#ug9m zA-M-;QzN|sy8I|CqnNI>5%y$=)GM8M|Mq8LeHBpf$+6gXFiKgL4nnJPN&I?6b9Y5% zgGk5xNHxr*RL~Qc4J*I-WzxE9W1&lHuz=b-#_0Wo?k-K z8{M&R%7!@wgFJ<{Bj}B;fjV*dae3w<(`)H*x_o@oUm%|O2^-w_xF}e!x3)$Qyu<3@ z1T3OvaqhSE7FLd?PjrTbCH3g!2f{}~yXz@MM=fICR(3qk%=!4y!i?f1K69ojaZ27M z2>B46bXtACmA9Rw;cfFbbmonj`!3}XMMG2P{O0NLPGf3ajcn=x{V7Xh={1q$tNG0+ z(a-Q3G+ECd8WkmV#P8l_>D^^z+F#*!5u-J-JgrLJq&ob{3#N+4V7o2Mr)l}pGQI0 zrdsn$mgaJehHBT;x9cJB5K1G)@~6m12Ucl*w{~3?#1VV5z6A0ACOS>33hwD{QCQ>T zWdMN9pQ&ot4VNH0bOd(8*09)`+q2~y+dYtVSk=0*=9I5ywvK+b{!=QsE7q72^yYgc z2@QhBQNqz@@pmQ(&Lv$vGZz>;Ky6eGGHJhCO1T;+q3$g`x-VFjmHv4f( z<@m-8ym@L2oLUpIKds1}WzMA?@g73BN#>vIv#F#tKWwdjBz+n_5R5Oc+)Lthf!QpT zeLM>85&Kv)cz?VA3WVizpY>wdW4KHZp#F5VPR~K64RmKqZ+UN2S7A4*A34y5VFwCz z9fdCD@N;@8#YVNN-Plv@%?r|AuFy+_F|D3{+=v?1H`jd+&RiKl!P7L1(0IRz!ukB21})rpCQH&$LUsE{1t32fXQ>emYsJ^G|%vmW~macIzNmzklsf z0FG`PlhoUQ6#vqxVaxVer~#VI+sP`Bgic>au|>oJ*{%WeE?sdHer72c-w$wQ>E(D; zf-8fiRb0B6+c5QVvWKveFP5&fj09Y+rOvrMs)d*^dv|Lnd?xV-is>#hmGPg?R)U#2 z?Rb1=Nm-nHyh$7}HHfw}Y|9J!;AcVGNTCnopo!zff|_sx&|A9x=+Lb%GEIs5GiP%cKEAINpllB8xg zQr|w1DqO-~T+2xpZ1CQbD1pT|_gKQLH3VJ9s|EX#j?P~0^1S8fxIeCVGAL?jniqWP zD=_l9WVXer6HXMSDqAtn>woSzNR3o^0!5HGXJ*PYqU_|~18jHOt{i3V@_DyQ+=;TS zmf`Cbpu$)XZ%s7d4myvOfbs33G3k*gV zce(U|KlA=Yy#nAWD!t{SkBivXq&;_CF6C#Y1k8|cdgd$vW_P{Ivqw5wL%;W~Hj13! zOM#xTZ6waQCq$yg9h@vnfd64UKgXqVr1H1(?Ilhfq6L>hL$1!MQ6ZBCe~n=Wsw%{g1`v}sK5%Ymcpi9-QR zt82;R?Xl(C=HlwSlMmNru7n!n%VQhPtI-)QBOA4bsFasy>0N@E53O1pxJ|=L((k+% zfGr875(H67sy27N;vb_j0+vIs{*f-d-&vzhCfhVboLvOI;r^D$PO&1CV^k0)>U>%K zX|FYeU0>tHdKK~9c5R4-5cJraX5)5h)JYVAg5GEE175c;j)?sp?TX=^0pJQAf9bzt z)OEV`7s6&Y3Em~U9FReGNdYpv$!6hkG9%g5>;q8(T^5KtPITspKu z-N4p2NSl5tJO*Nhli@ef zG&KK*s*!`|^s1;Tc53AH>?&vK?7nE($i~Uj*Gv9p6A6C&<=z_0i8ZBcSevX{4;|hM zu>DMz&434T6D&aAs2g9avpT(dv+--v2YOFtlbZW@SndP8iZ-Lu(Lg)Zdv?9ftIHfXfN6y$$x!jYL$M#j zj^2Ph6T@JEI!Bt%Ujp!0XQ8f#6h6A0s-;6bhW@-x(qYLDK7bNWXxviisAqYI4Y)sYi;e;4iQEB!8v{rAGT<($PgpDqdOR09}> zcDnc?rOhp4S|IX!%o1Xys;xT~Ji<*4m7;&sYtHaA$(4H2s{|m%+Y)ROR1z|s&`!qQ z#t1mW%N9Q{JT)xj+mcfGVNhVn3YNamCa zesSnduKx8DKRpmfh;nwFTf6#2QNC%I#h;4viFREog^zYbj6GGWYycGnZ#iyCs1z5> zC3@NlNxZW1&BGNHv_{v#N%ZUK_aC09fSc`6lebyU445D$zR0^P1WeO|q-}SIh*(5Z zS1)hF+AKE7Zn6G97acvSO)sTJulk;IWcDH1k2jD5nzt0KBzY@us{e?7q_iEaFr`n~ z(55z$yl!GzcOF7GTj^_OV)mbB5a;FnhX(D+HPglx4oA&YA12jxRH1rBa_r#&4lq{+ zqm&=Ax7exjLsnb;o?9BFfV>!n_SOO|(nDv#KD_7RDRbEQ|9-5YE>%SpQLO_UzKg|x z)iG1>6#>tnMmGIKsygEC8tUNyEcyzsUPrF=QFPsu9KcR{ck}#auVJLD=mh{yBp(wK z(u!WX_cc}&JK;_I-ld%#?O>xc*PaJ}2uKG@0u`k>Q=oQ^t`c>E*pQu%7T$+4qnC{B zk?MBlGnON49U@O%Ul-)0{oZOoBpsurF>ZK}7HCpye3cRKyT`vjrAXF7Lr9$-dcADx zr^J05gAoT}j20hBetzdODVXaiaKFs5<{w#)j<{ENPoZce9JcmKAKb35KOKs~GM?a5_aJo?hCOEpRpPf%+%wq7hw`C;n-Ch;(JQeoY*v4_TdN#Vca>=`c^ z(yY|(D-7*(4AhLVcMO>?b!I*;@HYfD3|=LEGD>H@22>LXb(2g}wuS?sNJfAjs}Rb8 zf0wS>K-%RZ-ZH;yOm&7uu&?QlVqx_A(r>M0`dwGYq^zk|Bu1Ou3A%4T9+E?1upnTc zxJs$wB-R07OK;RBlV=rdBYupY41K*qJ4~UwTjoyx9fdOSPY~^U#%GT!E};M<=P=Za z-Lsid%-NJgJAu(;=QxPWin=0Q4hgJ3oV|ZOjJuXQf`Bv;zC=Q#Pa$?_^euL_c z0xrfskyH*GXZuSu=9>Q3^8)eTlZ7697#NP@kt8-8YjkLJkxjoZraL9DL>>ys?wy!a?8LN^akYL^1I z*2A1gn22ulHT^rb(}8?4>v_b(KmWs^l2EA>a#b|{$C_109fFb^7*^KEET_j~I~-m0YMN7J2e;oK0gfT^eE_>e%3_3RMr z{p}x+S=jdNWFwI-NMe&U2CCt7CJX-3IAts5leP8w&{Wh}b}mx2v(o7pFeE)99V19H zaKoVV%GB1DcuY{Ik!1Z*dtV6WqkFuP@{x*LX)l4$K7H!6hxtzKVA%3S($!XuefQc6 zMb__&MkZnJKfOxY8h#-zbFrAyZoonTm<4=H#OQvZ5w4r9xNDmXOL@Ucw2wApx-sj# z79jq#1QYnh+yf*S2DkuGik5HDaqfd*H)R$g@?K`tJ-*I-IzN$pCVLlqYO~SN<>q)e zpkq>x%JVQ$Z7|y~hwQ@aspVTvUNjL*+17)1i+RUWtiPM%Iy2+gJJn`BVWD4g)fqK^ z>ja^SJ8g)Nv{|#n?;jf^IC&wk+|r!=qREo2{+CiCR6~x)iCc`4Olzreve{dh9nkBh z!09z-O|VYck5o14_-4Gklq8*Ya*T6#^{ytXM=mNEyW!7uH>LaD!aR&Y;J-JSi4;I3 z*W7c9Z^7=Z6@Wmte_D$$F)cN@F}I9Dlg*ETIlrREr?k6r z?zIX!yz8p)LxxPCIg*vRfAIHoF9wquY#a?yAID64SUc$`vSLtV=C~zKW*qB4U;e>Z z-pI+ZBc%qaE5-g{znx3_S2=6X|a3F^66*@ zT%{s+o2Cxti108%a(yxiWj^;Mx^8q4KU;1Lro!cVYLrqG5`|0?4qsi4P2z9Y=FW*` z9$>;R|NB6g^#T3_6Rh@&L=pQbv1WjnsK{2A|L5ccr$CggoE}xA3*7ka| zZ!eN|?L47>XXa{(nrgw;={1!3PKK6bqPVSn70bO0`($_n()+($P*T1{s^u)CSPAg6g99V?n^e{W+8kEF$&aCwCBr2r5q^C`& zfgbd~6>&D0a`wnaJzJmX6d;2~6s}g_@?noBQl#%X8`-^SezS)~#RUL&*2~pwN}m@K zkCD^nKd6=LzLCcZSk5eh08e(+xptcMSk!xEyJ#j-+VfXrQ6!RpxI2`pX2lNqoaNJH zJ*dfX)c9PDpTDfQ0B2RMx~H7otC!lZCBOc1nWr^^fG(CciSBzOh*N2}J9W-@O}-GqdANBWgoXNclABy)f7*oZji z*P=x56}L743BX;!b@fk-V-bz+QFUk>O!Eb5;k94N=Fh=6j@o_sxSv5fkNrugn;!i( zi)7xP1=m!gH;BCp$?-1@ma4n<=#Smcb-_CCZ?km={A{LVBaW} zluo#7N!q4tm{Uu3Tg664;7(9R-$?=qyH|j@3EOJRdj@=Q6Wv!9V2qo$TcM1wYZv5U zTnX7{aZ)87xd0JWkx{0A4W_8-8E%in{h^WlFfa5XJHMASk;fb{RapWmXf2 z-k=!D>+I2q94cD0b{)04>tBVKo53+osL~zt77?}H2xdge8d$Jlq_TwDbd7YcJlwmc zWe=P7-Mrxk|Go+eZrOa-#3BxaT~y4UOd}rLya&SNYxIpZD~9G&ok%%$QF(kRiwEPq z{Px36WvlN>M{Z3#aWwXpbkv&}2!{0;1#u6h1Tq*sOZ^xQjuRn$4k=)?;Qct6?lE4gmWkUphGogJ1L z1oudqGw(6DjsBT{#5Xm}U9-2tdKSDiX!E%a6-F%V(*2WpqQ^^8V9*IXQvH)s?kHDN z6>)=RQmh!6j|y%WUxC~f-5jGAo}l%sVOM&}BgAEI{CTumQr5mazI?lFDoY0k=!w!j z^nNwikY_UmFR)XLOv-neMEaZSPo`WPOn7*3EZ@#6eBoAa&%zw^%l~$KrX2QSggV!T z3LZhek42$x78b1bNx9o@&X?nIuM}uXpthEFmH9U18${OT@AU?EeoU&acp)u(;8ozV za#-}N(GTI@eM8t<#-`Yx8F3y@VX`toi=&#hlb+|LeAr0ao%Eu60WMgH6Gii6L_Q@L z`|WPP#@Ff08=6|fm4qk#$TI^~X-A(VTaXML4U)suDahYw?GhVGg-*p@vIn>a2MOFCw6WfBq z49id=6w?3Rz-~tYgjTp!hr^$h_;GWL;(x~+AaH-xYp4+@cb@$K?-~A0${~V|lpoSARj8E(<;F%}=KqSTSEc@I8C=TQ)vD z6COi3)pfHCUQ?=^yo6(e@pKht)U42MK)}B_9`I?NC#&;v@-ZCeH&$Og z7yGobT~-&!MGg?+mMk{UVi;RlH(^YZ3L<0TrfPj+lt>oyyz^aGUVPXyZ|y$ilPIY7 zl3fC3M0316!;w^7$b_YkM2V~SKtX2mRVZ`a>+B40dBVg-JIt>$Smw+cH3#$4T~GMp zf3l5XN5CbqOb55&dY?%!Y6KgrXn0J5NhIGjcha0!rFQ!Ne5jPDdAiY@-!ewjYnGis z;RI4>$hEhUHqSljL>S%J1YS*f6d;xaG{IdaJfG;^)T z(>G3^jmoX30Y(ucVJh*a#Xr@a-){1ao@F`2$#KUN85{CTuM!X;ZlOz{|GnjwX~7RW zCy8^&#VKQ)_f_hc#GyI@2O@;4?%(3nv)s^wHZ zY61DIQP0aoytIh#O78H0gTzu8`EA7HntK-2otP88P|$Geh8v`>MX`+|wxkXWeX_rMbb=h5$JdHOoXGs5OhX?vkDp>SGo(O2W5{K*h@cov>Hg9=hrdtL%As6-}0Km#d)uu{q@ zN9@#y>FdCAQsYS&z4USIlz>b55Ex);q>Jl^TcRjSVt(u@GdJppF0oN9!tz7?_J|WG zoV%ys4EuY7*hJHZ_rNZHmz=<=zKyD^#Q)u1N7KC@m)X95(Uc>*9sR)3OnT-au+vUf zNWQC$Sbwi3f1mJb%jg-&;=b*y!wVQ*Bz}?_aStwB|KnbCli{JlDHs_av|POWz2X~6 z!kqX|{w*;C-oh2%A(hS(9z`8Ya7sq$Q?4hWXR^|x*&%2Mm4u-vQ4(4sFYR5l3}V0y zYNwv=+uQXB-M=LVMRnj-&gUr8d@J#FiHro*gaI|wLP#VH*MO)!6weXw*(Fe@KYr;wS@0~5TBrYT%NXM(^SlVf!)1r;ssXH|i=0sX|-Bd|AMy!?W-eOkShtIEQeTEMb)?Z*8MoanE}G$?km>XVcgn;JVDnRCs1`{4dTJQC(ilK3I6i zSwfvz-5Kio7!g5&rRf}FTC$*KA4fui7d%QO|F(+m7`Y8Ox&b~9MIm#eH^|p#6W(m* z&tv7AT;Y|?WK2+$LPUyXz1d6OJF)dX0^@)Q?0J7>2Wlv5&3$UkOF}DAYZ^3I*~6E& z1qtI10yub_Zc&mmL*(kESyvp>Icitw=V?2YuK+o2ut(}?b?xkaO1vj(nUQR-lKx|A zKx90=7J-%&TBZi|w}b#V`o;Kb$-82b0FT(@7EvOn?Oyg ziY$xn?$hs!_;@R@5mW4O9?}&cHarvXaM5GLS*LSAv0IbQ_Q)lK6I8a|xSnfw1gQMm z5Fa~M@lN{Dyj_@ur*sw4`oGEiC2@UrrXFl+D74wjhTz(~!hN?CF{(75XCUndPjTJp zGr%w{jckfYKh)J6RPCrt;94I~|BH5@PxV7K_2yVXmgc<@aN3QFCxmU=l=*Q{Bkk2O zE8Whu^9hi;i<6h?TT^yK_Whz6*tMJ4;6s!)89lE~5!M)=mALX;5Scx_!Fts?=&!8w zFHW@L3VXt0W^B;X+JUTyoij@<@~l-X!$1($eISiJ)O!M10jOiN>w1f$SI$_*n%zMs zwxdVC?kaa>$3N;zuZTsM5D}Vsh4`)J*HbLgJGBTiD58zC!vBae?^DyiyRM&=0O>F$ z?0xJ(img>#_|GpucL?kA=AqM8x@qS+X}h%Fc8OTVLU_=RF+0=!=ieNU+m|Z7zV0?^ zb}K%?Q?eG+JgB*n6n(HOW|P~=x@1Gk!pDUQ<1x?*>s%&zy^OZ z(dZ=V1w5rK!V6a?hQR{(IX~xJfd+oQ#-Zz4QK1!Yg5b`}fi|e8>6Pq<&36LUSl3*b z1Nvh0*}enh;Xd&9^3L@rFSL$**knCl19qK}YY;i;BV7Fm)%3jCJ){O(eDAV+uw^$g zyRq?={aH?FkfvmDZ?hM9DCh>ruXPSS`l_^`g{2HvoWv<{S^LFy-Yj(DB%n#R^Dty z6C&x-=XB}W&ARLHa_CWZ^4C@>uFk)z7VP^5FcMau?}!|vTGCb?m9G)MTdn&M&1gw> z1@G&Bfxq8k$@Ih}mx%{z*XpS+KAp(@%>gFJ>k(?X7K$FUhSrNw{TTH)8*jJ$8Y%NN z$D;owfJVAX;7I_#t4=;`M2<`%K~svr6j=RXF-xE{Y=IN}Hj(_o{bx&Y+2y z@e<9;`COfEQq}gVNM~4`vbnRLtwxv^3heA{nR!3hL=<_cWf!75-A*PUO^wg;Tx7}* zuxIg=eQ)mZ@bGDJp=9wgF9j8Qm!Br%H$GQF{JC5-$$8_beIexX=hC2}eRqiCt zR`YAZ8T((>8%~TibxEr`m~f9ZW8_s-o>;G2vRKk}?qT`GRI+9vrlm4;FCP<9 zwTFs3Pn@KA2V->bzR}5)uQZH@@=1nUBbpkR)^_GpWQtdD;-*5DNVZp=teLLd3eC3X z9}d&4SbLVQG7i z3^rP-t@os>?}alXg2Kn?AW9x(UhIBd!C8E8$)oxq8sp3>(^XtwG37wwO7U!XxH_R9CLbxOP|2C7ck7m$l;xNqBn@LBU~oeF;nj z*0v7SY?07grtG$ReSPCooyrGazpyv#(Z^LcD@|ta90+`Te8*t(Vc&03>Xo#nI2wdU zsEp9ZCFJvtzn%T*hY`yl2W+330muV`_`k!G~XueLz!JhX&rIpIYIj;--V53(Vz0xX9BPe)|e!(#dvo5z4;*i zvggI;L8hwAG#>`|ho#xHpu2=O=TxgQs8wyc-@E;BsbFNelia*-Veoc|l8O);E zn?EDIH+jZ4&D`+P*}&+?9#@NM5W)vYxh+U~p+P2zB#YWqq7d4RvuBBFmZ_|STc}>_ z;>*j6<@>~5&TGt=`bV8nc|g=1zraOz|H525KgFB3eA;>&Afr1H!x`j5JMl~`t)JZH zSETW#&4`ERo+D!1Ym_;~AC@6&a8K^+r4LVhon_8=|3%bCXpPq>xrMiQd+o@aV?2k$Dtir|ZzgjQ~ zOS|kGe_3+XbWDL3)cB;!u5KqBL-|9I(Op0J5a|D$ihiBTxV~sLq~L$&fMiMGD55tz zV~(jX{=7{MhVSgpWSB3;GwtlFJ=xzCdFk_3gR!&$s2?h2ju-XByzbfFDEao2<8{Lf z&~S4Ap{7UYQ{FiQv#Yg5S)!v&bAY%pHop2}_nSY7PDQCFd)KN|#dxpTa}hNE35?!Y zmhU}1dc%jx{7&%&U4*MZfC#HxULMIZJ*$B~f_3AzSxOKd%~dIDR}Fc1Mqj9xrAD-l z5>g8vyol3K)q2~y`W9!oT$+kdK{#XQ+ssuWsVDIXrBrE7do4+g4TABiO>&4>vA7 zrTV}7q`W@ylX4nj?1_$!Hzc4)l#!rQL9YI%lKzo2SehcyLu(7n80H+c1KLAWcd^0zbm-3+)#6z zNN)IsiZ9^e?4z%B+hG2}vMlR#fot@G1y8gCBh*H?ULP1Z(|1{@%WkuI!=p~Bw4dp? zlg)ow<1-o&m}-y^CLfZ_UMkbz<>OUy@C9k&{K%ayu2=3P6urf$78b5G{N|D*KQvtX zxY401azJ{DBAdAHl4@#y>7S&aH8*WEDXOS5<=C05JD)HR-=OOc3?qQ3A?^{He zoMwl#!M{yFbm%7Kkawarhs4T5E>qtttL@9R&~P>VGcF-)2g22RXin7{xg++|`~Us4 zxUYL(#R6BRXoV=4kS_if(QNE2$o{Xld<4WyQ%3snQR$SeVoE@teU-G_-1YojVH)C_ zKN}593$|$3PHm0dIB6a=qhH)|iF|f+A)q|Hue${{59imUJaMMHMA}YTG+VlZ`Yz3} zHLf;pTGzg)G-bCY7=fAC^AWUAfQj#f&A8iZySoKEfmf*kP%?!<_HyG*wEIh|&wsqI z5-^=k3>vsgpcL{-DI$vjOZOPAO$zNv|LF9`S0;ZU(O+v<&jn&UFS@`@vUsMi+e9@n zGrcD*WiD0DfyPW0dZfdpkb%8uHMCB$k#;CoCf&Fu?U?N$RrzI;uvt_|kpg}LGM1A- z-l~Vd4rPflCLguC0&lpdBxAp)%mp6WCC%W8-XYaO2Mg;0I?kk0cuTd5EjHn;M>6O} z2@1bMN?vOM-ww)K;Y40YoYtyAVz1{{UYIH(TUs=$eC89SCH&Q6iw zSLPch44-J)XGj|pszygXk=BBzFe4f&k#QM-me?(0FgZfCRwR^@dOy+f8(FpT>V?t96T zSL<~3ue@=I`@q~9AKM`RWzU<(4R40|mM)u4QZc4|gBfcCqui0;e&j)JYywFbKOaRD zufldq6q zytfry;!|qD&1jsOI=rOcrSJrAcEpR?6FlR?8V~8A@Pu=nxk>Ii3MVrC_Sb}$31rx=`@1?}f&VQYw$-+_+P(7Efc-UL1J8PW`9BmAon*HFgS%^j)gG!7x{JF)g%lU4}=GUJkfR2807j(q&N3C zrnk_3cKY)+R6k}vZM)m~3D9p~&yh|0-+DT6U9swbv~1rM3q46+bLINX>lD<+NFq-K zm?1)!-nkux`pKTfbM>>O?&I01VB8UU$-Hlm034Op>`c=J!EQv%{c28Sl-ewoYM3x& za1gHO0Z#>Pi!TfAF5tMeN-jc6zbBPtEjxtczk4n1<3~^AUvUy2H+)m|wp|chEG-h- z<0T2sNk?2*!HE|gh0pn&M>vvq56Ys>eujXC8CS=s~{T73q1qWSfRUzeZB8_UWx%p4$K!?U4}uZtf9$% zT|(mgMhqdbNPS9&F6b6b-%zX|4v<=+OjjlAQRNg}aqSp_W&KgSR*GWJy$hv7aT+Ch z`JA)lfZqouUEBLB9_SlxztiTU#D`qWP+nG|ImZ*+RhJ?F=RX-5^cADk**Cw!!xN;$ z(yvLaa8*iJjLWg7NHh9=Hu*TrwyCxDUYF4uPX0+ko-R9&9ZE&6r*B+D6^BHCs@sxC ze$57kruX)vyts!-jo> zCclO;%z2zoNg0j=w$kxjPf%oqLuJ_-c!%Oyyw{BQy>;x1BzexIobAP9|IgJ|^s9f- z-{eTcghY#kGKbFGxj0rs8VARGrr17HHTAiyZ%o{I9_mggE#6` zqAJwKHm&*JT{-W#60wA;QfLkgdl3k*>d;g=VS8Z@(G^}cnFJye9s_k=b2g(}D%s1a zO55Wyfq|v+`!*0fIED6bLl|pP8>rM%f(QP}du9~eiSNYCPDTuu z&9~d(TQ%q8KjpHYR<S%gbedaKhbJa}`8j&fhr|Rn`zu{Q1cmqwd z^--AH*J4fuwrHz=o;tp+NlQ}Z9&w!`>-r0!fWWqTtm_{9N;KZ-mJQB9qvp(j; zqi+R1;Vg&u2D5^ma8lW`h1;1G$8G;xQtZARSbOh%Vx7hQ?8=3hOt!rq>|08;Z5_~T z5hQ$~mhWVSx}zu<3#(g-5r7*|W8A#asJR|r3*PrV=UbrOE?-_SE(}<6rXgF@0@82e6WBtO$oMQC??XA1Z3g5+>ILy-4aApR{ah zO7&y(8t5EUB9AA*&IPn5gnQ!xSu3}GIDW6hbP7G{+@-?pv%${jb7*`w>$L%+pB9>W zH=9(4pkoN5CjzvG`lBxlab9boi`IzETdrpQ^X{we11~StcZ4B<-D|6jhNP{PctcfP z>G#L1xQ}Xr`~0oTW*_;Ik(oA-qk|9qivIRsl=D6#@-OZ@=3O3~`_6Jq=orS$_oVAo z6$X>0q)*B6xY!U_vZks_Wsr`|pf`OU^Sf!xuV#;QMJST9R-3o{CBN~a{4F&_4FpzR z9Hueu8P#6xK0&*vAJQ@?DPCbYb2;hJAnffrx>r{)ddW3<)B@@|$E=MVx?=?m+H}C* z(Z6u8Sh|j1fwE3Jysa_CM$R4b96qz0kOz0)lj}pb9!Hp1dE;<;W;q|EhPFgVEMsqn z9;%~L^iCI+gWzG@m*$982_z2M_gd+qPPh+;izajwX%SaiU)1qtUO$k5RJHA;JUr^@ zaU1(iVK5BK`5klV?l_t|e8BOqBQbT(@k68QrB70|^Y+_9-I+gx0$x0O!x1x4b0|H17)P%3yEz(OC=M)x_hptruVCAV(0+$#`CnE4Qehe1&Qy zk87yEWG0HV!Tt2<12|mpeRHUCC6bNcX(LTwWE}73yCGu};=>P;7doYS-}_nO#)YPw zobT6vD-G=g2>d6rh=-Z<9_ZsgXJvft?3ARCnU9uanDx1gmnz48vCOe#$9$D?)afoi^fbe z2RvrK_*XlM_g(x7ah7d$UD*;Q%;#*eyY>thvLb%jam3_o~69+kF#hNzpInfCM+v&mV5S7$=4fM9H`9?vMQ} zE5IvP+C>d(I8o|Y>z9Y2MVY;UFu@7Kc>f8{%XEroN%dPzLIT@lAq$ZK#<7)wy?~;k+gT4-JhvPo=M`M)eF-AT;OFo|t?!Fw) z4PpuVBA@U@TbH4TWIg~n0sJl6Q^>+E!iL=;obZird8+FTq^&~5rde_5Zx`xw+-_cUYbo7}(d1cw&uXTQwY9Kegr+>a;CkuT^1oOB zF{xXU+J7m?m?+n+$M%DsMiaa@#NED=!%eaK`)!~G-Ui6hrwomgQ29)E_Kq2TXKRYM zwF~Sn+NF5KD}hb<<(=vr7qfjD*JD#9v~Rfj+ZWixcNoJhdIrSsfF0qS`$YM2uI!Dw z0%CT`7XqLolS!u0HJxs5DYcO-PsI6rjakAPQc>=QkfTEiqA_pNnNm5K<- zbb`;|`95))cfH;u+R6+Da*`o(leWFB7=SavX3ZdJyNQxg*GXz`JLA24j+Fe3b5!*% z{@0qdSkaa8!5!(Hpx?TgvtwR<)$erwe;7}38~Q*2SxzeS1sOZ@#F%#3Du0g80!^6*d|cdbM;{I4tn{mT=$Km&05)+~62kGqV^bUE#5MDDASrcQ z9E0b?0CM*Eg*)*#hcvy%8Vtes>NW4_vIO?1@#ckRyN~r<{m=5OEv~$t_zC6-AfnAH zc^zn~f{=nH?r&R7lO0{xakiq_Y=Cu9_Nr32t0AhU{cM6e#7{!P#)$SrSM8a!jVq@$ zAM(zzH6!H#4RycS>z^$GlV{0mDpg<1qc^8ZWi0-4Mb?&azVc4`I+!%x1vm)*koj!) zoA&!X-T>zur>TBQ>?Y{VR_13Ra0qWZnMftBr)|PApXUkO$ByqJfmW;8j%1{wbk#7ViC!vck^VA zGAx_F)r+6+bVhv`Qlad$@#7W%K>I+w5N7^biBB7DvDQUt%plVzyHDxTGJ8E?{DO|i zn=ps89{lN9%y_46dT4}&g(W74D#4WGiLjD5mZV5u2fqSKz|-9lfLgNhjyT~sEr1uQ zN190DS2RVMW=d3uqIL51Q`E?a@@dFDT5a+2Cr-vm)Ho{L&rt_O+iR12fpj+$cKJcx zgQtU)z!eVn3ZFW1M^pU&5+auGE4u15Q|6yWjn-S=!@ID9k%afdP;YBCa9s-3gb^&XXUG>C zIT_73>E-Vex}V+Z4%l|9nF|A#YrRT!VYoL;>oQJGS~|c*GayZ@CCU?D)%Y~1&Oc0` zuS}SJOEE5KbQr@*0(RmJ@j)R=X4siTpkg)5Z{2&rWK5b0E@`-P`z8x8i~uqA6pRE= zDi?`%{C+|c&~6^aQ600l=K`f_cPj}%V|dmzf~>b7@}a-ef__6;0kde?W(ubY#GHSX zokEz=Ma5pT9SpA(bzdd7flb>SYm6RwqD4kh=bE(xKpyDytL8yH_oK8Y`uTbQ}d-v*O>xbU}2 zx<_Iws6|mZC>7TeN((Kmdk}&RB$UP>Rtw@#XFEjl#rfX>K`!nf>YR-d7=ao!0}CUT zRUiu)*blOE8N_dW5u6og)nt3aPdL1@vopH+FI%fvz)V2y$+#eFVutfp{`V~00L}sv zc1vT9p40uxrs2aYr>xiUYp&tAfiW4d9F|`{z1Jp|V@p$Y+k{CRggw}7NptEq{*}sq zR6ROJPe94KE>sa&QyRn??*YWghP0{;9$B-ULL-HU@|0%OfYFt}c>wu58^^d-J3AeB znS^j-x&LX}2n~K|2K}RT?dX3^8}wb%1`053=mVw=%wj#__`VB^4VZ)7r|KHUKoj4& zG3{R^&(&UE=D1PUo(s{d2zzuH(;Nq8pF|cm!cObnD+Mw)y-p9tpQK|=|MY86L#A)W zdC}g}!&j&H0(OlcL)m*YigY$BNQ}oE+`cNspG}X5pTZA=t+m5zGyeQ;hx4fmb3eQP z&t0;UFJi3t!8yW6>xI4gzUa*Tro*b>6~VrzE9?ty64Z>pEv>$o_u$Lu z*1}+zef3<;s|9XPZ6^H)i;sh4P3qM1ds}}lu!P*n^IL6i%=Hwz#XvF;Zq%d7&JT`T zL;KLy;MI;)`4LnNGY#-tjNtjW8pu06di+xtklc-Nn{) zDPWuBB&`}qgy^h>&g_Txrc=w-#ofmkzC#V-ay&U;ACbtbbYh)1WyDZ1#hYjN56`D1 z&{?wnj%3g|zT`%%7srBAPo)PHDuMo8MdjoN=Y4l@@#>hAS?RH)!weZd!Dwu5^0rO2 z&jf&>lFeUndEb@vFNw%h_;3VO>^(*#nW28GkAc;GReGs&z6r2KolUlW2`Am^Gn)2` zTdE=rBz|)2U)$86!FK2`8nQlW156F*lOx2^WsFI!oFZd)9Fa)-tkQv*M)jPFvpmw$j<U3 z#R-^y9%AoV-FeShpnPQiOrNvbq&xe|a=gTGO2uZ2tir*sZ2qBrW~O=;)5?h5=(cM( zBx^7pEACu<;5vap=7z2BF^hVwzr9VR7HJ2l4EE4=+!a`SIq<}qQ<gfzj;*tQx`M~jrh<=XZshoD>2#5r=eLFjd)C<24DrVAk>LuQ|+{; z?T-lq3Aw~(L-|8=CNaxJrB#>QVuLQ4 znGBJOyLpuF(@iTD57l(bTDh_rA3O1_A?Q>VPh!N%8|{oE`Duo?2T06E@s~t+0>?75 zRpqjhawz7YS$${?y_Osr88+K^`R#Dm)AN(DncE-{+6s3qdDxKXu znYVRffX?lkhh zE{WYU(Xa>IsHqeDlW;PHsQ3o_Ovf~K+60}hk_a+?gV!#-84DvNLr_mg*Mq1|UY~QZ zoFDiFft1KWTh1!};Smj{dS~(c7D8+Je4ucX=$1(oNs?0(d2PI*(9cu%Twn!e8Z14A zyB<}h$niz+G@g&u{^uiUxg{lu8qA6*hu|mBgwL1%7-aOQj4rN!%eTs!C3o-jFvQc7 zgqg>vd@(*KEgF_3NafVNitP3tGN~JMc8jf?x!Q$Yz>oo#!-*rZ<5pHd3G9wdR5}oB z0GxrfkL$RXoi@X7!(*psLQ97&Q|{Y9U_PBowd7kHYI}B4m%NG#7Dirnn#z7M-`YJQ z^gN>WsIpc2VMS>iKoV25Cd&7l(bC~k0XAd4zMAI{V|Dw(;06zv5E4YxLj00yBU8Rk zz?I(TVPk>2!0mc13eWM~qLtSh*js}W{R0>b>#X-m`D|dO1%G<$j%rvEtOuP0t=4ibOUk-y%9cCf4Rw;pzc2kr-vfr&{L(&Vhjxf?UFi{mGNtXCNL4psNABvtCYUS=%C zSv|3LcST5omrm^ivb53_jhv>{5vB`Xt(#26pDo8)`+Hq~7-wjCE+C$2c!`4Sv8$_D znh-b9hFc^3&hqz0oBS!0PZ$U=%eVZ^ss8w#YuUcjeYrf4?9KvUlJEdb56a+q69x2+UlZeDz}L!vjReau50Tl z60EvX$sHRCHoY^viuE}{vytOC~DAYk^C z*O?#9$AX;K{3KWU(|(QP*z?N!o$e^Y7PE?{nXG zv2kPIC z17PN3>gNF3Er&tVF2Y;y;4q4W^EXAa0nHQg#?<3s{uZwOIy=*ov@Y#fn2cILAjh>v zD2>+`YwsvL-j~8iIDG)lG@M!;O%gg>ueY%e@#59Np<~6~=;xtJGTw(%z4pzX zY$-FJKc5ev)|89Q1yR7I%E3q~uB)lp124KpH-s!0um!F$zdHMq=(@u94T1jhb89uo zfuK?5(wX9{F3NFydB%IbUuAuPp7zh4epyCl#B7hTGU;AATiL!2s44(ZVTX3HP#|)@ zu+%)}s0xP{P^<00HqL@o*JT4|@KDvb=K-D+Xa;uy6}N37Rvt}6ZdWJ=XZ$;8y2(My zU)=rsMxJ%y*PwN}oDCelhX=l%V_`<%(hhMHQiSFaa7br2vEuxwbf)zmU8nM$FiR@& zS`oFgKw|AOZc4+<&r34N5jaK@{d9Mc&$2Fyqa!pl0jjHC_ekwT*Z7gd)Oq#?Q^H>U zh95dbHnN!PYlZW$Qy07eCTRtbc(5nuY7y>~&R<*#HNd6l`IAdwc<=BMTTI@&U)iLhwOa*E&cOX2@>CYto- z7=&(>8(O14BR-b}px9f>btvs{HEW}TMAQgLt&DEs#u*a!0Pjowu?q6!Yk9W(8n6t@ z0}bulX?o{GxU`LFPS0C*!bEB;O{Uf?^nkHAsWJT27Urits!ly5MgJ9TEI zT(7^wEaf*r#zmLkM4=foqh)q{yM4Wgxu0sV+Mz5C*}W zLcVk+Dluf%oa2Tyuy{|1t#(4n>#y-3# zeciX&6NQ@dgvQy{KEOv&65w!BqLUG{kLxpQ=i3#IhM-nAcE)2kGo&ye+F^x$z&Yl3 zB215EKZw@R=nC|puCU?1gy|~ad zXqK`93%+D02`=VLe>rugpSgXUvU&mQ;#=P*m46RCND&Yqk08Ubz1L0nVwV;h=7d9e*0kavI|Y_oXMapwb~DU)=a``Cqe zdaF2|?m6aMqUa6WSNwd|&78bJk%(-(1)+Vqbsb!G&^9E17*xZ3L6p_McE|JI$)g)J zz-AMesr^RecE~J6_Sn9JS5!NOkK?QUC~^u-OK!DPuAd+;S*_0eo|wo1|H>(}c9PHd z&m6YdrBSF8z9!Y*2r)3j2j)m{*9+X53$1}0Tpuz%4gXgb=y_asL` zMvwlTqc()r%JoqsV)?X9}MIxZRXc zRq4bU2F?#bKPR5ngNA=kJFIp1I+-q=@oagaD^X{E%Q0E8dG5Gzqpkd}3iJBnS3rr0 zR(oCB{t@JKD2aV&_?IN}xKqoM*oh?oQ-&V*+kUc}Lg^{I@}CBOhUTeXIO}oM%ET$S zA8UA8M*PX2UI|Ddqc+~d7aEA`&xR~nYrNmQ6VX#(C|mGrYV=f`1^wbgX!iG8RaL~( zz5j0OKfIkq?avSn7)e1v?NHlu{Fy3CyyRKx(AB3D&RPesG&A`P{D?Az9(g@*hCZLE znrpA9w|Up8`b@^8%CZJ>ecu=jDyX+jjiO&^fFi#g^TkYiEo$Qxa>xg>--0@P6b4d; z;=*e0B4+}-EWi0N*Brmr5**rK?lXIH0`+bT-2X8N_(@QDP4zEBow)2pjTA)lE|Wi& z{|omsqBeKx-n(r5Qu1U=|39QScdoQfU4re+wei5(U$@s0fTcc7R4ZaBZDIZ9 zz0K^&mXtg(SYk1SSXHf;qt75nb^W_CMVNeE0RE*$Ivyv8gMS^rjJR;h*Pa{mgrCN% zW$L9H7X%b2EWNy~D(75_k9vhryI6wBmu6YUE;-wiZeFn?-Qlfs*C4p2y)KI&MFDU0 z@r5hH@wl#2^o#L_?;@cRR=_ECK9JF)w$=ApZ~BeK*uDDYd*l)DvKx(IkVGlon)Jn5 zEg;9P-6LK+7XKUqFRe%^($M$K51=7uQaB&KpP8%NkDgnW+qC{jmDUI$_k#X*$kapt zHtj67{j04Wd!%U+do+jl!bw{SY?qm_w)Q(9 z$#AE66$Csbs22Z2mUZ1P8}S$1;s}(-+(*#$6!{fNTe@sZ>)qCSMnaP zUm1C+(a72I637M^R+Hy}W9D;|({t==DEr&jfEc>`9uRZ_3>$xfSwb8aLq?1MKgv=S zUVU>L;Y6?AWTpWti9ziuKf$C5lLDPEC8kIub(@royLXA|w{qinQ(iFfi!1fbs~2D7 zF9T{05I$sD8%t0}6ayf%q?hL=uvhkIRdo$g#24IWYu03W52A8ZCt}tF?h3~5`Xk6T z2V+xii%gCazu;oKb!l0W4*xj2(-^WgWM(AEury6JADF^Xu1A{;71jsL+O&dsir=KHB z#1Xerfr|?^q)8RYS_{SHChSAtu9~;?>re&5_*>U!em~LGX(wtZwGXIgMeUm}>pf1U zhISgg0{Usm3x361Vah%{z2M4|4GO+w7@xhcU8LxwAPy&I{?ML*&`B>b?f4SC@$e`6 zSD3!NQKIO%E6*2b32-|G`FP?_Si<+ndSMH3M41?|}R0&8zAarW3%0pw}C! zT%%6E0yvj(_=&GeZT`^!)0@BM^K7z98aEjBM3}rgLk$%?apa!QKJ&K|bNc;v_iH}a z@&iB_QG!dO=y z3E2`c_g($)8|5s6Yujb%RZEOtkgJ zxc-4?<*Z9lo$=jPGgW@RB*XcNQRJ&+5usYOD&&yb5-}6|Td)@t*hnkhAGo&P2P#UZ znr1ccOa-2dTI-Er$Y3CEs55IJhu0(Ns5*hMXE*VNY?CrEgxkP$x@QmkUV4?ql;j!v z9+CB@nbNj}8-!c@9n{ zF`0m`>b)?T!<3_bos{D3v2o#ivD^yE#B9kn8b;rI27{N1VD5{Wq?c5?d45(}d?)0F zvc<)!)(RHA`7XNS(OA~ls?wVQyjH)?1+0^o-IIL1S1N`gmkRaRg&UD`+zkV3n@GVM zWoB*$70RN)hq?IMK~Ew}_D)GN;RydCQ0&=97R3_Qp=S@0g)ABUt0#`_77ST{hbS8nS0J<1U(H z+qDPlT1!80*2~5KZRn81LtJFkwT0uxD;q#nosZ%0J9+!h^Jejc}~d z=nyLlz0fa+MtabjfS4tbVQOX2dmEUY$zqJ;%kv4Lxfgd#`Pe!Nk;JZas%g~fMj23?9;JY6?el;Qe{aCg;YNxiHq|6yfAM2l%%Robry{ysUN{d{SI&&KnG zzRQn<$Al^Jk;K0%$!U%3D+Fa*5%75Gp^zydW;N_LRSJyQO8u#o2j@XgcbGNHfLs|D ziU&{7mfaOjcjjEv^*>ftEX%+C2jylYR1%rvWp8!k4)+=F-e>yTSGG8l{wn6FO`277 zv9R5$e5EY&0&+N=Al|h;ta+|#75h%&=2Fx1PEM&Frvs5>KI`eU(7`}&gOmJ+5=#kx z;Q6H@stTixoKWansXK6b){GyFE-~|TVIYYl>uiCoOCmTo2Ixc9A@Ze*^5)tt3ecDK zc_j%^N>CkOlvsDNSx5JHz{>`67%fI94s+UO-uytrO?hDmmi0J2dbn*e9U6U*9!Dsc z%2FYgiFPq|G+MI4XgD;25tjJgSVhFOboRZ*sl+0r6_v)OnQI}{_r!*#cZ06#YY?fI zs4to-anF)+GmwL1FJ)Z>ATfLg7qv^||70XXO{O@QRS8VNOkGV+&DWI5m6({?h*C*b zIPETMV@f@QEzQ&=P&4tNJN3v7Ic^yFQMGcxE@x-hy3gn5Re86h*|L9i`*FdBvZ)GC zUnO$PT}}sGY3$azQf9pSC~3q=b56-d1AKVHyPl1UeM-%Qvnp0FJ@Pf*E;JwoCnfb9 zS*u{#pI<=w3YvA2_0CBQ;+9^_O7$Wq?w2}tR?Q79(50f>YEN-wlLI%jP~oB9bwFU#xN*9{IMS?)8oX~5&zhDLivvX7 z1^z?F6-gFj0#7?h;8gUu5qC?HCH+b2|0UAP5Z_u-&;KQc65>L}%zDN*z8;pQssf31 zWB4Y(EjJ+V5jJrFMClLPI{AYmCw;X5C>BU#9ZAZ=Z|+3`YGZ$}2sv2R|4JVO*p=x^ z0!5TYgRAjCDFq>i!e44V*IeTMMS68@TJ~Rf#nE$o0AAsuuBD!x_GgrGO4;Hmx&N z6%Tbfp5G#vt~AEFg6VF}Vuzzvy86lI&OllV{nO0JbWxS-EA6}HFPkYRYp5P^Kf7K; z0Hzg(Ba)*>B)gtk$7+GJ+zOQ}e1x9M6#GC~+wQZ`!X{NETp0M5g3aaVwMgV_gZLdR zNFD5E)TzD%`Aw8hoG~KIyj12F+YooH5M<^1y<0cz8w%Fm``KIjl&pU~EV1iIjr&v6 zkq>N@TaLdf$nnjv!L4eij_oAh9hJ~F{|0a?A?!EGTQ?_)|2cKHZC&tK!YpL-^Ol^F zkv1WjaHL07eJ|jQc#=r!*#PB^I>OODxRnX9srw?ZK4rsWqJ}KArzEyPt}7+-?s#83 zlmjY(9%IhyeqC+U2X}@*3ooLs8O3CqJ#|V_?W7g5akt&=xCKe0Wl~RNSm-R_-obmc zs!UpZGtQ4y>D#sSMrjphK?(}pX-}TYF6no!BYYGng-c?jXO zb<4tr?Q?y+mhBQQDKdBRR7)JN#S5%2r$R@02zuPq|F|Q1LTIla@%#5&@EgXYh1n%Z zD0DoGkKiFl7JxIta%p&t)%~qCEf~((0Ng0AXB_p-p7@5iSVB0zH3NY3wFX3~D0V;1 zxf*e7x=V1K);i>HAyxln_FAmTUkhC2d-R+2TK3A1z3gE>7M{?*P-kZaQ}0Gn6ICM| z*yedUz(|MhE@3F`;=Ql_Yp%C5ytp%GRa|(}5~gW4!!I>ew*kq!*|bpD`85qI_KDNo z_HGxk<9Mj1)ZZj&cQW7EZS$DCm@;4Ci}s;Bj-dJ6Z=G=eNfy~fm0utC zIEv&ET#{KM#V)3>b5h9&mU-#GgONDN(TrD5bwxV%kA=OAo_tAmxa^!FI9pc+W!x*8 z6yAL5QGYD~bHnhCOM1P$Jy7>SJ#W^ImoU-#a&*A$Amxs})b{Ot*)TdZK8oKhfKI1k zau5UElI(rsLwZpu`+u&rky`6qr=&P4T`4OA@?q%=q^ux*$F5?vz@1K;@0hi#k>~ z`*cbyRdIwBs=%LRQ0fJxP(9e zH)Z$6rFB~CD!a9OmNw-CNoY-apnSiUs8aLU+o}FL!@CoWDZ(&=nrE}8ufG0vXNdp# zzRV-`g~EWeW56NUz7bww@Uk;UrX4_F_q7fcH--E-_N^2(6X4f~fqB}c1^|HnoT)+! z)NL{N6d|n$_tJf+cg4p}A3W+umS;LUOr{@+r&lSjTez6rY5UcAOgi`+@Vlnj+{rUv z?Dt7#i-8T!b})Xaif=k#G;&vGDM!bS))ybt6n3KSl^|w+!JKX0Roiu{ab@KjF$hEQ zcye+WO_lb{fmDldaRSDQ^MlO0G7-(@tY%?=_IrQx6EA+YocBPcT`O*2UH8S)3i=C_ z24U%-cLISzyqZPh^-oHE<`uhaVUQ{2=~Zv97j)sStoBE%zkp*qSCzl@(%Tf@QBsH# zm@J$92jfn`ifF?Mmli)s_iS8crA`gxc-EkwV?bg-WJF*e#)R$(1MyELowO^K{!|i@ z(nX+_3vzovr89QGmL#q{B=8_@|KdI-wj>fslLM~|8JHFtcCw5cGeOoT;aX#!YzbzM z6&$mRwx-!tIjwMuTu1@P7JG{^`Tw-H3T&V zDD=OlKbHN6zX8EVy5N4km^#_nY@T#?=u2d|9)I8QrzdnFhAF&n^jw~@I)hzb(A3mCGq7Nf$+4Jh42MZIjF?4};y^@ZCzuKS-RSFO z=SABz#?2RZ5v#{~_uLNph5g1nR+3wAiK0&i4Xc!eIXy3laGu1kUl*_IGQndcZa^4f z3J2;WmxFE7&%S;p_wKkqzww6{9~ruM6ebUh=hAR4j5HoDG(g=Pu!E-}t%Q$e))z-9 zhvioPi-M?DVpPo>k{K~dV;r~o=&<>f`K}CLnyI-c`l3#X(9V75RJ>l$v++@iynUEC z2r&m@&kta%a`xkgKYcZs^~gb)XJ}fBMRE-q5J_}gX=BH*-F&ivp(`M>X*z-7izATH zqGD$HFoJSGxkdHj{+VR&4iQeAAob?o3@erwQWjPw9KyM%PWkp)6~sJ;dC^AMlp2Z# zybW=$RqCB>I1oMJ2S~MEadMKbdHFWu+EMRv1H50^ynnEJzUFtrv*mNd zro+?-OVdx^PKYUo-*vavgW-OL2bg;>&lbH_8ceSQd&DBM<(clos#}lYrqZm=Gr{gL zi&xEDXZjwvSV;DTK?m6aI>w@;1{{hH?I!GM3kZPCG2JHpO`&fHI;GkqBL z`&cW=TVGU5eO?Ypg&I?99^XOor0a|pAO7VlBijHHK*#qT!f9VOIzc0(Rzvd}HEn|F(0tpOXQRVR{RP(tF1aChH#>6niu zx9U*0`xu2)k(0WxVQ{Crb|$VwP-h6sdYnVg@ZlDCMd4 zxf43RNs>2O&wQ|FYV{T{F99~Q^*KBarb(0m@)*z4&K-9x`F>1(xE(ni;O;Zv8;iS< z)>Ty4mtPpj;y~;9<3>)3;~uVFR`$R+VZjr~*IvcIir#VxS%6sB{lwjxUU-RCNLICU z?@xyqT6rrHlP*w?EK>}S2-IwQfJuTr*^3N<{Oxs!KCrEwS(zidyy+MaHi5@%|K75p zFialmPvCM@W&&k_ee3`@SRMSudiHL-3R~F(~JKGxI~{wq$pbWj>?8n#%eo zNq1L^jBVfa7e@iahnHzv_8v!CeKM;%hUoyLU=Dy3tk0a{3yOw;Q|vsjb@f8hQLOmI zBoM{1Vj^P}>yk94Z*~;~FGIhwzP<9;w&fQ!($$wM`mMCCbl|`&kPOM0k#Nzx4Jx*z zd+g>GJp%aVGuG?wii56r<72xMPLgYH0BTH-=U9IyG>;}(*oY#C(JVo=T2VO@OERS% zjaAMDVz|K%oUH@=^4DT!f>WaAQ5)@GNidZsgFyij$7bmnTlZROm%Qn?Y~%#v=5{Ga zO|wGD89ow$t<8M0*i0lUAtkmp*B-k%J*C z@$f>Zydi4wICe*AQo#Khys&-$2}O2DLoTsj8Fe8w<~kpEfag6vj!({o=vu}^L3J$R{Tyze*p^C(4c}XETyw zE5`kyx#<;Fj1%!nGu%m2s9uJ1+HoaXXrUA0l6 z$aG~!mE;BVieeE1ikTHqq)&*9IH-3V%PvGs>TV9qA z2AN7S<#S)~-mklfw1QUtTu3R=bkk3Rb&@j6fnLy8vjB;E*Wfdh%__`E zVZW|l6q@ZQ_n;4HE4N!oEYLOLGvj-Lcj>=)VBFQzBKx6wm|JU%9t=bp3ZL)9#}0K5 zo^shK^bpMz9c{>{%in8=%$w-iP{LBBo|MTaOky+=2n{??z3`otZ`pcBG^tTcFs<9w zKLEhG_44Wv-$>$y#{K^}9(E#D*~U*{W*h@Fgn+Q;zajm-b`|`m6|(%(HK*3qsn!>g zEYyFbipiaA#m?;R=GD$wmQr2>I3wvu+?Z8=X^S)AbM-%VgJ$|IsdeQ_m4}ruPxTUCV2q6 zZYs;Q$3PHLY2eJY|BtyhjcW2-|9{(BWm^=g6i~!uD_f~DiHH)&&|L>=QK(X8NE8H= zhztQC5RxhaYJ^mgQAiXDC{qLk858CRfkeijB6A23B#;0}AcX&ocJJT+|KhB3UYxVm z@dYnj&tg4fxS#vJuFv)P5;!#Z-Ap|QKH@ihCV0(9oXQ?1YTA++rE_*I9GezyATN=- zpT28YIO3{h+age;QFg6mpk7UE^dyVNdtcbc(H8&G-%BA2z?cR0Xrfe)m2rb#2I!9> zZy~opffbwNOc%Lai#osJwXXU z%yDA8eyg#CF;jMkAEafep@>`&%y<)NtId)I!n0y(Izva{)V#IY?^TMnC`O$hz53a{w@|}sB&yM>#h|xrSq?-`YwO?PT>>lDg%nhG_ zZ&(!S4uHei2QcU$kO7I5Q-<|hjfrl=gl^hqvMu*^&I#AWgUMT*c?BCznT^6@R7rc& z*G;hRxh}k&%hy4v{P#Tlva;dDgEs-64#UWE$Vv_6HM_|7In31>=BhcO`hamNt$N~- zO$bXqD!YzCw7#9QjEnQ==9bJgb;3|~mxK30B2VqLsq<}U_j`6az_YLZqQre!Q>wN0 zw!?X5QA%wD6P!eYGkIfO8ph7x$p`#sj==0N*W>00NQEaLL%p?2&A>HFN$RfG3a*%Lrf4m@`B@CjF4ZgdOL-`&F3 zAojmyrar6hq4^Y*X;S>SL(t+-pd*&HsgWgOtj;;reew^eSpvhcbVUPH(SWH@t_Y!5 zr)DkG>*4vL zq`RmxJE4mp;);#?PZWwQ60@^i`qi_VioEc}Q=8cEtHE;<4Q&^jQZ}c^^Nn0U3{W_Y z+Ileqdn90P9Nz~Hu$|?R44+R%E9IPP3AA!aM}E!mh{YBk_x`1UCHSx;%2*JICeZSn zgiB%_fe%AN(bE&A-B{?7Xn_=H|!|u zt+J8z;laSB?O{MnViLu^xvlS&tp1<06ITia6Ta7z#+&}(48+fKBebeK%B#D+Xn98Pd08RNw91&19z(V07*7``f!fm%>rWOFzW>>xplBs=Ia`@OataI}Qz9w4I}zA=7-np{NCs)opZ^)KE1s)mH85FFJxMAN6pk0* z>2UkvXEB_NP{zw*yX``=XR3_+TWwkhz5z1w-$g7Z|MLN(IMT5e4J>@Je}*u` zyEj#MXR1O!9(FX61`-O?<@f12I^D^3h3Q&B6;Ebzjc-unBfLFqh-7tRY$D4Mk)I*F zDjd_sTSw)FPi7vaUQNSiR?Q&gE6_*Fboco{E+8i z$P@cUCUoR5#<2+1Oh_vhuSPE?L|igUsC~uPh}PpIuNe22PZWfO-WbV$?~dW*#hqlv zJ!{QqF7;)H8BKPkH@^d^VWRfLgM)FN>pAg^h#*k539fCMQ|6=l@JBYS-JL#_VYEcm z^wox>2NqN{EE*~v?4xvsw#-^P6a;G$yO|rJ7vXNfg5VW|cQhz;fnX5qO2KZ05(9Gc z>GSgrVGM$2;Ss|bPToOP>m?5@h1P2)UzF=$27SKRgc$~z&rFQ`-BhMUi>TqK2L(8?_r@WT8s{L0QX#8>mRC?X|3v&lc)%a!CF%G?MsVE?- zFLFpib=nvRp)i*E-G(6)AJ`6jU03i_yv6Fn^kn8fcIeLfh5xt!1n2j_VV?pp%*LGWlZ&w?^qPJ@z%rQv0cDt;1L(FhEj@SwY zNh)m&R~ob8mNKwLFU%4pu1JA3>i@>zu)Gbxu{d!g_c-r#Fk%b9W4%LfojK0Pn7hDp z$8~B(-Z5L6Zaeo=lp4ql7lm5b7`fK?74jo#1mpCyj6yFM6et*?w8;sDYMiY`GxrOC zo2-+->SCLs1LPxNd>bBjGeUGCrC^3bCkQGrm)l^rNWp(Z3)?~?E+^3gM|kgl~Nd_fI#p%I7qUGGr zJgKejeeRlu{!CoRb$O3AD!>cK01z=&Z^QOPa-!xzEruQB5Ebpm^kL{hm)BlT5{;31 z-v>JbH2-&d9T%qsUFJ-@?PPRL@jz5d-I|KQho-Y&Jp+liGwn{Phf~ahYtNVo4XEP+ z;(hSqzwB)&O}WpH^r$k&ZXI6w=tNU}go5;yPC8w>^kwLF-oJX&LW4ZrVu=J{k;1>e z(GX?YGaU6%h?YK2l|VlRvyDVi8(a$OVb7itwV^*go{0$H*W$hvTb3h&^9|I`IAZ73 z=k6^xrHCkE%AGX{?h>)n7E++AnsMC$pk|VRJ*@DL60j}c2^3m1VsF<4DyUK>xmAxe zJ={VpKHDR_Z}33uTK9fS(0reO8>RcM+oL_qNa{vd>d9h&sosvU(0Ksx&X3CQ0v*KS zteek^Blad9=K?r6_)8oGa&?9?8$$Em1}% zApiqY{BAv`E{7iT@suht@2lgp#waGC_>qq>z3ZsR`U{XCMFW>sQ`{3F&J=Da>sNMB zEM*<~KqwNQED9(-%lmw%b(^hst$0Sl{pNXrBkdKk*?@vMov8_T%`m}(C+CeqNJNyufI%ds-4)4B6E zQ}~2qyxA(M36YiXg36J)*vUs#^_I}{i)-#}4NbuJ;?|Gv zt3`)xr@a`1RftFJB}lZMNycizLON)buf^R#8E0Uhuyp>@RGd_6ZkbyD=l%8l2?gm- zB~G#;b>e*V`X?3S{4J&i*R6JJqrX5$gLDXea?qj=TYRE7L%OTBP@qC0`HC6gwUm|q zK@_Kt1P$TbcW63nZHQrGpPXAQkMoX&oexA5Eq}`<5Ft`zk9Nf0ljKfkFci!DV4tShqU@vSMYxV`XFZF)(^Ft+S2O( z{vCbyD|wDOg%9#_33I2n8^m{5zXqkVv2NBveqvZuc;oFLG+T7JjKM0lMqVFI&k^>%tV%co#)z`cZ?h}$bLQUz;%WcHYs}@B9Y^xE7U%U*FWK*KQmwhC)>^ft z6~BADWR-*PRe-{Bfbi~rX6-Kl3h|P%IS{>EoA^@4qB?qQ#)0InM)U%sZ?}7OOd<*6V-H^(|JoE!|v%uNQQ3eftyas;>e#+osOB>c+O^3 zbyeG&ZMUuMLZp=&8Mh{@Z>*7G--YMNFIrn9GSW9ei-ou-)2TaQB)g}d-f9Sc;iqo4 zu`O|I5%wJ~T+#fLY>fA5Xl%M&P?M1sqhAm+ckn%k2E33MV_h7#Il9wbT#9tE(Lnag zlPI~1uQIHS1o|V(o43JTxDM4D&!Yk=*PQ2Zvb^>viiaqc_12lBPl)l$A#W4?7wTe7 zo@f(Z@9rUw!eVukT@#W-{9q%N`c@JF_9LqJzpjl-0V-pXh2ew|uORokU}qNyT(>9_ zNN4b|IU*j5WXEMv>;r|AfHwTz66TL2QvvcamT%y7F7=7wjRX&kbMZLGg2E%**tz+ zQs*c)G7^_smKO7JYz&#N>n|G=`VlRBsuKq_aA8j{L^+?5pn4?o^%0#E01vcS-rXKi z@835H{ffRV^;$yfws*yRhwy7Fqq|lPy$*5Q2p6ealb}ZoiZV7CAb}E&*L?L7FEFMP zPT{Zag9}6!e4eo&yXuq|Z!P<8mLMfVz4{UY+~SeNFx^29qjans>+@Aj$oglag3Tm& zdp3PU%xy$Soul|&_*uKN1gNfbXCc0=7t}$<(rjSrR`?;q~3Yr^>I_4pIh9=r8fu5#9-b#of&d(6SG06-HjSI%eE4mmF!6drFp zDhO!Q+>)7}J2-;XUe;bsD*E1G?jeI@Nhhe?FTiO!lHVV6UH=X${EjNA%1_f3>LiI2 zjvn$~&A1m93f%iNit=M)dHMJ^ZF8j=TzK~aqj@T_s71xiW#y7tEc`t>FBd$2UJx!D zATFo$A4F<*MuPZEudf%c19?U9ic{5goTMFA4Y1V`j=x-!8B-(%lV|kcAv0b|e}9J8 zT-SZz2<71Fb^~k9S{os-n7?ZVL9RG5C$&I>6bmE7<w{b&eI0{3Nr^w zO=jb#M{eMB?&()qOrK^cso7UYID=+GQB(!aanpo(kQ9y73E4{1>p0O>MZ> zl0Yqw^-7lksy2(YfN~VVkvOvI`rF$z92^BPchkA$(n}%)jJQlyCGZTO3D`u9p>o}5 zt%3Y4xuwMg5kMIlDlKrXsyeOiQuJ$&X_c*i6Z-ELk0E|>Ia8$~A7;Ed|Hg^Hsx+}p z0FyJHae|hFwopF}e4Mt-Ib}XWTI3U4i2WT&=xY`lv2IHSH#Y&VmSlYQ%`afsa4R4N zV<^oF`2)8p%|ZLn$JVd7|A8kCdMm9LxU1{a8>6hl%#Drv9_WY^^1NnkVWHKS{iH|` zZnnIVY`L4Iru6Y8*tIJ6D(b|;d*!nZoU(uccN%%LZCQ(1);O|y4o6t1w*Z+u&js+Z z{GrAxY9;eVNY|;IWU`4+l4z}A0FKuOwTxGqZ@iG7OB00?j*JEUh9e`x{qB$6dUo7* zLzs~Ns_KI-W97#aYoylYG5IauCoEhibPtJ$d9)>%k&?PqXik{idB&zB84L8_D|AgJ zci{Kw2DpvIC4!@16%X{4i8OgHx4)Z)D_Bf@9Tx-%=T?aXRlnO4HVg>7Ie8kbB*_?Y zWu3GIu^w8ZF+x68QdqY~kk@#^22TYelUIr$>`(}3E)&YN7m z^y9UQNB=sjzkT1alX3q#A74cN^u3DD{v&_B?>~0y)VZ-->b{1N?=4e*i0y6scAw49 zzm)E!^(>L3%1WXhQFW4B!|6nH^c;QzehXd7&XP5uHtx0>YFT8Na+RN z?gmWRJQYWiUoq>1F|bvl>UL}YW#=A!N&=QgIOY%+7hh#TnE~Ikhp5*h-tWzgC2c_z4f{4q(i1^ zjo8j$P7tcer%G=;0f(v>rD*KZKVm!L68;VUww&EwAu^`$_I7__uIoYNZ=~zX0qe_B zkDKqjQwE8vpHM-dgg0%*!F!RJKl~^P80syrbGA>2n6RLtqnS|^+)2s!Qls!+R;v70 zr95u_(e)1DM$C_~qWnEuXV1 zR*XC*uYSp{@cBEtBGRaOu_GL39u->^u3^iVLkb#vpP)o|u2o&@RW$9LbpKwXnUdC8 zQ>JGTwc$@}r+TZA%u$_XW&o#m$~z7NCr^t$CGjRaa8p1YNFOF^ zl{H|zKX4Hl$yAA3rA14zSr0`b{E}PY@Z`U_6;2e#0?Nh(7=P{#ZLbyiyHn>3d|I_o zO>a*Wl&@Tfwj-d|#Wl+4qF z&K!Z?z^e5_kda2j*k=Kb!cT1K9jS88*LAVOuRKF~n-ZE3>_U>E*|OpoO0K8CAXiJ0 zUothmE4*d49fv(j(ev^{c!)(2#vq#zL${~~Bam6z6EQPM! z!cdf-LRz7~n1E4bDdYJeYdb?-O6G@g8@=(wrq-&rH<4Azr`7kA6gxHDP3&t9CH8VW z=L5Z?@KC~+3wtomixb)R;&EG>zBxHqdZ}cGP;&hUKS6xA=Oe#obBK#(Ojir;op^^) zN-}AM{v_GpJ!+Eh%a+`=yQ>*4%c(;Ef` z_-6w{g*CJ=WMQ-`kubZx*xT%*78N~kHxzN%uhJDc(>I1@1ZJq}UO(@KKjJ)`B7xh{ zbcXRYD;?4CmPotpEh>Nl|eXhJ~KeMTZL=yW7N`h(1&*N|weE^n&c|+K(;08sKcY(-+vOe|a4S5rDrGUAT30)mvDGP#A*eM@x ze(;ClyU6IpOKA=PAU&hWvcP+2s{z3a3W|X% z_V7$(g6m69JAPLlE!dplSI*a!#z+|@u@GQQW*3e($B3M{C3Z6$Cr(Lo>BBsC|Fb6z z{EA9H2u5HQ6Mlr5v`{rhVX`RceSWEv-f+$E^Q}-17w+kg_vls~>__w`AV(pu$}sFn zipgevS!awlo)ql7;@Re_%Xe+K;(rSL^~a^w&HPNjIhkxG$P zEEwBJrKs>telwhOa(zu~jw-0o2E})ibWXuFXqC9#VCld!nvpgq2IZvemN?5ZBqqu0 zq*M!jF>X>=GUO(+pmTrkA(#1NJa_By+;VL6a+;IHkqZVws3|0Sy7oCxcI0T_I%W`l z45`+^V30Pkd|&Z-8Lj`DOn@M3lTY`oo`IJa`gXLWWhb+S+~jXSe#L-+*rR5$>7MI| zmmR+jRjEUZ@R|Npo|?@(GG~x5Uhjx<9*aF{jS3^@^0I zJ&=4*@-HxdyB1`ep(%G*QeYOJubNz$czgRp>24KdS@<@{dCwygZjQR6SY5u$rRnV2 zRhMnRs#8v#`h$#klf7Fw@9l;FC{UZl;$N|vajs-w<`P(3C0o;BwzE6Dj=eisXppO| z4AGbC`~w5~=wGaA1hh?Q!p173p0p#)EG0?Rn8njQv4^2gwzH$DLK9dSn~pYb0Cb3$ zTf>d4_r@8ODbHV2nrjonYdXH-8CepEvc<(+wb%~%d_(#2)?DxLZKgMZ#tjqvJ2knU zXFrn(5Tve8YgQLlj}p}ik7zHeU+z%N^Tr}to@q0LvU4sUOVXh7-3KQ}j+h-E^9zcn zeJacOnD1RT4afq{syvB2$!hlyM}>uGFg&dDbHjp zMzU?Tg|#6Yj_%P(+q`ELKTGWWgHG6>DVCOE0BCHUjeTRyf`LEMSr$EY?`H3Q`a3^j z{J1||1DiI@ZS#{uN$=i+&tJhAN z)8))z#pH=~3_q)ic-D7e3qAG31s4caWzTR%OsMW)DpXNthK9cDH(^?uaPFEd;&PVH zAxNA%2+7I?_YY=xR<-S9Q;-KLfZx@WmA#9x+Ka7-8;=-Df$I#o(o+K#a`<&`mopaM zWS`H3n=U1TC14)#U347_z8NO9f2Xy&z`B+eKAF-h0Sx^!I#MOKZLM!{;!qzrV=@go5ZLyOdcu^g3t?y-!dIDQERrI@b(Tf`4 z)6hE9*o`p3l4On(ejaTyR+;b?Sg88thuz#Ks?%l=#7Yg%w>eC5oZOFkErAG zUeKWDr-{uwRYe02D8^t`#*eTlxIPi>#Jz6Zm)T^Pa5~!uOeODGeHIs!Z6V3&at*xm zLcX~3;EH*IK+oFJ6>f5*g6D<1cGmi@c*Q%gc_3Y0sXEGA zSImVmS4Bw_Z+StUZKkC-7WkX=*(ib3%z~kX!R5g)TQ>K9YmVn%Bo(hIE!Oc9=d99 z!sw$ny5@soBW%J&x&IZAO1pLkVHR@pZZ84;fH?7;Eux@^&oOJfpI3fIT}AnbT5zMl zH@xd8`M2Jwtu*)ou}FG~3{(Vlb(wnS7vA6vhb8yjY@Capzi#KCxC?2Ut>_k%r}}S( z%&t&6ZlBKcZUFOO5gIm|3WeS?hCAo z0WL2~U9WaMaW;S13)hZnDLRchrk8BFR+sm3{^dgqxvMRF@s8@>MupuQMuo*>2Q+w8 zyCOg{gLQ>yV;?@V=nHu@6>|UudO;g)al;baU>?%fObzBD1?Zb=Z(T+Htn$I}l^^j` zcb~mZ5;I7Z4ohyYW38AWpJUXX{Sj;&TeLJyO00T$&FKR87>Oa z;@fY9?`4f|D9$odN`FQub=4f*46ucsR#5EVB@idRY#{@`ru`((bi^>0dF*lSW0in} zxNFucvLt5IaFled+zvz_k{E+6;xYPaHGMU0Bkg;1sWu`Jp!bu4PP54$tXOMzlWaS- zD=ko@&Ppi8AY$$6LV81(0nvS=%(Z!Er04-Rqj%(TCVlYH(1lILh!+}O)8lnm$+KHA z(aDAe{g0*9V|N!KMBBPAKeIMO0Ac^R^B?4#lXRahhrJ+q!aj2sU@=_F<&J%Iz9LPS zn|ag?yi3QiLsK+yit1#KfT|sNF6=MiH`U5(>wQj`sCOl$%dY4gF-M`XB|BS8n{I-gX{gb4|kJ!m@p zzCUXd95-ngMYQ`8IJaHN^!Ja38d=J#f95g8t`kmOH$O8B2S5WO1KRoW%W@DNoAFcC zRb^~xlJqfadt8VO^TOnc#zwvw^+#=oAq-d%n00H*A4n^*h4GaG?g0r4oxgqf&DJ1N za;NO)ZAuGf9q%6VpxVk(6Sh0DnU}@$B>5S!xsTAwl`txA!GS{H`m-aGHQXa;2JnyU?Q)+W~rvrjX;vkyjcUgc=`k`<07^e*eF0W##$-O-*zi=KHM zWbJ@SzZY|wj8eVY#5;{^ao@n>s{<2$^PI+0mvw}pId>oKPayC?rnIW!a5@Qne*x?BX7HYJ7&9^41 z?!hkRcWNy_xIu4YH=!NL;hLY;({OixoxrX=H#0dtbH#KZ{buXJ;J+6<>=_{fpY#Ij z^Yf*KllnuYd`vW?4n#-VMvZCE08rhQXw7E+)3ShaKhcl8bom%M z7#Fw1J7zgDeoj&N!Yg}={A$B#kI^@my=;TX0DrwtSn|YUxK--Rr0isuh3R{p$3|Pz zGSq$UZ-&x{#K|@GL5#9ymyMo%n|^^zwd8)qB_5oySI4RYwbhk=WLK`hdi5FDbPw zKcIEqF!JZ<+A)ua3R#IZLSUFaAC_i=a8;a3WQ_TQ^4+l7N@HExvlh`irl==MR8jz4 zeeL5wsfxg=39?SFqlb)FrHqHeAE53N+)g9(2|=~6*vdh_Nm!%Oko=))Kbot7XCK{Z9F8TMmki`*j995UPx4#@ptp9W7e-8Hjw$?RkB4S4-W*8NbwqO_6fn7A1A z*jmreqy~`Um$grD%^BGq!%>&j4v^d}q|o8NOA3Lvs2g8&T1pq`FL<%lUv9FGM|m^` zAoY-MwQn~q_Ht5Y>aeF$2oXbHw_^;Mgh`Vp*jGwn;p8)P{Y+r3yl zwk^BXv7qAT>!?*l2}KWET}R*rGh3ZdMl%IhmpTm5Dx%7Cb>Kd;>d%Gn_rsi9s@d)s z<)H$KAM7Ha7txF|&$$~ok=gXrwYu7X=B;C)7Nr?>MRNlks9%V=G(MOmGw*!E?0rN% z;yU2)is>t=nNUR595v7y`Ztwy{6y4XYh8Y;J33k;)NI>8I;amz^GCfP$U$dN!N1(F zQD*LKutv%cX!*ZV5WLP;qn$D?KMpXmXnd>vVeCRQ^Ufxx3XoNW4dwl$KUo@{2V;8( zv_Xsad`n3pt+M-?XS!AbB<-@h2jU(oRG zP)}lAuDhyKXJ3DvZ1NT2g3sE+4e#1|l+bN>1$VP6!#*J(WWsyNr)_6~bw~8Q<6~Ra z73m-&IuJEuZeSR-pHf>{G8r-An!3$Sjp2Fi={Vl6)RgYd{n^P`UToIa-V*2% zm@ia21qgQTaT??M-?i;S@~S@it1;@iZoRJk0t>rKnSVfq?M?K{`}JFGyUYx!se+~ zi^&%?OG-qzpgj&;rf#dt!lTRAjKO`ce7^6<=zH>A*1D$0$FK_*YeNW1EvS2QII`ar z_g#UCLZ@G{l5#RdXmV=lZKj~wqPT|h^>i^#0g~7yZQd2Ww&7=me(j-dguor+a_0hb z%>)&~%d0@wXS=<)kk|G6-5YINf_VOJi7DNpzy6Bj!21kpz_r`tR9EDa=!|3G^->*1 zA#ZxSQ@@bIR=iO;iEO1hK|xf6Q(0sGvl*+oCSAw`hZ%YZ5+ zyigDF_xc{Z@vd97KPT0|7k3!N1tDBxSB9XgCD7FcYiQJ>2?k6s@JLN32u*e=7zVWD z@>+ZXMs4sr9n&)?`oY-|I>&I;J5JYk7x!kya4An+@S~7!#d)YJ=#YD5(&Xk0X%lEv zO@AUgwo2RwwaZ?TTIRAplomsS-YGyNgL^z}`c$Fkv79_U+|LyCHP7zSU_{*{z!OxV z<&!hz5K~e01&zWZPaKS&{sSEUJc?Bhw@?kVJ17RmP;T%AIq$T7L&rcN3bt~62_r1` zLn!*4=Ra1==NmOtCrhe1!)?z3;-Np5?KA7+q}JZK<53F2AzC-WA!amSHr)N z&#g_Jn;X4@pl`I_Y<;XcdEzn4nq3Jsq%=izDZIQZOh_9WIWm~qB+WN$?C{^z3@sJY z4rzCim=jAjUx8!Y+R>cU78BL`OSy0M=(*3d`;x2uqEQ^tQ#2|9v7qyqd!K%S-zFET z6DaY2BMOT5G>w_MWXQmC8_0(ORbw%r6x4&JL>8}JB6hvJ(e(p#`wY5?bvtN}9L-jw zYvElGSzjoH^7_l%rkMosqeT@^8`N{j1%nBub?}6#8xn1hNU?HVl0SsszPxjGYq2Nd zuJq3j=pr@Jo;pL%T$q;GshY5#~go*sm`GIP+E%x*32A2I2c-6o>lR931LhB3oO{kZG67^5UK3=7C7~( z_|dkRTQ{_&HjD|I;5ms!G zC~=GO+)gcoOx>1L2REbR3fw26ajIL41ku^KyWr+65f-to?Avi7XF8a7*N!?eV1aFB z?SdQ^w>3$e8K^t=2;nyxp2oy_JwK$qaDOTAK_E^Q01lC#SrDK7b0t%-6kV;%T?Te@ zZ|7Ni|F0t4E$R@hNuGCLwGX+v#r{Qp!N^vN!n0kuK%f7J$QCf9TIXC2RL zzuDnD40dqW-wpbsl^;l5FYNP{aj#+G((<(Wm)5{>Aaf2kda~dqbC#re7HLIt?@kvP zz4MyAK>my{6m1|3l6zke2BQsx;q_;P!Tdi615q|)!g)WVTG1*^JDT}`HhQz|nUOIO z3!%%25s}buX)ckgWhSgdvg@Unz21nt%CN426jbH~`J=aNq`b`z>8$iz%s>|B5YA4) z)*rq7RWcAgRImSOXJyVo@F7m5pyQznoFM;@=k`t2Y6FFnl~b(UX2|y)qdI5_ft?3@ z1-uSh=s-1jrJ@SyA32DNZ{drQK-&(wnc7iyt% zgIc(pP;hwXwlNgNzV&CF~L!AHn3TMXSs8Q!XUec ze?wAhgRoh@d&%yGUToEXNeT8MdC-s}+ig6Vxbtz=FF`YUPf>WO$9-0ilWkY^3fLaV59-;ND;L+!|ujCk49g{bFT6Q?-*A8{PnS1 z6r95qT{u8601Ha z$T%o3tA@kF=>E#QTBmQ$ZR0)YeYqpMwm)mF@W*Mh2;ADmV7=X;cLg=l*ewc?Y#w%oWkf|GTpWX6UBLyG~Ijt|MIs|6pR&lyz7jQ^3 z`=-MHp%B;gM=l1YmLIpXi3U<%WctL%cHh%T`I<9t5%$-M^kgwo^msP>wnk{?3<8dk zblr|C8bz2CiVln)W;IobN5_2?Z!XN5jr&%no`k9eHMi`_D1^+%G=)77@a>!8vcpki zmn-;Fh>br31SRZ0NY0F=jd~{RZg%Nb-)m7s9csdhBV~buS!av;pxc(+<(0`jpdP9R z5~0+i+}Rx|ce1#!vuxj|#k$C~D{U|g{@5Fhg8s5Q^rbtLgJwV46~|E$++-8(AEY~j z8hgwN01Y4n792+y>!Kd(Iw;4?-|*1bJ9D)e9{O(E$%F`SAeC{P)EHv1H~xn(?8B5# z9#g97>IJ%?{P`r`hl!yO&|^6tQlEXAnp$nR@x~~&Y2&VXdgyyPkYV8ic@F@+Ce4N@ zzqE+dx;CEv7{^vT22bGc(=kX8yB%2Y|2)iY3=LX6$>%&O;9-pX*AD!p}6pNYHolunee?wxcnn`PXyIU-605mFroExVpA#bt?XzG*tr84Y?;s ztI_MVAydJz@Epm{nKkm-?^1-n4H*a*IxKmc66R%rZ~tj`u8!qXZA6W@)`ipjgs6cG zTrbuk*}eF*ByMP{rgcv2jp@5RzUu1W$fbsLJ`mMbp*HvBN!G#GC3(Z-(n9$1D42R#JXLqX+J z_dL7>v{9>_+g+q)g_8NvbE}8X0s(3(URH>U04oBf+b!Iu^{}>+W44_mncz8j z#|A=9E?jMF+Ghs_UB5FaHVK~ie*_T({=@dE`w`Ry$gtBHd5hShL%VbR-)VN3uOcek zkF9qBsjkVIyZoEC>M15)MO}${pv?UjEpF&f=UP}>HGO3S_iLnYp4o1}>o8+wdJyKW z{_4^=N@Yo+l(mTjoo%tI+*hJAVRyb=j8GJw|c{ketjrzuz=XUEOM-3CQxS zOYXW4WrqmlcmNRqSoh;(%9ZUt!Lu<+HD42FKhCW<%`I>(G(}SdQW2-(a|i@QKcqXW z&p59f%1yBIXCCL=hJ3!S;;dye#RC@6pr+`eDryUqpl#fhcP05DJ-=_$-^*+>OY*PP_-8F`#XMBC! zuhEH-XJUCN6Ix#8thl$j;h=nlWUxh+VLyuxJR7?qo7xrUlG^#}o)r063l)ggId-G= z7GODWAV($j1S=2s5YNOxcGGm6oqkWK7SCB3OIkvS6NhsXM3xUlbqhZr&jkeK~JS0+kU}mD2nCHsN_)GTY48f^u^#cZRrAMkviX%H#5&-a=suPNkN_o z=Ct-U z2F=+O2PMiPjjN}!c!VV<(h`c;W`h=sc$ex%7Y;s_;{xvPw(g!#Aw|9QQJk~TN0~|Y zlJ5w%FhxsjEZpiO|2ZJ6CKL}wdDmNSQHoh3T_E#~;oY)>(RzWpIT_hrLu(2AnB^k8 zr&c)-4Noso!&HD+1+B~nC++;4gPxbm7Vq9nh^`1QG*^2rS>&otme+LB z>z3c!?=I1^UjK(T2{;aPDKM3gyA6MW{Oa#EZM1kiEP_lf*au<%o9LiW{7<3-_LIgr zcI$4>!Le2s-4E#o)RsronXhR?1SsV{IGxQq16h55UwrI)>rVvOMjRQNP$H_cmNuj8RfS3`iEd)hWI9CN04=!$grVKI? za?NSV+vS7KCs7esB)9KLx_e-M&Jrq!Bkb7 z__C{=sY}0eV6v&5O&+CoFFRt-fMzpL96-%S42F9Gwql~9p3#=BcTVYuyMok!=0QvO z&xowO6r0w<+V|Y6(@AoEB*^ucnxeI8x)VkGUd@$7JK{%<{0yJM;KOqH5r4S zdKO1q%r7X87_}N&NKgkr1k+v|Vc#>>**W~cDd`i2THhw#1$Ga$#%im=INmY3OK0bO z=Jyx%?6xtyNBhoAL;gsy(h_Q=^KzQk}J!eRi0Q>$j7lUdv-K#>v949G{|7)|WN6;Gf9PRwQ%6Y($ZPKL z5b(!cbE}a;Lh$Ta?N0Xkhm4+-JISHwsO|BQfrGhu3wgWy-FJHyCgmGDyAbLZogf%< z=?iZ{$Wa?$x%#uo2^w+PArTxKUm#!aht?j$R&!k5+pTaKC~LK^agXD&Yfb2<8RLT~ z$zEN{y4AoP`eLEZnoS|RoS8Q3jd&DhsAH~b9jX{mM-+}9W%iTdx}x1t5r?2_C)rSK z&eFKf-|K+g_}0h6hcHg>Nm+2ECtkOov~|%r?L6k?#AG| z5gG3KT_;-Pdpx%0<(xPvF1_D&TJ^^MVp{!=y5Lh1_i1UI?ofwZGcRFR;Ll$lKlr1MB*IZ%5}Eh87+fA`>!Hi#mJ= ztg~i4614dP;i+MHzW>tO7D@0!Li@C5mGM(yStomZAe843W_drfb@5w9U)jIj#R=N( zZGw{3l4~U|`U*iQ20>u8i$<@Q)#D6?&0id{#$0=tLi(OeEw-^;S!`WiyknxO4#s_x zfYzXBvlfFpICkO5cmbo}I3g?QV3dO}bGNSh^gAeaR83| z8I(J&FdpRDEtic8s++|E*7{)OarrElvQm%f)+m&M`W4NS)hC{xG?c6`Mk*_UFTIH5 z_=+v7saUy-I`53Su48%vcIkPaD`Dx`>v2E1D<##J7JV_e2Qc(c+1F91};T5nASx6VzT^M zW`KD@PmYVzgQ>&k>%9*i`06FmMAS{c4rJ#=swcz&PkZ$~HMZ_5&|j*muNKgo6!B#$@m!*Is(d?1}!aTpIU>5*trmwBUV*#%gqo zU2Sic0pI{K?=B3i<;9ayO?rFPy#E6NY#b%8Dwn)9XoeKgAxhKAu%`!1j^!`VhJY~N z#Bg~NU-cH`FtigC%1`6!cC7BfZOt2yENuUCmzC@T^JUP@3{}BjWqtcwZ@W3Lfw=pZ+IqP~j;PsaO&j{en^pB)n~ z+Z9bthK%G@Do_oF)(#vFqp~R27lWb3{)>Z7w(3i7+mH1A&I(Hq@TG<#jfMR3nGEZR zzOlQ~R3!DJe*ayd>zn^yw7qFqlh+=;+iI2FqEbbO10=0fsWOR(j7i#BWm^P9Dl zr(6PW-n?1sx1Q&|Zz!5r8NnM`(pExmfX}lhZ&+8n9MzOlP8}2cjvjp7`<8dIp!SjX z?rXh|Q}TD;eQmt8hlp<}EXaUfcUHpLVlviePbTwweT2X6q;Tnyp2nP<$|a56YABiq zXkf$mx`=N#D_PD|3x=_3DFuz3+HV^~?!Tt;QcC~=`egt&QYMh|F#QQP;! z+tE8Ui{mTiC6q(IoBP_=?(dKuO=0{w_;MdrH?lq$k)gynt2%C2e_kS;)L%qqi5=I{ zaQMQf^4gA@8TZKix_F&}cDurJSw6!7@WDwvd0pqw1GI~K$rq5UtQW4uFkHxLQ=75l zw9`4C63%5OWB>AYU%==He;!je`{lz!2>4^Yz2wPe6A14dvZ(lLH57zS z1KR?kp}#wF%c>E|a>aq?%we3ZXvE73eLW5wPgQ&EWnrZucX|k=7fppjhq1Tkx{68e zp)Xr0k0!qji}1meM@MdEB+WOSQ5SE3Fj_&kIV#jGb96bkHj%ga9J0&0p%| zU8sGsw$)|y>+zK`{6H$?Xi&+aTNWm)kfp!Hg(p$f7`^VntP>#)$^u32B!>yBlzuRb zs}%zr+9^m+eS-@JEC$*81ect6ho$XFWkmtwiV^0c50|Sa$D`lO=BF%XTL?|P7kKwwUuV9e{piZB$x%sY2gmz$Lo^bl^j>wtfu zD*DN!cbV-z7jYT9wf1a>uAYA$%v5@^kl%~B)n>M{c53KAJaNMPG6ED&auOr#c>&Yk zM*our(3|~7~ zK^-cZnEaM%(Avo8SSawvhk3tXw7Fq7S{Pb3QZ6HWFnsd}OtoV6SHz+DC+u}}_7GKf z_7CL@(HCYq`70AeS_osUqmtQB9gb+=_2WW}9?I~nr|=POerh|9D7)r0tcM9zI0zDN zI`Wj(U{i$Y*%K7)cq_08&vG^ed%}KBDlLf`SRvU4_tN$c_r48Y;9VWiS6sge52!uC zl8IH>-E_25C43#XI&vPzqX+!V7$7!T`b zeq75~e{coDptt(3)SVay=?JRm2G)uZkl7W@n0k+F{;Syw?rv#+bN(scltT$T$nBky zhd_*wjkcbRFsmmYGB>F>MEFTr>A+EgEAVwRdSS=+BH>5(&Y(GBt` zGctns={vDZ5No257t=h>(znd9e}Vz0E&m3Gg~6?P=5x_BR;E(B+og!=JuB+GDh@GX zWtfg%vr0le+KREOmkw^_o8n8Su{N#JuG&Wa!*3oMTp-&VmDMRO3#^m$j&LfB)sV0r zFW&0frrAU;Zll*6a~ei*l4$ys^yIjf_Hc)h#>3obM?wKVHQLy5A;$DBqwY7mBg=E< zD%>Y}0AElr@=fu^f?!=`^iB009pwCehIoNw9OAI{Blwp+leF{$M4@MzdrTsIDH-}W z!#>f>svea+GuIxb#~F5Aw(33vfXPzC8OnT<&)|HX&xYhXiBNkqaVX!xLXW7WK)Uv% z2|BPsnO7{UqnKN*7TpjNODGdQcOevBt7LvsKeVmt%;#(X4kVO)kjk|%j2QYLsBX+!?$1`?5JcqYZ1)sE9ob- zQQw5Wt%aC6L&1k%jlFLbQ_Zcd)wx`^>aW#`q_ql;E$Foqs>?!KZnnh&&DC4}pn0Ax z>Y9icK2x_Kag{gIDXy(|_tB#Gm2HC!vP2tdEJi4H9BYopQ?_C`@afW=6oS7z#5)L( zQHS*)_MG)S(;hk@_WxXU+KjLotqG3+=iOH0>mhNqeoH28=y*PEm2_~^Kj`p3I{^?i z&j4Qw-OQ`ck&e)8apeqdY#sh4#7QbgJ5cS64le4qXl zxq2e|!aimJPT3F~8(TgUT=@YdU-QJ4K2gMymD4Zm=R9=zzT98VA3xiMXtAH1(g|}t zpW_uJB$cvEnOVb;{u^Dvd!>@03enc~v7d+5Sk-w&dB(R3aQU90 z@I!n@j{4rfSpd>!*>H=i(^bX-&8i-(AhK(TB6Jv~RIhngLWHxTY%!?8zVyuc_#KM{0~b*7l69xe>M4Xcp%p9+$%peAK^tTT*Cc zp^W67-<$4c3h{5Trw-xVk|%oIBI;xxJWis*=Z?#hu#QRN%LX4-tmCPjVNDz`Wtr4D zD00Rk4Vx}t?sr-knsu6CZ!b$@?Ab%Kpu|r1nOD0ZVdIw%dgXJ6-nkrePg;51nqRU! zcb~FSY-y2XHl39){3#(&R_j;1+n}`RjQ2DaG34V&45o0LDAMJ73gg~?@q&E(JXGV- z;&6V`9t+s+$>Q~8A6xsi{a7NQ>@ry{0VMBZc5#Z=2Z{%ZKBW>uwA@YaGOLbm&eS^= z8&CZ=JG}8#XVgOuWR38g3j657KIw+|y&7j$r8rIHRkGrJPi+P>af0rxd3606TKM$L zW_IW4=|>xJ7xi23M8zCp+ZUe`gB`*vh635cft1eBHFD)VDJ#l*v+2yr+8>m409UcU z|A`)vQ?lure9pUfo>kUP&?m67c%}jSHDZtAoF;+ z zJ1x%TL~twcT-_yO4$HCfUXKgs7&rWf{rsww$IfU{fn%Rn!Y@vbZ$VeO9z;d&QXegy z=v8#7EVhKo6AV{6yw3%wvcl16po&Vz{cpBnq9athKL|f#f)Z9T?1T3XPCb#?iws#d zBFc?tG3&SH{#JKlh3!S1(-z-R%T{W}>@m_TJEXzvY;}wU&wy=yI{L%scUk2Js_3xUm zf*4i#PJuRF=0`*4hzR;!NJHrzd}|e>Fp3%0nCqKqN3s74AY} zyv(ii{Ytd*>0iiEoTysDUY9d5qI*_7LGBiMrA+%sCOVVgrNE$f1It;T?@1W+Zbv>w zFE?J>zIFAHJ{zqsuCYIx91uQaq#b6h6Y?RJc6qs|haRFUrx0_e#Zyu5Pk z|NO^CCCg*qsA)US8Un$>bO$z8XKZ^-5oSRNERJtR^+7BbUYHu)YB^w%G;At*x2!O) zy`MS#pUPpr>HU?ONqHJ;OEZ1zC#=d0=$Jm2Y~rvu*2iFG`0c9en~f`nqjJFMMiP;TBvpr#VH@1(`NpSZ@ z^lnDHo^@n&6tm=po0=^ae#XKF9GASkorDN|tyz>XxGR8Nj0OqJ`ZX}gtp0uL*9f&D zq}j%lLzR2E8F_u|x}JqkPl4oc{ljj+NU)^`XvH(870u;PcRQf1iw-y3Gqc9DH(K3X zIa!Nk`8t(dFAI*094_4M;>}hejPgll7RZ^o?`s0d;|iH?NUaMm+Pss}vITk@8`HJw z6sOSsW;6vhkFmvtl$hHsFq^#H|=8N9) zdy}9c?{ZsBgA^p3m~GT+5$dg>Id`99-`?0NIUC9e7kw0QftfRB^D=*{9gSKaAw{%mxbk^V z$l z4R%_r7e~>{t^H4g*Um){&(fj-v>z#QN2nk?hB+;iCGpc_aZTy)l2 zGhav>ux($%wE61UUIRvjcb|+3`xfMYR~?5NTq~Vr_6e|Iq4&vdx$6kDJzWpog&kW_ zLoTIOz4|#WgZ|sT%X#YhoCGKLYj}TUooW8fWmLXImF@2@$DVtDD?YpVVnxhi zdpHmU+gk(QqzFgs1~^g94x_mo!=07)eX@D+F+KfI@!HS(Kn?l8X#EX8*9;}y%EwnG z@9|N_yCZlIm!1K7?o1@SU0|c5EZr=9dBXhTdRQI1=7jMCxVwWK+}=5+D7g#w>|2br z+6x8VzWo4$IQd?$xo2>e=NwR?MZqkmUUCksJ%OCbrS*}c{7ns|+o*zxAKRkkvV9oA z>3N8`BvDzn%M7=sJ4a`yR;35nCVVRSt?cTPN-lcyu=X~s z!1IW%90`|)JfsPKY*3Dy%+Y?b70q0)WA-x(rOAI&S zYh13%YLWX-z@Y8xu8f}~?Bx)wOtfpwoXsE9Th6JGaXs&mPZ@;ZcrL*og>6$z$+P6z zX=dHVqVE=!O&X2pc_=V2z>RUod3vNxHn6O*0N6@>Wn z3v=p=W;@Ijk8%z?-1V^1GpD9g{(5t76lVV)v zMO5M|pX=|hP`vM(5fJb(7v0sSYRe4u=6k+_4XchfdrgR6>fh{D9L-X&trjoOUP7$x zW|XAfk+;&h)lyA7t?#S_6Z-h;pbUF;8L}{D1aqN2J+H_;gez((0bl3;r%%BWrZe&QA6f}WD0P8#;-;(h zcRURO^6XCd9=0g?dkPmg%&WkmB2)^aAyaX^0Fo<>Sa|@_oiCm-(jShi6t#X7*S@%7 z7uS098`J!Gab&$Qm>%UZz9Op*dv|iFq83WXhQ?iH@d6VA$G5SBiGwe_6i%?jB+vQr zigGKrx#6aPvzZFnNou_CG2W!f3Bhm-L#AR%k{m`hWA}x#Gpxq7Oaq>t52v-&bklYP z0OaY?>0~m&YjVo0>f3<)vD=WJ2&kRWjpn;TLfb$81^ z$Z;o^j1{RDha)`0!)IKklb1_3G4M%EBYCf9=Wx99+CEKrgCG_eJZWZ`J=)pL&ow`f zh^ck*SueZs8#U}D__#~yE#Z|~=FBvF+s7!DvAKBI*<4&ksmVw{XL2HBELeTLEN_UO z3C=NYNsDEo}6qj=UD3RQmGDzmr`^KKuZV0LXA$aT8Z(5P0(jz%$r+?9jyj^I9ZNp&$OogGmo2h45 zM`6Enw>LcOpXhH~{@F6yi>xFFR<2Aw6|?jnm*Eru|69kF%V7#Po9RYuO6Pw$(X<1L2Gkv z3&xS@uFkM}uduSl7v~pB`$>+3I2A@Z3!T&s4p`@}x6?}G7M>A%%u1uJ$Txat%a$Aa zov@OY0abDu_4?hiGGbqr-H^`AR2N3@>!ylpkYVqdAJA;MAl3`#`s!^7SStOd2_#=o zhmdTO0B1m77*!4JMb*Cj+o{JBkZCBusb+zhI{0RODQ2I#<6x+5oEhw9yU4Krf_k2( z5!HOuLsCY(-uTBzL54uB$NLI!qvWseH~CV-YN{XdFWHS;DiIplc=7g1>IJiKew4>P z++b~CZBjtfMT!rcCfU!^dvh@&pL6V-4^|Tq-qB1R{s5ZSxnOF*!Lnyz;nYD{yMF;_ z3Y+k$$&vFP+Wx7OZ-2T)l$Sq&bVz~T`{pZ~eut+su-Uv65r;}%AP_@4YIZ(pCUV0kJuBk_Qbt)W)v-=odZ34Hb5)Es5fW|!H5 z;1W@GIj^t;J(-8fuyOC|RojDP0Z)T`=`R^udpI2vr4ch~YoMpPNb_Hcygg@(kS-S& z6I+|S1oAW$tyo6VYPT0(rMh!6i(U)-1p8E1K&xCB^)V62pmMt|`wlJ-lRU=cY65#4 zBc!2l!5kIW;`CvqwO5_yoeI;~`en{paziKFIcDiB#Ma;zv8<+RvKQI^I$9GUZYN;D z$3nTz-p*CST?K~LXp@!xf7lQTyp7~g8z0io&Ju{gZr~0dDv|#1Epe8BC>G2e4*PL8 zO!C4)KNfdyl^&QGsQ|^(n)dHT$ttY|dzCEZV_A*)-%9jw*U*TOrUBV`Drg;W&CdLD zjC2Z+DN>L*rud@gTNkh@YcVr~=ZEVH#+1a_AaSy?9V6OclP*zKoa%*65dq=7rW6VP z#3`=to#Pov^{MxdLl!46K4D3ESG_Wr^T}#GKa9xpg{7hd*9}~_!U%~h7Kj`PJkX3i z*ngCJh)k_&@Ju2-6{vDHJY01_grLgR>Ru*Z$8t4+xmt#<#qmFY3vF8ux z;piH7w2GF)XOsyeDkz~#+1&nuvvYZlysn7}_bj}!JPk477L{`XPzlN=$S)(qvLPG8 zYO1p_*P#1S+P_DY%5{^4d{Y6f52m5Ao@_NPdaZJ3zG+QcTo1WDx+AIZ1?{tla-i8&eBE}`b62&fB%PQxh z5M$~$wOE2$odfSVoNcNgN88h~UR<0k3PQo%7ph+CU5eTGjgvdoA6<7n^=DlLwhs-f zAInjt?{NhUp*K*LmZd~HwqF`>1$t`U4RvfG?>^WaKqQotljs>pN5+Lt_-Rqs1J`LVqp!AioA9ox zv^(urKF@z?6r4_*7u*Oc9;-k2PFA`e<4cju>k1e-`|l1$8|3&Fl#jKGj_I@Ci;N{B#AD}T z(AE1#^~|S3E|W&`Q}Ic8{5r+~610os?6dvLt*7Q@b1@-cn@EZYTYGTvoMP4Su

M zWO}UA8W0mh@SOW{(2!W2uj_ypoKm^@;5|lKsT^+oMsY#S`9pFtn~Ez>Zok=zkrAs` zMPc}-R;c01Hz!GhYKS&C?zAR2Jm92Gd>(X09YvjM;5o+Tg^oec!J<9)=bF zC>}74hUvBpY{YeA#1nHrUk+ccK!x#fkEoJ4rBYE^5UG@}viWlc>D|;+kj7Dnk#KGJ zn0A}B9;+1QpLKWIJLLmLI~!K_2ms3q}il4Pf?p6+(={c<{CuiZW#^gK(=L6C* z!+FDa{PjnT?-RtPPMa6{Yzu3HFGFZTD{c%K)W);Ts?J|Q?Fr4ty;waQ{=512xpoT` zugg3pI5E7d)3ZE%k{Ly(=Vfa!Zl(qgri1?RdlWIl`SCAY)1!^Uf|d&L1Hbbs4M^%k zp;BXHGks7kI@N<>Kx8py?yJ|(MiO~~c2G5AHt(|1nS$O?c!+sqza13tOx8BkUrZum zrgdC;2xCNenb_J&SNyv4jJ)h}n1-Ep3T(ZbDeI=L>LhluoF)HC&SHm8|63AcFX61> zZSoEKB_u=tm)VO*l3@kL{WhBT+k|XS2{UxySMoUxjtaJA`7z)!>LY@BMuIvXJEf2E z#o+1zl#N_#Ev%^D&a5^4#O-r)r_M@ayL>ySzKUlwHBfk|7O0&%UKHPZ8?< zcy%IZ9V^~s(^+z1740gjW`Hocb0hO4c3krhhgyd#HnHH{kECB(*eGd8jT3~eQ9#mk zf>SU0W;iVFkDx6<@}LX2G3~eX9`6$yDw40we|YmV!qLy#&M@FZip|(m9!Nf->g>lE z;5gft{l?Q47wWEOQR#nT+bcY$6!iM%ecbBKo3CX7#qQT!keCYW*9N59g&BS&Z0$xx zHjAR|&^&B26l@;s*3k9-B_e2T+E7&2lRw~Dw*&$%4{q~Wu7D7*uphZ*W~Pj?A5wvh z0TA=K^snn~o$%3*DV%=_3mZJ^4z&_Q#thN5NKG8e;D0E`Y>OpXf==|Z#qnwupAw|@DO`PDel6E|UBM2?(+Mgb3*NWWlruTMIi3?=gSW+w2WUmSh@?hp;RZ z5Wsh{HpW4SN_;nGd^gS5g$>aRfnfKKT!inhCHeMtQHD$TjJmp?y%0hW?Y?) z_xur85sr*XmwZP@rkkYGMN=D5!XsmE(%l+{G*t%KIxfq>lW*x8g@pntRF@R`d65Uk;oxeMT2gBfLR#Z-qUs=-8GdqKDu?cVOS;c2d=Ai!U?upwe@ zRjoi@%Ci+I&X*ag9J3)pT;XQP-Eg;$qOx2vy&1hy2SvmE5A0B;<*5 zkpSnt;LzGl?O|=c&f3L~XgC5_G<)5{wU`0G5Ma4OxczC$PYeQU_yf*1=L$?JnE3m* zHX}WIcs~-%woiHZ0sbtj+Lc7I4Dv~5b1fh=q4&J6>F`Qz{r9b4Y{-%{GEGuLw4uBg z;p=}#&Rx_;?5=Bbks|+KTLpp2rlJ+E>w+@nLSL*2hj;>+Cv*}_u!G(Yuc+1W_ z8qWN$&Y(E{V)y?;XONhStoW=mczum@{o1z9;7K{lekZFIWJSX{&_m!}fD(dQwrBpP z8lW(AHo|H6&C;2O?p;NbOf5Z17Wk%T0FY|3>n5KNA&c%zp2bOyGR19S=J{Zz*8RZ1 zu405ZZyK`mch{I&9OtBhaxCXh#>*4i1;k0tg!frM4AFm$>8*Z`Lgu;T6E`?L^t23j ztyc3SLGPcuvNY{O{>NaMNkIt10Qg#kb z?xY!Rgw14dOD3#KNAExLqp>61rCjWnEEU*b=Ud5iE$dVUM98xe!&7T1jb2svj1B;t8INIIefpi* z;bsuVaQ|}+{nqIxHDxIgSyk5xT@sXv}2Y$n0#PRZyBu$_2}+Noo4fXSo{l8KwYUZQqX%V zlO)A0o78GR*mv?0Al{Jg8+P$5T!b~KZtVj>Px-+l^2@bo!kNaj;2 z*G~gN@8!#Nh{na6m@J6?j32iQ3bO#G(kyy9r!*CW_{Ttgi9eTm^Xkq~v=clGJ&gT} z=Czo*7pmOzEVbn^sL7ZFKO6w(`bS;rN1b6EFCXMbJdj0YI1qfDKY%L$It-u`WLzp@Pa@69c>qOr2_KM2KUS{D_$hHM=9 za2sFjcZ|s$2-VMwsgLn2k4+zZE^yGhoP9xir9)&dUAwN@9IH>EPn+U62_`?rlyl2w z_>Q-cg-RRk1Yy+&&b2M#uAFne=MvC#KF7;%Q^hujlp|N)_?&(g$#2-HU@8@}2qcXy zD~zSDhBO27#qqV8F2V^CriW5|rTA#Uvo~%H?vwu_SXtN_`J|r6$e%Ip4R#qkgBW?5 zS9y)L+*!8vqMH7^`}{tQo@cuhxX$bncz5?#>ivNmv(0KGzS{2mTX{2vqG69A`EKRi z(4n$0fI{T_n7nw&$OoiV$dcu2B$kmfoUVF=LKzIn{~Y}>&9eI2`Cy1OR(5N6`Xk%F zbyv|aA@MNE0pExdWd@H+R#vQ3wp>95PzO6YI=+@*0McIdI{I~wmmiH<6Ae_xZ<%uR z=L;w8=ZPQ`TFSuzMp)*(dRs#n9d6@_9MN4L9o;yU18-}k6c-~P&9rx!T)j!mW>Ys` zm4)Nox5_+3%YVx_eLYKw(q<;_;(l|2R$}J&HtX@VI~~6$$|qAkSreXaTNAnn`+_vF z%hO7}{;ZEPJEW}`30oI@(rJiZ?iyL~eoCW~j94t$^@eMtHHY>}K z{zTT^5jgif?eKj7saudK7utHnJAM?DNpSc{bXr-h=tCw9JDgfNn)C1pcJiDsLuHMmx9rmywnHqO{agU{aGwJ4`-IHYu;vCa- zt&r5aaWq`XVM1seiWWmXpYo+LKc!6Q`dq7(TH`J-2u7?H@LuKKT03;gcnAi(Zy!T>s&_;+H8`{`GzA z7p=9ZNq^tAinYy5L8d=716>eqDXPm!E%o8?r4-*-eL6m)bg4Q_Ap4cNewBrt(|_J^ z|9fUh*OR-Tue=vW#Zm@yI=u^&vpY37xEX7rhhw$eCqKeE++}9=vme3sA3uUfQ@tzk z{nx_9OPEYUM&b-)s&loUfr_Z3ypN-VjTQ8FdXGIzVJ)X_*uVdqi0<+2-nF|xIX<*} z0>g_{^Rf+@PPX?-3__&!eMbm#VW*V7HMyHh$X>qD{5nZ6z|quO6PuqNH*<9C+8vRw z$kdr!T?GRN_Q|`MsrUtEA91;%nc-aEpt2Jcf_wLTG)Sv=Ug(ckNamnbF>UM=JjDP= zjZ%xLOknZLd~r|YU^alNmbi&w=;4=LAfU-A`Sud81l_}JHv!BEZu<-xRPss>|X{nlZY@lsZ9hCm6( z+XwAe{r8xQ<*# z#aMt~TfK;iMV){NwvU?`FyR}sIoi*{-HlTgzuxVEn58r_EN=~s5hau-x@*3sct<*E z@%;R~4g&1Sjb*VK(p$iy^9O3xr8R4qaLFu|2;lz1s0a6VDw{*|JYGJ0{qP#)?P3XR zHPT!`GrU&a$gst4$dRL`V06o--|D&iL0(+O48;B_#vyaU!GfyC4Qq;yHb$G)e^qG!0UQ3 z181z>&0n8CPtTz1b+w|!*NYvT^sEzFgPk>aDa87RI+}XA@^=fP=i`HzRoB3;%a7*w zHhXEsUy~?bl-O!;C372<5c}m8`xSff zlc<}M4K>}={;BdnJ!Y8`LeSK0DBRI(YH!$*Y68jP8V1~O|36~~&p@Sd55nGkc+Tgt z)t-M8oZGj<4-HEG>rVdP^5RDI2#t-itrA%4;z>SjIt&H;Ye<8_cCmT|Sf%7l$^R6w z(RS2#8vJED=oTuc}u?E_<72qYDyg_-b;DLYrZv?M(ZYY&q9&u;r#F`Z7`(x z==2O_1W6X*A~cQT5hc|(-R5$fW5|wZBWn2M-1q6|*{3|WhR*72ckzltr>Ba(w0+7Z zL5U%8MN7KwbsI|G+XP7*SDQ)CG?r@B5lPV1Ug_=L*ytDx2AeC%y@DJr+vFIFqn{p7; z-*o5YCS3Le*zShrnKscZcxZ@EmjbCaKVU$~nr;Y-66n;)qlZj!8c`|0gE&0Z(*w}XMi*)@-jrv#Hm;;ciwa0O6 zQ*4+1khx$o0qc^PwcjqC`)l>W*@W?&DVF1E{hz($z!cIE0oeIIm~#*}H8j74Y!o@r zBvrPpv+uK}Y<6;uKLZS|0e}JhGr&Mlca9U|q{U0%ydZ^`ixcrZFV5@av)bNRm@lJjiBZ2i3Uh59>Ti}$p{v8%?v{izj$#MY)`5GPDgTbHJ)L_X|SSAz} z%9MT5O49u1=3I9qBoOBiVe|b7^>m}BBmFzb8Or<#9*_E=e$90`Wca%_7FF~m6YTp; zD`fuc6e7z1J=%ehCw3*{ypj;WiJI&jud(k#(uJ%+8&i@7w}Fl&q@uqD@QO&w@~)F{ zP!e?5SdOW?3RLd0$BK4;*^qA4nw=w`100|nR?XQS*X{ak1M;Wwulf=xB8}@NuN~9I z6Y9PgEkXP=69V2@n;@~)twd%Ni`q8@njbtDb}c23u31Q6mY_o~?Nkj>$#Iw3IJpN; z{+;LGh?{wPT4kql-Rrv$XvVGNwS$(<;^k24*K)U%!fqFk9g-FzhPtVLaWQ;toZ)bf z@Ffx3vQY20uz;+>A`iK?eX**BmL}h-?<|ZRrMGqQ;zvpF6Qx_fbxB@{*?iS) zDoz4I+Dq76u>heA*0v?a06DdvAdbk&HaPh4t-&|!cW*iZ1TyeWKV7>J1AmHK^Nm2Z zvAhK#%hX*2B?o0A_k12HKx-d%63qCUfFyR-t=D#&fuIE#2#5b+Ak0)uLH{2Ngwp?E zAh6~8ou+1IWU-$Z2uNX^D5YbDaO;v?I_cY``wF=4NVhE`<}7eV#nWLrWQ%*MyjR10 zLgFedq|zSN3=%D5oL^rvq-Wzvj*3dr2W12&40lta`?A0}kv>w>vidCqDataqdkN-d zMC=kE#O7zCeuhBTeiZkuIB49K>U)xp>q_-ZdHq;iAyQJdfuX#jEUQTOxOaZQ`(we9fH~v8FGA$?h^sukLDaoj> zcO_K`pv^PI)X688Rafml-!MN0e}@MMRO^uNF{s@R?fU76M^Eu*d#r2cRCys(CH}6z zk+}JRTu7_ZOuZs%ht$lPrnAseQv04&Gx+rCwn5>${~8q5kqT?Sg+=mgCB<7KQ5!+1 z2-yN`Zj<$=GhTDq-uh$sGNyd$uY@3GmlC3N^8N|kB;qn-^?92LiDJ(= zeSRsmxN0BSbJB#6k)Px!`Ze6pfb8Py}PJZJ!&Tu)| z@0`oN@n%|*!=Kp~tq!&;!iGYv-nDmB*T1X4ygCU5;)XC+f8Ve35{2i6CF@3r((4>0 z&i>V}ssa^^0F~rrf9dtPIOV#>ufH4;zRh3+3!Main*o}>UxVMCPa*}l=075Zwf~9~ z>H~WtPC`|HqKWvixoy`k-m8>%80H}`)O3QGUCLgB>7*tSC9cf8gAp-=#?{;xto<9`$i zxeIv0XN7{NDq}?hTBQsW3Zne22erv6Js<8D@AQz<7O6f;_|ki74cU^hWqgOqekJj3 z$+wDS9%im?>owAm%lCnk1vqaaCNF@gPx|7ks(RhIUCz1{exmUK_WFU{rr4=Q=GKK; zVYcD+LNtW3AeHU6BB&J%v2NM8;CXZx`@%RB93K@;cfJACP;y6l{NY|#;2ii}JdIwL z!NV^_K@X80r`^)v9TKI=eaycP4brT9!jr;LBU<>S$R1Z$b#=p=J&yx^dQvs_Yv@l_ z!-F$nM)c(jb6vJ_aY}Y~#_!TVM{vv^{$^utKAtR(lMMt{YdWryE z7ai%jd#d@v7!8O8phjzBBdM=i`M+_-LA1f6@l2%qolc;abv#5jAs()EmGoG{sY>dc zRe#MKsHl>f*?*05P>AJ()`OM@q}(oZXX5J_idU|JwSV^t52+ zDJHUh_~_b&^*;%!>jqGynNZg2@tC7RagzQ>-GLfx_=8LM_=L{Na3qjN(#CJ-?sN{l zs@~QoN1PhM-M9`+Ftkp6c3q*NM=d3A_gv9?wIm|C6O#RU5yyGKD4Bg54}c4~ma!je zMx0w0`yL0db2Pdt)VoE6=jtUh=|N>i;lKWDo^&BIZN*itBId%;813S-Yz+YBmUP1so?a_H1)0=jcsJb;EADdZmMdjGbf zX!&=PF)YI;+d1J5@uWw9ONLKlvo>2d2Q;3mkVmxe#IH?_TeJ|B$A>=sXLD@g;RJ5M zVX&-R`BTx%fK$nw&&9;FQ#cvDdv~Wv=-B>AjTH_T}V{?tD8(~pM%M3x* zXR#;^54NU~szWP~sWrw_Tg)sQAu{o3fIVXF-Xc{{gaw?J#`zHS`bQSYto|2h_imL1nLfMX%?vtywUI2OE1Pf(q2 znyb^3Bz3N?S%iQp2)yCjW)k9M)KBUi6-N~DN3GPmg_4ruz%q$L^ECe7{+hE-k>8lp zlgb%`gp~1?RB|n68hxMnt3ZV2ucq3Kn@u~2G>#IgVFZsidKyEz=#Bgif6v=fL$^S= z+Hh9%S+U?IDI84utXSZ9;}z1;t3KUH|D#w?RNW+oxBoWn^hvS6{ayD%(%n}6nDu`Z z3*Mg<3x%4c4dl~xDl$cHI)|!Vuy3WtllDb@WXolCaNawziY@vP!b_0K)iAZwK!5fD%naazI;B|F&`P8{er?SJWBVye6Jqy)~1?t;?u?rEL+I z=_F}-aWcyM_h;n}ME3EqIS&V!4<_?8ozec=| zga+Qm(H{oZ61dOE0X{(o%|}+B64zT+y;1EnA8Y2X!c7hd_MtPB^cImENg}*%#W*9B z{Y^RctEL=;&_&a@q?)~vrG0yTCAqLG7`o1>I*v$New^&5+Rw5}BVw5PVPMLSYId7} zQqkkoaJToJ*um#Es^*q!Z)}%%;PZ>5S6S70M+L{PV@&6#PU}?}al^+TzK@ecT{2hS z5VX;a!bu}D>Z^3h4}se`si7*0$N38Qby@F0by{6C?&AdSXaD>=xef**zoysY5z_V8 zF0*~+6z?d{ty4tKSaP=e$57nl$}j4IMr*qTihDc??|R*{@hR=YsfP^KYG7FHTT;O4 z^E<7gjCDVbxQQJVpTGUm%bAX7%e7t3v~qDgeWUKK!wOZ2v#EAub9;f1{Bd6kY>Pp? zQh%r-8Fjb0OimhX9qJ%k65R>^a(25Z2P25XNSmuUTQqe9|M3<=CTnXx`W1G(A;gAn ztj}8tVmI#D^h(A>d`K^jST~ti&(aLr9!kJhHr#xldw`!0m4E2i8hjblqKEtoa6$oQ zJcBvaPcSwH&-D1}0CNb=u&;rxe>2p@Kg!xQ&u;X)edFu0DuS9*wYj8_jgKMY9S010 zXNV5j^w^L1_yt!>^-k8gOlM@ormVxz4KLlcT6pZZUMGhyd^|J?Nm#4~vfvA=p@Vep z_@j-RgQ`vvvkvlVp0n@J+w8-_*P)2Kz$o}zcKDz=IxIYy2)0AZ9&e=&(8Dfbyk?J` z0=ZX@e$B0+d^=Eqb~CWvf^Hs(*Jx_KDqx9NuV6vTss9&qZywe3xwrl9)~(c{(3T3Q zKz8d^s!SrH3>j*zvRjnYQszKJ1XM%_ks&06Dk2I>suYkZsUo5b34;t_NMwu*Nd$y2 zNq_)hCLx3jB;mbjpZ%QuK4-17*1OhOXPy5PvtmeoxqtV4eXr|tA&C#q>@O{{vYi7j zd&cZ!&G;utC!$idO}XWFwC-x?rW+%mS2qZ*xSlzA#1GCf3QlDajSM(>j?ssx=FG1( zAIZ!{%s7$#bWKxq@9Sbto`+OYC-a%Fk<@JAr@x}^J->>hn8&Z6WeuA;1J6Ew(*-81#@zJwd*RC zV;*~oX>%j~tSLKwE|WOtzY@Q>v68x(A%6|{k!@kgX)}F^*Qz(ghWxR$LR-hWPy;#cU^YzC3Gu&Yj=AwED9|h`(j|jaXnShnNBR7Tevrj3?>;2N=3-h0AB44qhv~lA$|pf+775*2Nl$1#igqyA6K|6@O1wGv-l_c8^2^0mJM)sGw8nm} zq;mO!gf2s_(7Tu(K02OoCIJfM*YLo`)U#bdjPS{{B&P>#TpJy9kvCU^h6SV^s{Qq9 zztPn5rrivlD6r8bthT~0+HX1-Zn$c{-k^+G1SOw)s%;B}`0Vl6C+_j9;pO%;JKmcZ zi-0X|f>S%hBUcz|EdFyvAZ%?9PPTnUOCCwFQXK8ldY3*$yT_LjU4M66X^?D8GWTh! zWi*n$^V$*egRdqKGSN{)l*?9+XQCE=Q&qw>Yk_L)Y1ep$d~yTBB2R`vPsAItVh< z>#44z87739Qa`dx@u4tNI107^XH1Q6MnDJNN8<|=w~E;`hVq(kC_HZ4NOd_k=3A_f z6Sw(5WU*%II4NVYA-3wEszhi_sPUtzY=N&Fbf}@5WkhGfaUc9SKksI$*OipM$=gp; zm!uuJ1Af)VkMS{X@oRZb96DBGNmyrQhg?NWcoQf)!36RJB6g^b2sHooVcgWQYJ-(d zex&YfVb+v~_5&YT^xP6bimLROGzn^=l)w*}x57(FAw9u)pnDI17Ol|lGViqWZwUoq zFZICXFtM?#e({#PH(PKUR5=*&g{{$y2;3&t7zpm@td*+8U@EUM%z3MeA)ORdg?!%{ zGI#5#gwFV_Z9tX&bjENEk%HYrsoPkthkRyg4rIoz ziBfLdGM2CWEeSf+cR_IeCsxb;KM3y9+q7)Sot}LvHe9YAWGXS%CWsB@Z;)vT3lcUv zBRqs7(@X>#0kzY?3_(LXci)1Y$~JD|mkh>Wi8JG*bAhuCgSGb7cG|~QUeSE7KI)LN z=d`yu?PecTa~NHprFZCGBoPkJeyN`|vIa zzP8;r)TCw(OsS^mYsec2>KXZc8W%>=o4c|z%|L07ZZql{gMKtGp3~NKX3Srh9{0Ba zia7VKeq>uwFx;+Yw)Vw5hh3LNGi2~$;n`za4O^s%SLV>`1-|09P5B-(uF=pZC|B}6 zc_$z$z}- zaQ;nLk+^+)K;1+-KWxdbZ*VfHN34@RILZgR@Kfa*0iX>YNnSsDQXh^#YqGH6bmL(n zDUup7M%h<+F`XtKuS`sea?|Q7I?SI8P7TNdIusl;qaeP^@4Vo1Y3QW65qo?XcL>-3 zM0kCR>+MHqBR6l4rbJcI;YER9A5{V$fol9^$?{LEnZrg7jb&4T9Y73K`V;1+8zUO& zagw1o?%D5A_0t|I{p!w*bKvrj+WDm+&5a2|wybZKA159fu&|lOUq#^ZTL-yvs_%}K77kWQFZ35U5&Ly(!zAcQxT#n?uSr_J~(=7pt zPLB2b?)z*V`B8qie4G4~Yy6xM%iAOKT)7|nj}&=og5J_D6^Dy{2wc)q?|j4Lu4 zJ*W={zb7vKTK8=?#$*ClpMCJ(9EC_l$GF|#Hw+wet` zu64}>{Kt8ELOft9p+c!9-dEfkJNy$7?|kl`wp0f1l|H@8Hk`S1=n~7dYxD?JzQ

xzne7vo1 z;Rm*2YGBZoFw>8)`AqlUOWiF>G}sDIHa>YUEhl zP2Wn^Q;7Ru0cv74`i&ocsmf!k(7}VS3~+GSR0p0@^{n%Ef+EQ)Br4MKMw>@Gy1VM; zAz;LSM-Kg%R)@`yi{7z^jm*61I%p{>A+0o|*TBpi987l0(<4z`(SF)#60A*C5Zl52 ztOt%=kYg2eFcVZ2Q-gie=;fT^h@zJ0g$Dch!~c7mLtAN?+wx-xvgVMX;;&ucXrJR} z@qEPBv8ujW_4lLHy21_PM+}Yb1V43z)OLTB%g{(^OmzxcHEAZOyhMwi&_>Jm>&DHV zE+z$uPwtM_TRnLUqgn$6nPfh7NA2hxcLPxNC}wEX_l;0QZ9RX$mU|!F$#5 zvy4UJ;Ta*%wvoL#u9<;jChg+!cU1ZN@umw8DApJ8`Z_SPMbtwL0LqLA9JMG}t!G#v zt5|ZKxjNR6m5?9SR(Qhqg2`pO-}!x^;ow`BXP4#v{cN z>*j#1@(sFmdb21jeVY|AjGA0*WTf<{{q!`y$o=Y+5n;7abFpmgpMIBmtYn8>ey1qk zI>A>9KI{EKk_Kpu1HxSNJA-@kFJu;Z=ST&z^0`)J^AXZO##C&mH7p;Rs9pnU&9H83ihrbE!NIHJ-L0%@UqwYFS&|@ z_;6CjVpc#q_~a$RCx{an@(Gxjj@Adlx*-l@%YQCX(3dduDm=oQ*D1ciqy_kRNX#Gmz@3 zFu`1>1gIFvIGKgBxLyuiv=?#$WsuaiVr;Pr7QU>^&QT_DOQ~6&l zzyT_j6%M3hQ$lKof1B?x3Eum@=rxc*7j@w71-6Zeg{JQGhN69OMcy;`(H1;APK-rd z>c0c3B&yCAFbrIB^%26#PYEUSA+g%rZqMn}qHAlfu4N&+bHh6VdLBojW9+8xPjEmJ ziu6n>bii7E@qS=O6L?P`=H=%0F`&#M;b2DNQJ36}sK49{cyK^?t`I!ySP-lWm&HL& zyl?q+>xlNHVDMuP!5xJZW3=gu`bhi-keh2-w?a7HwFsRn$~ zWBEyiJ51oXpaOV@fb&TpT z&tjS-X_BTxi0%uXgqeeJJvaTFbH;8M*FQ(k9J!m+?>1cs$hOrX2-Spc{0WyQ6rP*# z;~U5)U4iG-0xTEViqDE58eLq!`NPc;$%KF5-f9%$MkW?8_2Ai@uHp9)e%bb{l2RgB zHr5$z8P_57%UT)65(hqBfz3HTBqnEyCZy)sVwq!4z@^W|6)+rKm&CR1pAlO{(p)I%VOhudTd$B2+}EE*1BYu zcYO2P?u`;)+o=KC;U*#XPD}u*N>&9?H9=Itm|j)o2)i!@YPD7o`}s_wA^N9?i|Kv) zRORu|L+yYu4U3P_K_X|C^2iI`o-&0O^4Ba!KSXW+~}w1Hjk61=F=jI@aJ@P zUm6ymQ zmk~N>B$sv?BqhdwjyB~;b(xq+)gAZ(>hHdhCh;d-a_zjRSobWFOZ8e#rG-gcYvu~3 z;J%AnaYSlnHEY!e)^z*TYrMTMIG6iJb{TjVZK6ItvD{i{^_hI=XD$r3BY{0UWtNhv zoYZC+$%}BlIE(2!Y(jsAxiGka`^P?YIk{`FWV&3wc2JiYh~;)W6$aWsa)s&n@#|pp zXv3=VHsY?d0v#b_**JU&nLrs(McKOF@ryiA0=D&i*dV+%Ow{?g;j?we^{eu5SGlY2A?V$*Q z{~OIf+d?z+{|A}@>mk;CBe+w$;5+CSYT3O#56UMWr@$pp>IuZ>=;kOlR48%!qel+k zM)xK=B7z7r2dL>8!Tqkqy?}DS5aC?JJ&(8%I`FEDJuWFGvz8MrujFa7-M%E`7JEVQ zPbBe0|Fb^{4P-!QDF5D&*meOVFoF_lukhqyZ_@(gK-%QDsRI5d*iVpV+4vH}91?d6b8uQL?p|Ue4TNO7~Rh^(L@-tIzWV1>I%E~RwRZuHy z{SRb7YIxx4XBJ>Y0d^!+s`2k;Al|3<+WhrYMyP$PPxjK?yHcCW?nwd-PvSqoY({o=*H{ zz{9PP1ZnZx+@s7RHxQ7?l?NjjhpU?MCo;U?p9-^^y((K8j-4-fuCVfrS4(S{QwObZ zu9#j_*e=b?XA`eg>~AC6rYek8Y_bA|e?B_M6wB$OWQ4}EU(iQs$?o?cs$xU$|6h;> zA^nZp3B=~H_6_{Qz2mgG!+G{whz9@EQ9W~;TRzv~4%uDl{F(Kspz*Dc{;ueHTXgPm zQUYfFLpRm zyt_Wt2Hv<8PldBx|1QyJXY~1Nojo4jQ`3;PXN3!o)8LKe&ausz0E9pZ*y?y_{Ilah z@b8X?imi?Z9|s$|+QAZZTXTewsI1vF4Lr_Ubh4-CLtl!<=--HjZeUM!Vu$@VqJd>a zX@F!#Tzsirf3pdl4Dd=|uF!Oh21$x3qJXRh1eeEnmtD-EuR=9CIdbJa{ec0e;7O<5 z+9koJYzr+DcW6-h|7>~)-fDWlGj7IiH9Zsur|=j4qv=7oC&W#4z9629ap3QLKeu9| zt);s#O18=)ABrpJncvCe6&6` zxcG(&tWn*Ry`yN-2s(8Hqjah}$!dr{Ohn?*MlBuSB<*jtd&3nO+nYwTf^$`{x{tq} zH~0G^5O+GCYJ?M2gpX<^70i@Jc!SZl7GHaPr!zaiGhlP@zMA#L#vS90nxXxC-6%E$ zF?G3E$mD$pyK1+Ck4C<=hahBH+LV}w=}{?2#GG}4DiXZ&u!A z&Ehz=BA?nLE8f7&a1h~g#|#-3M^vm`FmGnvPnrWWs&hhp4@utrcsXn&q`I_6H?%MY z$%Q16qLz_kc=>ht_z?z{C+|HQwtMBMrxJtmDo)or$>d2ciA(YM;(c&<%J`_AFPVu zndnuPE+HW?@O-X7v1rw1Pr{`K?4WrtutmzpsAAspxaCp08C>3^ON47?96m?u$9}ER zssD@;&nPsba1kE8grKzkYto@#bjNDeY3Yc!H<-l0Tvm5+E_WWs>RRbPR=o#L`_!f; z9;+(xVlVEKuSGJhxs6$`W=`e`vDOLmltEbJJpg48&h5c1-rF9i{_?K4FMX?O&PQ+}(-q+KVF&Kg!Reb1;Mtz~YGmZn@}`0TJG_|A_iXrtISfCGOO)ilvS2=zso&ODGD~ zrYK77B$?f}-De)t%(p-dNRQvbejt3G0$iEj=YGSB$50qw{^IVjJomj4l#URwgr4E- zl)zbMB;`>ycS@QsDrUGbt14gL^s%A!J86v#6P@K(JT}Vj=mr_&kO2Ik5kBk2brb&y zYXC%FiLui|MZ;a)yPB!Y;R2}gU(ttI!M|1pZ5D$xyv$qBm!QaXK2I-l(Hym@x*4al zl0X4I$j1Sv^0V)cW(SnUnq+VvU^8%uW_Zm6L^Dx1wlO9nI>4)^395t@oNvjOrthT} zEDR=Liv+^qS@Ky`Bkn6W@tlJSjoSm^d5s)O-WJuMT+qMIIk1gXjMUiZq#(iBalk;gA$v}-=yqeXjreJsZ%f?Plk=fE|fAM;D`ND-;W)Qc_cFcNqg<(DvLN8T%KbrhV9$3t+2!j zfz5^lE_~IYl%U0;UNzm><|Fhj; z2DCfiPlQBtr&r%xy`IHin6_1Z6a7afJSs3}n@!$vgWtRd=Zdht_cgz2LC3qB(`K-h zKNm8+P5LJdeTMx!ke8Ht!HiXM8f`mKkIkpG^#%LkAdiAS(5^%0iO|%ioDxq~i4<5H z(yQ+KR7#bW6Myjgp0;3&dkS`oeChdr6YdmNKYnpySNGy%W{C&%eBG?zT^{MAY|HI`8AMrNc z>c*ym^L6H3`R17s%EJ-N$a*sk*V5^$jWJO0F<_B8V;;V0s0rK*PjC1#}?VW=AtNC^beaDBqxCW%mxB{Ntm zIR*C#pTDJh*T@|QGW>Q^Cx@nGStRP0N7x4=k7u6y$~=3p+Z4^7QXNzuyXyxY8PwUf zbBCHneMO?4;N6$hot=|Q0TX`t)V+>J#lg%h={*n;)F{n`D}pzmne_r1HG701p9{VX2lI_UukLGC^Z zJO^v(er{pXubA5L20H4?c-2AH3Tuub8|>$*@s%9ouF+l8hx%$fO1KoEf@yj+;{$72 zDNDu&s>Vt##tz`=RvdB^Dv;O~3Ni(37D6Mo8qB;ikL61JPWs|p(&Y6^&*2MDm*@FS zet*lV#K&!W672nK+DMkUmQEy{-u(2mjw25l$*R-!uy?1rF0lX3vw)ftj!ppsN8QGF zxhPivug%z=QX0NSJL*R56@f#bR=$xL@0B#@_JY2NKA1fwPvdT4!*@G$^$Cjz-P#k8ZVGRbp1g|2Jh9D zDnm2d79_G7gRBR+(rc-^o@}gY=B!&L#raR5`nzn`UlchG#I1d(o+s1R`3qQL3fJg; z&js?9li#OqyyejjBK3#9g=8~O^UyfF10xy}a^sAKdVM>iEo4@c3(sTBrG44+4qlue zByZ1~cGb{bPmYGSWXX*NZ6R41q&AWx@5wFPmn#)Ve0ghi+|yRHw6w-6n+>&Z5I<^e zN9jF}G(X~Q%YIpG73W@7;Z)v0Q+~5P9m%zl_Ovuh{y*^}z!QX~1k~%BOF(>lWYylW zI%mU)oW`k2!L5KAIA7B^Pw4##{;!Z3QPxzAy!ZXJ{*(RcjjLpJ*_EV~3%JnuKgE68+%TP&{h*eDm-PD<5!`{9O%3 zSAuo0>sOg!j0(3j$V?{{1OckCH6BR(a39=|NNjre{?^Gr+QOOKf(F)9APgbja7>f6 z3F6)lBKVoWpA>(2Doz{&iR40wv(pG&=~U$3igU|SCE4?h{Vm55Ic13G(i5N1G4px)Zf&!f>D?( ztxRh&H?|a4&~zI)3Y@W%%gr9T2%WXJc@Mb9NhC`ImMJHu(poo0U&&u)&{&ASQ9dcw zn>7V?*S0@IDInqL0E5>)5I1Chc5?sOQ~OFD6uuxVpV@8pu-mC-s~xTvqiy7K?kme{{ewWyULgS1%W8+Ctq~kfY) zNa7te&Km|_m-5bxJy)^6`_dvJXLcOaS-$(6gAUQ6q*oLe?_VZZGBG;n{uVv(M#G=e<#Z4A=#D-ci!#F!ARayQXjlxY_zS6ozR0 zeEUE!v`FpqE=u=jsj1e#Fd=SLwyGZu7$ctw>9&LVz_lP_fUTd;Wd2TfOo;T_9#)kP z>S$>!(ttDEI4k|WZ{ry#o=DA+=(f;iyoZss`uyPUxL605QvG;W-{=)(mY39@1}YyU zc<}`hUP(WTm@XE4%`Lw;;osC@=_Q)Izx?y^7bxx1+@fV{-UBlZLd}V0NYcb6QMasi z?%s&ZJI-S>|M|-$d+NUDM(W>hu(!9DZVWqaJwGgFh2XZT5h_ouw>2I^2w=?N)E6KVuIn;n(orLd-;F#P0X~4@qDW>$Dt?hQfm4iSX1%?&ByOr*5;qR?ZWjzl zg@l;Y14#uL0n>Oos!I%O2Ex+6w+ur-Tb$9=d1s8-V0ek9wPFGutObCj0K3lu6wA{w zwk`Zx_4){3md97*t)zSz_U1@sjO6DMgTT^HJsK}2BqkZFuI|?zeW)&mcnHKbn+^53 zKp%(+v?Q-U%Q_?knIYu*mQlB{Jz)F)xoJUpML!m~nFs^ffUa*942>VEqWo66*wAh<9EcnI2?Z5mAz5loV2jo`&1MI*0A4)<0gUw(4 z4-w~WunqJb@vlG%*SVGv2467BB!&RaLr73w&JU3{n~uD2q8{cKHSyb?(K8k*IT(9= zDX1c^1qsUqRdOa)R5lxg+SBs1`gd&?)j^5hJ?$*&!<8K6mk?e=+a3?pz4$NTdraAd z@u${FA^uOwW_^n0BFy1P(hBPz7lbEszT6(;dGpreOzBXBZ~1(dF2}-w`l=2K2Gu4l z9w7hTxA8`@ug>#mdSX)PYcmu3n6*yAe5zJjNT=&IG$_p|Fm(V!Jvc7HM4)}L<``e> zmuBT#A^@3^#5DXjNS&PW*3`fgT;DIionRS3p4f7?zZ<<}cU80cjV7TM_Q%dTsCN9m z0Cjlozha8p@%_bqk)Z^?G5!Pj4`5bJ*%He)bsr6AAGPYfai+s|`i?l=x)qFK(t)Vh zthp3cvFBOmL-h#1{u*hpvgpO=AY$vs%&i|ErpSK6Xq!Q874;wk%oF8u-Plu}yq5%F z&3vavHZC<8JzYe;;%0li!JU2DB`R~8F!Lx?cJM4e!~#Cp+3Q5{AztvM+uh;>XRiQ> zDE>3}9*-Qfo~f~&`%TN9gM0Mb)xe9&!7vL4dWno@i(Tu z@NrGma=2@OtJrMR(*AW@+X`D?iy#*?l5TTLoHwwjRMX6=Hy2-Z#kz=l&(I18{QLsg zn`x7^7t6zXCtQ95%3**Bc0B>28W#%UmVe1TPN5#>v8wJpFXqVJinZpqynlLPu_g61 zJ#b><`cx~%g7t@1bLczqZuFdXFYdj0j_Nv6#^blJ>TU}gXoPE? z!ds=+QoG>L)jfRc<&?C5o3R-t72aN_%L5|vhQA-1(18yegbL$|vy2w@rR$inbxtzEoFfJEm-qOqx)($ZFLls)}`7!KmqDj{oN&-XPp|RC0QQ(9>e&5Ah^u#M+w!8?_CG|6R0cz0A`vpl>3z9S^Ju^;r;vs!Y z<)5I3tS!*PBqskw+BCITZ^qSPan0Id@;YKf_4P9OUn8G8sV91!cd3eAC@+{_#j2>R zbDp#b8w0@gH_~_Ex~ojc`(RI!R9~36w0UrZkMzqovS`B>%#}7i1+T`&n9VUd4Z=|m z-;jqdMBT}7hawBFEQ&pFx?UbS5T3XHsb0rYB$?yJ2bTB2V|d}{NDJQ7;1=V-Yy~hLkbv<}V=@+^I#*uwRA@K7K7$)< zF^RI&d?mk(@+F=!<$@FBPTxqKQyzH&79ZFBnpHSZHokwlQK8d)dEB0HO1F0Ms=uUR z@q#l2s(R?XX>xuA6jTgBNp_-g>VfzhO~tQ$M(J5EYviR3F{5`nY^;j|P$>H6dziwp@$CT6la6Ljt9lbah^J<8Gc0)R5Juw!jOKZ6V*JZ36}2S$md}k>~fx zQze9AWIET|;#|51N70=RWxc+s+v@*x4zrH0>+Wg!!?df!m2dYI5e#m+YECjf`^94_ z54vStmM8hE4Wjc`F^j{tvK!6_3!60{C>i(dR0a(<%cuCs*@^l}C*iZd@ZkY0nj2hE`oCc1fU&Yqdn z<+|u#0}Ofvu!&nqG`e@C-42FGe&uk@g7>rj1%b-MlFM_LdC+C8CWIY(VPF$LLi^A9 z^v9}SHkmFYZ$etj|2iZG$gCys>HhYM4#}F&2l2Ux)N>_z_h=DiBXh zYpD+BJc@tfm1hM4p@1_T5uWKznbVn~`a2vvHTpHgT)z#O*%y8Of9a4?J zopQ^ta1e|e{a-m&V*$OOj_khg*Gh*GRvv1ih7Za zQ{5UZb}Cn5!v*DaCIF9t=RL_f;>(@JO+1QTeC%~B-a|*N+r?9r43x{eot4k#8Zu5a zesGBTf!Xc0OIN!+`0MCN5i7g0ev%=6$ZLzA-gqSsT(JI= zzpymm6EL|JgQcSh(jp++HO8uGB=fVY zRzQyUvEqpNJHYu#}o&!5hGlJVdd&C9u_6&GuJ-RLY z!?U6J`#QCw3D9g{{;TF~gX`xdpGIEu#DKWp+S~Q7IqS)*I}3{!ZUW!iR+SmUB%l_+^Ql*4k_b!frE8s?UOp75so+9^DbERCT= z6HCXop=xI3nu)%?01?$%*rLUAbU6yk34V(q2ky5duxw&$YQ;*(K$r-=ODiugk zXWn7TwrkJB|GX;rF<`$LG72Q>P$R`k`__Jwmokg!9Tji%-t2{fQ|DoEqIK88R47u3SV=X*l%im5VmaJu*N=@VkO{ zshgTRl?Sz!k|T8(qAPFfX#4D@&CpNAvRxi%y-_&)0M9e${jesY&l4PQnk@tW;(9XF zZmn%yi7RDgX3UpV4T~z$gPeKzUMs=GC13vk4>=9qa>A}uN5z&uvV`%^Uuu@3aj5Yk ztnGueX;*X}l(yr_)SH>H+kI$T0=KKsUF;TSF;O)xK>pCxXHZ;6khg-8yP1|Q*1P#R zTrGCMUQVY#(*EBhGXU>&=o|nuFirs~1MA)W2;V?zF`G1^6d1~UZ~7PITe{d?$gq`J%<|Dq8fR0$ov39v`r| zX4o@XJ_)x!3PqTHH|o1gg3L@k0bk(e^4si4p*utJDh;q1s?vGSmVx0f&g%M%4BaIk0;>Md-= z(WD>d_~rrTA&F3f->MYAZOMxMTz~lnRhDv zjT(|NEh^ug&LDsD<|}xKlzin;T4emyFyX&kq2RxhHB63u;cm7NS|O2P2|-O9GtPn8 zoe^^;5f8d=pD7G(>fLVQN{Vj)sAn-;J%@}x4CjHXp31c+r95v% z?2R01G~@0u_gwqE{}OZVe91n~YveA*lAz};mU_hO1uMuF8DHty~;C*VI;}>CCC_gcVhb&J}}}0-Nfc) z29Ri$ye9JcRtqLgo!DS7-2O4JWjlG>sE;bq<55)5_Y7_m4CO{znsqjXsg{R})1_CTOCF?~n_UB?AK_U~kx% z)oESX6aSUYQX~fd-WvLSoV$Y5zVhRyO(k;%IGirz+Q}cWV9S`z882?^0OWf=D^0^k zq8GpJd1%1T?J}Bpb5SdPOQ@dpD%%|Wjf>sBV6Tw133XZN5M3iP+=OQlnAX3!oI+mR zgZA!p)#GGJ($RhUjgOD_ra4$=z(rry%$(i^$TME<)Wa*0ZF>dM0-Jv&C7P74ftb@# zi%_AXZez;g`g8j_R49C+8ql*^6^G;YzAVFRAKN43EA2> zbazSyH#cMw_aSmXc_pCdUBC&8XDm?KtlTKo2_051jvOv*D|b9=Ki?d4zFc40#OLd-Us~jA1PQE9 z@s&fRY6o2WgDn-5B6uC&a7fOz+ca-H#E;j!kIi81Z1g731kNWV=^^Zw-c=}Mq`dpP zU76(83a^%sA)5TkOOItOh)H7^Jyl;pW@j5=3oP=WJ~Ogd+(UThTxEA*+SI2a!9SHd z^PtS>3?I(U{NbpcG|zzrax}zG+ZhJQ4_Tb=t1MWGl>Xxd1mvh!>=oYQCwo+CZ)n_1 zy6kh@fV#6if0-pPobOJK?Dj^4M4-HKYHfXJD_`g+VaC_G&za*r86j0O1y+q^oFzpT zzh!1$qjzOs0}E^Pdg9m2{;$WrPhti`D!x#-Bj&qP*bZ*HstbHE(CA+Xyx*-p(6eUd zz4RK)Qxx~jy39pp=d85QhKeygAei(EK7NH=!SgrZdZTm9%X38%`4jy-Q_6hZ$Hr(1 zo-yhC-5hPGsK2--hQqU4!*Y*2G!P)^xvk{|1UA?_^>6 z!t9SNQs2tygy4(^*d>(fE@qK5VzxQV*p=g)W@G~>mrePUNqq8KQoEL#B83pf%v>;AcZqsw@o>axp|BTQJOej)vWau zA~#pJB-}oLf(ip(3gwv}%^*3<+Ts`c?FmA#(wD8eC7jMhzt=)LRx;Z)Kst+2jYg9Z z3LF-mD6Ncfe``3%MTwn9sEmm;UTyOH{jn#fZgPn@7q5%&a-Rr$$&)7{huY1=&ZI$7Fa za$9#sU6{2~WTB@mzZkOqYH5^T@DdWWX~V}~rU;PPB+~1AxtYDyn?# zQ2~>C#&`HVZ>@tMjD>KyiYv{gWWjVS34Jw|qb?aq&J%#SXMTMb!^gdDgn8T9tg9@?svug_9?wc7GZs<^}e#Kh{hF+SAo<21;cT zJ@EKr5TnSpS=SJD2jka}A$`7>&g5A-Yk+VO|9uMteC{K+z-04RyXQk%0e_AjMa3Hw)?jMt-*eajLHAp12Q|0^;;~zJt=wCtzG6b;c1VM=bW4^kI!+s zhX8SS(cmL#-KC=-qqkoRSSN-+;)aFUJZ_Vs*ptS({j^=|0kk0!W5oS~q+h`OKlDem zZ4C|FW{%8Wrr*GPq5dxSTf0*3iRka--OpajkYz!ipxvGK$-!JIIob;-*agB!O41eu zY5_0}jQ&k)Sn#}4dM*0`M1{?RZreWrat|~3k*pSu5r1cYGVbZ5Ov@ov_}Sj z2o}Qzvw97fgPL-x*uW%Rs|zqs$2S>vC61Hp;{h=-=#(t!bODfAI;JVL5{@I}b2M=s zD`Re|nR1m7vB?%^QPKBb`x#2V?(DS24L!&Qo4|yQmBoPlWAq!@G@~Nk zC=EhNeZu>yB%;}Y6H+8|*X`OhY1Je>+PF6YQbrEmF+^w>7naNfOnbfZ?>`_*G8>un zuoVXKBS#H58^Y{`Uqde4{BAUZdV;@!emWuf+`=@n3ODLPhT+$L%=_2TRMcF^D~RTI z&lq7Y)XcUdHXNlr?Q9sk7Bcks`VTP~*(h#31=ILMfa(n1oRGe5JQU}?kF`s@XtuQD zo}jQu-vl6Mrz`fMBM<|Ydrjhlx_8BDjVcE9M z!U&_dLin5xsy)W<%gOH%pZ%DSE`I+zxACQa!6U`2J9tWz(#|h(m8y&MJjw|HUcUj^ zp!98UsrwjxNGAAIw>_j2m$&Z(ujdM=0C|0X;;{SfVkp4s(?X9eZJ1>2ojKkleLbvq z{mA4s|C2pUfaG9j^>31cDMwPB8ngJunhzEWqN`D}nP8n_)OT7DZCyh>ws|rekt&>8 z00l@ZB)#p3H94?`<#A)$ZGMqWTm9ZZuibMZU`Kqs*6P?dCL7TrgR};xjrwSDK*%Eh z@z6Ek>bi3IL&@Lyq3vsv0OC-@7lCr`Zb#sT}!tT4n2dWxR9MPiG zc=cJ!okHVoDARJ*|FQ1~r`W@%nHy^YBCOI*bV4LUVn?KP8N8^<5c!O{o3IB=(hQg< zeF{iXB<&rc*9)91vEKNd@R4p=Y(FGU_z1h43o0?x|7nUynj`sDQ_=kqsf|%4^ao3A z^{dezwkfY3QuKc;7*PAhI-+5`#q`=FK#ZnNW3Bb*jRL~>Hi#j`C2EGa1?&|(lhAVS zr3ni`>P=zi4_7xD5(}2%L_O}KlfMF(!x-wGWf{jHHy|;4VXC}nqmw`jL|_}2fhhvy zwrPap#c|IL`8n(EiuB^T)%6>Zv5ZxPCl-cQ7$ra)^WCAb;=^>83O#B`0T4m##_`_Ilwqw9_Uz&H>nA8eBp!*?p8kovvQ~G z&D~(uv3n(!S5N$kVWGZ?NmtO~yJ`qsP6tX)e#YE6Z}p_1>DLRsjHBLD<(<1VLFhq9 z$@(YYbfNJR4f@A}Vc7l!aSQe~Wpn0HIa8~3{4x-_rS=pPk@1Qx;d-KEbRQz*ivY>> zsY>5rJ(C#H^v3Q7*V}Oqg)ajd##Wnz0bh=Rq6}VfgdfEv8UM9QYD&J9Lm#VRR?;2W zj56&(9!>=akF93u$VpT!bicYns-MpMyVV2!k-V0vCm-#;l=|pNY_*%Oy?ih8pVZ@c zsAy>2uE?TETX2$hXNBIPyt2LyY!ZV9_)>}7iT>_PUx0$R?LZF3&u6~A{pVD{fT+o&O_M)e`I=BxQCF%^ zG&NPnPC;RuWc+PqL>vX=Sz7c+w>v~_WS8miyth8~eTd%DCr$_cicIBkCC`!3i zoNT>SGmvsa`AGVww@jC)O5ilXF1W7mspv5f@=gL{d!crEqf-LdX>URGEf#eLKhLrjc+&p2ngVc%HZGMXJ2|2AwN;86BiXM_Ci zY-F*Nl6B>xk*TAZxkZRb?TL&nDFf2AytlHuWlKqpcdxc1N1$`} zBV7i3wHKp2z1N#rvvCtuKy4J^RaUYP9xo4{#|#7PRe+a=zH(2wT6&3G2r{G8;Yj8_ z*qRjglZ}repg;;DG^LCK2c!XRvGfqHk|yS_BPBV~K1o51F(Wg&+WS%kL5v8w!RzwH zUjXMI&7WYIZwyklU<5W$;o);k%JoY{h84;wkn+9vw9Uf6=|M9oFV%mY+eFcB^Ekog10 zKzP|{yA(cpz<#MmEVC5-T?Y4DLmBi^M`i@(_+^*vZ7$svM#H;qU<(c!BC~tffNVO8A|vZGaln2kcRMSI3P5Y=y|Vuri|?n7r$>Z=kCtP z+<9qPdqDn;W>NNyi~^XtwWjvueN)(FAMloN1tmQ7bfOS~Jun+T;pqo6l_^YhRD%KD zTvv4P^3H9vh`yO(5}e;^`%<#IU2{EEne$3SUjv|i`7#h zfokveM$sFnCK~?wF4GmEIJGe6fc3j@F{I%$Lc`s~u-q<_FYas4`*XyA#^YqwHxQ<# z3Nnn354l~SmLZTvNV;yq%TCP|U|?!!3N11}Q+J{r(RXb*YxqLlQ@z;uUh{{4wAAWG z@$!p3Kq~1VmR$Bu>)~Ka5l?Kmc#sxfu*&$61u2x0ObpzJ|6UhZ^+&C=b+J%Cq3k;nSZ6rCzlPJ}8|-4B zm5~nSpQ)l24G5!y1|n_4r{5M{&x=Z%7*9LEsp;9DDf0k@$voO4Zvh^PBpsT5U5XAQ zJ0oloe8jx^B1Jv_tf9s9-F!R4G3eDY0e!!usEw+`HGG7IMLXs2uVE2EMMS?Vs%6Z0 zX5gMxv_Ly>>@J{jNeD048dijT^Plf7tN4`v)(J(ZnM@xeRvxo@*ITd1=^*$=f`(R_ zKHD)+9J@Qm8M&25&(2gsxP7r5{X2gXeDQM=$kDu>h^^uQH^8b_nl3zTdvEJ;9 zV;oJ3&xZnxnt{8wFdlh);o!F|zQ3ue1gik5K6(Q24606a;+Z|plx5tk;*Z6PUP)PT zsu8)whl-qiIWnPG-u4vItLL56+xa?^%{>1spNd|)h)4m@5tt6TxtUAzv|@rlgV?K^ zpkghaID&mPe_WCXJgm|DTXJULDrozNy3hJ|1JAJw@BK&CH3!nB+7mcxw%(p0Kqs!Zy4s|0rkf!Nns+A_E$7#?sSB_Ov%+ z{_eO|Tz#P6vS(D3Grddi3B@cflPvD4BLg@OZG+jq?%rbuIMhC7sL_)%tcX*NRE@ZV zm_8Y&jT$0ZV<_hwu>8d^9sDB&Y)~3o-QLH z@zk2q)LMmLvrK@s$2{SaLXJjw58rf1&mdjn0W;)VrUa72H-XvCVjvk-|EXjii-Je@ zDeMj7`zmxRX&D`#+VvIAR0(AfN6hIT=$+Ush}N$75!|>uPpmm0jq0~nISG6~?TKmg z9TBm^1KjDEp3OB2nX?%@GWb!QJUoNCdY*lKUDPPNPwn0QZS@i)l4Tp2ov~-&9+{n= zlp2H4I}R={YBmAYkQ?^|%!P^o1jb$21Q=Gt?k+Tq6d5 zOE^6_dyW?|J%H*;ZdBjCDUb;{>Yl(wB_VtU(Q>la)@jJtU?Rf9@Gt4cAw$02Mv3_W zZ5I081x01;bTiOwUq#!qG&&G{p1l#PL|VKNn|hM-@pnCbJG$ZwXm;TA6G;x=8VrI4 z8srIQx@N5rCQeGt)Aue0rYCQwsQV1Z>G7{dB;Hn4WB^rT@n8hV2-vb)6?zfr8c?#& zTI+?3(}(^EYxF&^CqNV=D;fZqvI?irGxeeFh1%3@4~hZhsxPL|CAvXtn$gRrq$hJd zznLBYV026SS90cyz5dl#`^%kG3owNXcWATlTKuE)rV_aKur0dWC2+0x(92euS5COt=vC44g!p^(BpXsyggNxQ92 z8eb%M*X*Ea)jFPHHP0Ng5AQp1q8_U_EG?HNo9f>E12)YiJ_8XYt>gs(EXF z^!E7lg+G4JzY!E>L~}2hec%2NM}J|Z71!_z-h8ikYWAxG+KLngpvxF*KT!38gA{%) zD~hVMYBTc`7f9&EsacL>7Y=)Nt*S|Ir8Krv2PkBBv-M#QK=ck|K-k^her!rH`62mi5d8)75L9%+igPp>H*3&%7|^!hBuve6;1+DviA0A_ zdm&{S>Yh2aPwEZe&DHCR_;(aW)jo~k@opKedfQ{XD1-Jx_4pqJjJjKU!dH+(rMR0v z8dpg^P{J&iH0$Z6qqWJ(&}Eaq%sSpj(-@2X7nIJ4ZP4+xNrp6$GN%=m=Q{xnEcxIz#3<0g4GRfLVfxQD0LnzLC7iqj*& zs?nn03^d^B3d$ha7@#xS*^AywJC2oNP9Chqii-c$Mh=sbLJadFK~*eKsO;*gaN0Z{2hK zU%^pV+>Q`uIPw42L1!w7bthf=XG9-FbtP(TQR;(~a3tM^6+aefU=;*)V^m{k5;Y zX0wUN**7J>$m~F%eM_iot)l}dV5X5EeKD_1+LbVzP2JRS0T&XoM}AN@a9-+YVzzc- z;gM5R(F}*NJ>EojatD)jIn~&3CHaDx0x1iw9t#P0qg9hwQkUh)iP}zCW5lC_wlsVc z24=N>RPPTlSlRgr1LNrjSB+$qDQ^d2cJ9kf`<)Krc$QO`IlxFR%bo{YGBHAcP?c?u z>2ZLU$XIKt^*`nO_`nznMjKHu9Y=NtU|v?$PMUoWj5~KrrPsD*wp68OxW>fH)+ws) za>B;Xaa3~WrzU)fvXfxRA&%yvV8prt+P;>Bi33i3`Nd{fXZodm&cx}HA>@3zFb8)C z)h~ppls%lekK6ctH`CG@Iy?NGJ?^FzV1mHvoYBiU6!Bn!^t=gGXO1?^%#f`wsJVYr z517-}1JU3zUD6c<8pn()aWOkVl2pOD#-)>HI}aL$|D>zKH;P>sx_p682hsm^(G{ie zXj$lm-5)H(tXT)rZe}$8xh~w{o!*M8?4A173yqlduiBYr@A3!R$lnyv+Re3aEPH%k zv*MC3KP+eKo?8Qf2*(BX`J%n5cH;|(YMp4CrH9Q?N8IUagGHX3KFZ2kvwb`=U$OBl zzKp8A`AU46B5N%X}XtD%1o6F~VFKumBfURpZ=&l41?ewq`ky)2dcDLROm7Q0cM`-lm^ zx1t#N*S5&&R}TuLbf-~d;RMOTzgdrUlV|TSsD81)i794h-+-L#c49nL}oMaRf_8Dv+vmNy#6Rr;wh>k>mT-wT;k0Rf2kf(yomCi zeb0CkcX|~UW~>KrAyokBY_yq+%0HNiu&1}3Ts!6k^uG%E$I{?66)@wOec>ZR$e#OfP;TzL_c#(I%)n_C*z=(m3p=YK6SLfd%Xy`5nlIFc> zuOz0+V)dnBy?l^tx%YySTGjc8 zM-Lqvh97}qz7hz#DE*7-LEN@R6Y<*vG{=(@T_yd4;wEIi0-%K8tgSMqQ-vW>US&Sij<2pb>-SB>q{?oT`~^1k8z@B@>eADs!~mw;pUea!raCVsfA4x zp#V&***1srOa0$ZB~RYHimfO_rX8@}amCk|LCK*WMV-m0%~2(A8ClBtY*a*j!f|>= zi>#iJmhA+N?oE0`KWbw`plBSc7r|1H6~F))gw(x-8`9$oTTi{4dm3g&VdXOxBX4T) z66>nZ)ZFJ>K55Ic8yC(MI%7b+uSH$y$+We22(AEHI6oMsz8MSK%7J{f5`{<(f17+a z&|2%@xqNkAxMzkKX4oVh>Y+aBbt+~3l_#B(0mp-RM&5CB(E8itRI`3$yCfh}LrTjL zpioUDN5dsHmu$)%EXH_BglKf6`S=1^!{8T4zm1Gp#6kWjTO57hF zTGLnt{;OmEZrVkil}!HgQ@@8=+!^aVC<4#D!C=zm9IHJ!v!!4g5(e2J2xJ7$JgQ%r zDwQ!ICs1luK|1pH>v15os1l7s z`GgD*;Q+!Ymq?PF(r;R6TK$1|RlWB(?~OSexNR`9Hv%Y2G3+dRGJEd430ZEd47K_r=?KDfFuA_-W zbm-un15j~dNq@Y$6GVx}>HWRLYg*4LH5;h=KMxy3sP`5L4m^|0MCS5Q2Hk(fKF`|p zpZ`Qm$)=y0sTJ+c^h`CTQN-LiNl{2LvQFrKN{F1&H@Nf5e3$xt|@%US{0T zYjJeN9JN>Jd82CNqP+Zb#I6=plG#}6jeU%|yXG>0TFozV?zAqstEwa`v*H0T$*kE1 zin)ed6V3pz{YSyP=r(X<4$_SQAc)lVzbm_?1*vuEYzOA=k4%DQoD_vM`>x^de$nn1 zRnG1?V}9sO*e|T${+3x_77J9hbuVyFUs7UXZoxqe;E>^YnP%#<=VGJ%kV zBN+%;@EM&@*A6$6fJ*KyH;an8uBqF4jbn&^O$3!ezBJ%mrjFsZUX$JK2YgUOR~L69 zOg8xDxF}w=k!ff2s9 zr#Lh8CHZIgPe1n|n`@RfLO+Bo{+aK~t!xC~6s4X^cK|p=I#_NH*mt{x<<_xzI%&p42fSSZ>;FQ@%%=ozX zwkfv0DM0s+i^J}bpCI4PP5p?U-UJ4PuB%ORlaXmue8%byCyyq_H!Hp|kof#iZ z6YHkzmJ_c=zCtHZwFloc_C*XLDv)JVu3!Ba$fBmayZ_G`?800uXT~>%r94K=>nG)=^~9iI!u(fH4l_NC{tkH zNZvFk6Pvi;lc(IkUL|?$t?PiCQwS#xZ z2lGpcvKHGgjEq096Qd5U$yshdz)E5CtV8*z!@o{n-Z^shNVd?YuVOXMA?2ue&K1@g zp{Sw=K7#6>kDiQKbB-E7ff4<`(;u2G`DW^;`$qwH$GF@7=TQ$DFMcqz@7(hi_J5%i z=6dqome|do{tKn>DL(*+;`M%hMSRJ|J9r5H7HWi->z7>`=p;h|JCt?<6lQ7VzCiUs2+&*M zR(!ES^bC)twS`#l{B^_8?ubOgmi7oy8t0s`hEdKBE^>gZd5GZQ4qavv7^KGqw zvV1*e^e?u}P&FZnUGGvm~<7id&W`ow#Pr4reBx-u_j`CDQ5*>=8N2UOgi$|O8-5l2!>x~0DCznf@#M*5BHf?bEBxERb%e%Rpl?W7jIyP#p3 zwzay|DoWV%!~uq1Y2JRvjri@9W{s+M$`+`M%-H!ulLH5DOO$1_l${bmvS3Klm;fLt zP}^j}k&O=N)f4?M+s}0(Xis>K&o-kKZB)=%)2^-(qZ03`E#1DT^*Vx>sxXe5wbo|6WuKz3VJN zrIuk~O#{H@=Xi4Mog;DDk^mD9_DCLME_!??5!vtJ3-OeBklDu*j>_lCm#xHI$vBZs zkWE6&vxkaKC5K7I=ZR6X&Bg$U!gVb_ILA^~1gPraLrcYc?8gr|yF6K5g8G(U|IE+< zahK4{*$b*|p55neS(X5DtZ|d*w6IjLb2Grf{!>BJB4!V8ZzT$&hD#)RN{4V<14R|R z)ibz}wTQp0$q(I{S1cbbj~?8we2ZEK9IFQ zKLy;$Cfvcd`&o-u?L!E2@@(HcGAj6ZaZ6qK`uU>6Wd(Ny_g)@#I?$N4lEVOL@UEvY zCn8t#gp7D`eW?%p(ex$3Wvbt9Zb3)xe1yc`Fv4P9LKZn?D00CCT@#U0I~_#)HV5Cb z&6$6%=PB>m+xch%8Htau`tOo^ ztYi`e1>neK9i!MoS;%`%Rh!YN#2dq@Kd(*PxP{CULeod2P1T>09krO(WBcR?_~w9) zT1A`R{*#tjr4hC3(~T3n$ZTMzmQ+PUjLF|o?^8M^`hO!v7zmQ{5+h2ha2c#5tL=8H?K@QG*vf5B<`~l)(qdnP zZQyUO&9o2SaD#m#j!hg=1UN&8ITm;AZIYoZQ{*e2Ak%LEM`W^zaa}D?kd==lL z{#$IcJb%v`n3CnH;DDe-vNo*!a7tRsUr+tl6z>_kHOEOaw_800W1}r2gGL0B?5qoZ z()%GU){e51irX1cB^kFeG;kyb z9qzZ3`RU%Tbyh#-y|q^IH-aV@s`cHkTQ!+_-8#Yj_rfP`U&I$XPxZ>oJg8%c&?WE4 zg(pxxL1VGwv9<|N@1kl?-10SiVkp58Nd8}u=Bu1LL+DuJg;yTs20`;VPVIn&2ZkBo z+%v84t6hI_KzFPSs}efh7%_eaJaM`?N=ep%(B%$aJw3Pr4*YAGK_?f!@1&Lh*eUbh6@D}XkJO18f*)O+piarvB<${Fsrx(e{BwnQ7- z@En_4xY-UI0Wv6@MCvzVmj9_h?g{tV*Z!X$1MB?A z^-W%{4bjisiJ@!5p`2Ck+cQ>-+8UdReX}hH-n%M?Y}rRI0-9bt0Q$bhGd1UzgI2sf zc*w>BH~~tP10HUO#MTV2?oTkV7oMFv!L}@PQWGF59@O*jw@np zD~o@aERI~i^Qyk=yA$A``3WZXX}?lHSHS%&LJ}rSZ$lI*b9P$GWWNL^nxW;uoo_I~ z8p^Tkj6uzUa?=Z*kZ%ls7&kJq4?Y#Lb_mQrrY&x8u?ONSeF>DDsL~ndP;E;j(4aK8 z%G_Zy{>On2ivFJ$C`FUOocK zK7fb_<8&QSb2LlbrYsz#9h zbi{_x@YFsgG?MynVX#>$=QOgoJv)Ona?wTdEII?i?yI+6CRQ310agwC z=Trx2;!bzi(`VqVq6v*Hbt@kb7!_jXk=XmYB!}njCd_+WSpLkO5JlEgHah>b=1Hig zpD$3y&0)+-mBWi)3Ath9Arv_YQRtRDsET3J?IU^*hM{VW&_GSdN(4cK)|n&kC{gTl z8hWJ4D1;s-=uP(Gk2hcf^AdYFH^-B&cmy^aI+uSCjI;)!vGLYTjE^N`@!*R?C^G-t z4U)@bMKe6BEng`Ek&;HLS|6R2-fJRMUs_PwJ@+|QFjKvrGu1{nG+B9tUG@yI1x{fl z6juo0F$4;CeHvtet#*yre_%HNNvJm~$`jajRC9qp#8+eKA=MEUw)U!SDX#TS8ix1) z-%Q~DSp;F;BsGbL8s`5kZ}kN%V%7p6sbs~ELfAZFV}=XVDOy|Wh&f-hY%WIt$JDKJ zD$G5zj>w#6E7y;s*P81RQCiZ$U;E@)Y00R0jbYRgsMlI6P)9Ml_u6W{ix3{-2(3YGTA6xhAr>-EFqpFKoKl|3fPe4~f{S9kN3BxR!9+acxj1Vf#FZ(T z&*!1Motf8L6b>lpr<*w=L?kl25z(iyo2?6HoL z?h#q3_DsEpVvD+YfS3EljWn-6oSM?n%^rXmod62+K;H~vG*B#t0R(URIPNf5-z1^@dD4}Z&iGU%`0$ptDz{oF?6|0t}$*S!Zv8HhB=v%t$af%mk0(s+M;@NgQJrB@U zt!Nz3;N zTETSd2<6v_h%##IRC?oJ!Nrj!!y!I zm-olGlj6MOo%cy7|8LrFOngRU0ZsPbeF>)t@f7NLV^CBb@Ye;~nu^>TxkHfgLv8ez&@dhs07Yp01B!THXmdn+-+A$>_gGv)#1XhNw^Em(#iMBf^A_dFT0i2y1pm0s ze#y4_k)qT1r^V1PB>m9tBe?=2cd{#cYMU#-&ONi<<%cE6L-0eUF+(j=J&S+0cVBmG z_mOqzUd9|Kkxx^kx3*gIx@T20Ml`nSJ}YdTT2*EIn$oVh#js0Zf*D^kzGS56(;nHt z59qTv&o~;Fpoby{8p?bMj-wYG>}83l)GPr=8ZT`yO3+3zp7)YD9q|HZVuhV(z^SjI z?}3he#pget+!%Jf9=RIFD1>bN@ZIkC1b3ded6hxXvb>+uR{-`zE~kQolajXfHYps+ zD&cRZ+fUreXmAd{KoG~X6PxZ7dw6|_e*;P-KTM(L<)<^7YiFO?xX)HN&NV*jPf)FS z&&YZj9TRE{m-pQnLmSfP}AMS>C(fe)_ex&h%o)QwM^3*b;xL;Q?Q0(1@v}ZvNy3uX%e_ zrN`ieAHeW^4jjpc{k)37M#Jm0wHX<7gATei%;XOLsvP^Igl;m^QFH%uDQ&ua>~94i z-yqy+FDhiVHg@KyfDy>td#)xM-|!5Am+2Lyv{?`R;$qFUVs?ANRi^VLY|vcAfQGd_ z>d`ZlFX`$J0TcnoYY_Fw>SjVcpLj#2EynzVv;P~J4_3r=dsOs2p+RH)1IJ$B|g}Jy>hs@?kzsK120uy`#&GQ8rWs< zqXC^&XLdKvtc=gU3xereWVJ_?KEvvb+@Xo9qmDG z90aOaxw1epP^`?rane<|wH-In#azY`(f_daMw+emj z8q-$}R}tIJ#LuI77HySzU1AFvEUWD=z-yq6^T$wLnMk7fhjj;Xf^Ad`YvWJr>hqJJ ztb>OLZp`a6PWtA;#{-TQ>&a)R&Lp#Xb3Ga|u#Hr5R6H#H-0_xz;o2nUh<#F7Ah@f6 zzPaR-cHCs9FU#B*hlt}`ph^E68IJ_Ggdjb9%WC~VK{9Xtr_J?q_{RLBNE_m2&rCD| zPEDcUg1(}B0mgsrn$zGsKi}?aIA(bY?18viTF3w-N4#kUmUd>*T-l0sGyySZt&g73 z$`%fuPI!4EmAIReid%d4N>b2-UZ7X_4eNud@B6^k%R?_QasJhZKwbgxnm>|aQ#rz} zXM`tGG8H{Om1wnU#!e>~J-QdC^eT(X`MBDR7}MYk&~Kj0oR)EhVRA@>>;BVI_68` zD;uldBmY*{w*V3XpZ#uUQ!l-5@K6(P7si%?fqw5@kg^8rJ#L^Oy}WUrIpUC)wLTE* zkWKaJ#`MXbN|l$Sv#qV|$3k2HK(%fsF1M`%+VpPZx|p)nK(X8f#v2+{09wqyGxjdS z{4-iG1#&-3_o`lGE=fN!H#&E6M|}d5RoD3| zr?QLn?A%@KGK)yz`0il5B4tpZQb-lb2brm2&lU6lvzEQd)FvP~z9jI>%#gY!%*1kc znyL-^QJn)%7^`fvEaKXUEfh_n9cx728Q@P zNb|FJ?7QnKBA;PrR>TADZ$LnX5Y~1*N9YT7q{t)(brcT!Lz@qGxe7(h4@A&_+ z0IJSt?RqzL?$K{&ifQw>DD-s4Rd6L~0F!8RJjK z7_i*f@?}0qJqP>ge)B?=8hLi%EEi?wjJ-!Yc@l|nm)_MGfYny(`d4@?LLG5S;AXzxazZ}ZR@c#6#jQM~HXN4TbabT-3Qos*XPHGY~jS&X$A|8hQzR1uq zYW@kA%=j$4iGYb8~YO=mxJvO=Gknr3Kc-E%()jF2BywCWtpsv1DI zbS7(%8u6Vno4wZ_$nXw^GS2p&?y~KJ*U}ek1D@>ny|?Ro8NinUKhNJE-t@f7#Zz%# zENpqK{jNUlgtL3++-i=YYv{Vqw#@(;gyku-*!8o{c#}D?ODp!)u58;+-H{V$9y^>G zYghq}b?k6*r%bl`nlq@xJns{pu20ic2NJ}`J@4!TAnv3=(fSe7{vLc4rTsPTgi%pF z&zPvelx}>dbqL#6z{?WF->m7)oge?}4Wnw|&F1>)*KX<`fba=eTF)?O9?Qv^RFy26 zdUv%Kf9jIfbmm-wdJZio<)>cHpkA8Ov$HdjKTUJEbs$9ygFm*I`f#}_;fAM;*++>h z%GO91H%!dTRQK(^Y!BK5a1X${1utIS$318V$TijSM9n*`-Pot*i=BC=&T#47hoFHF zBAm{j@7VMkmR0DkEu5zaTP4nvT z$mGtCS$^xH#e=vK-Rg->n8^IIGph|@G2Kmlw3M-j-h2b}m^R)3!JaD5nKCqxkq0oR z?y|^W6I|Ul^3#b~(@7T@=LnGAHTbx$6`=hEppb@EtdM?p1u(3C5UsTT{)Wnz za(Eh-0x*mo1^aP~hu+4wXusDNeRCmXpv{7{U-+FFcJIw~dtnOG<4>gUrQ01hnKM{v zcGw9KCkv=W+X0Y7t25iEng0SGG=W@vCfH!H#nXeL2ig55`24`qu$95YPACvZfyi@i z02y@DgI#Hl)rGRn+K{bU&zNlvm|4~LxGSu!&(7oNGX+IEG$1hC`NLGk-|?c17X72z z15RL=w-fgHKy@|1t;ZCN3g#do-8YZ;;>%I z8CiV~@}KbDkc5N3lsc=xp#fe#K)B!Fq_GRSu)nGwR+K!ydFR988|v5cs(zxD<)goG zs86kq2W}E1LyG9X*832wXi@#vT7a{tA`cn35r!cMxfIrgDpqZTx;DI8KHVJO$@I(6+K&WoI(3~q<3BwmOeh@8xE?910vVn_C8spNT_ z8mRHHL(5#sj$c)e4YD;dwDn%^Yr3nVExAMy4x$4)tq(MDOTPyhx6;jp`}L?FfqE2= zVGN9R^(enc=0XgL8+-XrzMexIwsO`S0hS1^5`ZrXX(;W(?}PRBase0f1Hn2%xHH$) z{Z#c8SN7rkc`)vg_fBsd>?AN50VW(IJQvEnbR9PWVfeR}@RrGny>0J25b`MofDZ4Q z8fLSs`=fBJNtzw`2h}6ub)KXe^}FHbc{k=t)Y|#jz8G1l2DJ~Mody;jjMH;`BU9Bz$;ffy8k?Zkx&H8viy@ac$r6hYfp>bOU~Te{y@OZzH$dMd( z$lm0mRxE34HBaYG5P1Ap@);BU;byXKm~nEM=ouI}a>*NHE4ytvixjI_4gFoVUWqGJ z7TU_PL*MF-%}U8r?EimJ116!QtYPUt)T-@!RL=Gfk-1|WSLGKcJ3pkrj)shc61EHo zVfQLdB2q1MXgsv_D^1Vowlgg~L`xBbXr?9ErZw=m7DHr~4}$j=-r;1V&# z{P!fFJaI?t9u@ik8TKeI`M*Ex@e8wqH*a;LewzETCn-fW)9vs3KDae@^f3V1aAK=& z@-b?AdD~i%(Iwk1B^5F^6a)45EqxAiQ4EI8-1yeaNfpQh^k#2nMhISJt0FE=Gt!CyQ8qMM&phFS1%xJ3x zY+fdrV#P5x5lf$w7JVx|yZ+H1wuIVJT&+ES?}5}iY9bH}Yq<#%8kd)RdL@_3UAKAm zc+?JR6~{92o%yAG1*9IhoS&fZB!+QJDrto8JXZkAJ2ITB2YZ&Dr#hyw4uthbk92>AI|~4?G~I9J4ppE zYbWVFzUibsfVpKOcf(u9H1fA^En79ejigY_ss2h|>w^Hhg)tV7zrUTQmXoow4HaN% zyD2M`?-GYzN-;XYlN9p zi(}4+f^HVYw{%;Lj*RZ7+WEk>!Mdecf6Zq;qRjKs-W`{AyqjTW%lLnjCZ-uy<9MN{ z7lId+cu3xP8mjm2Me!9h?Jv2_bT8bee?xFeiAyq>Jp{};trK^M*8NyGFbn0e_UT#b zR^^SA^;62J8dKe_%u~U@S0=xCtrb*~v%%y6bv$vrWG6C(;Rb{YG}x(d9NoR0lb0-f z>y+JCi(`MUn=FvOJ^ZAeIic%W)pkc$l$hL@s~4Fbvi0)|#f7cfRTH+4+nHrUfr<4L z-@XB>r_<>)D31(}e<84#yDx-62F@HPOwY3$BlaSZs*3{Twq-n$L#lSVr(tz-Bg!`PHGStpiIBw z(?GIFv!kLX4JjP#4xCfeiJ1+}^zlK6GY_P>c*STDgi$uCh>qb|51q}A(+9z~Y&|hy zp$~MxxqUZ)H5Ijr8WB=~ea~^!m82cw|2xtvK$6r>@2uwQlLrN^VlrFTt4X5(?T8GVT|Qax-fe1=`6G0xk`I2WMd~^_2{B=a}3AU!#!AdJ+AUW$paW@VUxUKPGYl8m_7*K1Bi|HSlZEGBwXmyzbZQvh5;MPg9D>3m3o!mxwAsOk$qL6JTD zh!$Y@Ne>ly5g3^6-FlRbvIu@^3Oz_fFrz23&fv)6i{So1Qdg4G(1EK! z+wxT~D}j+ii2}kC)@96#v3*;J&owg>eW%9}hKcCW0tu)=`RN6($dD!6H16)=2T zvOnGyG7hl!u$PiaDZ+^cO4{=$-n)1D?41Wt__Z1bODSOo*bU%npHy9>4B0y;7 z=KPjoN?-@Z4%Q}?Qk3H^YJ zyw}JekCQI*tKG0S4;{_ZyvLJGV=u*j0baQSj|%_5%2C${>&v|wI1u~~zhPwQ&OiJH zuCq`Y_E&P@|GsJ&J2KUSz)4?gUESw5G!Fy(2CTt8zkwCdVP@Ph^v{r)hOf39d84R^ zm$SDk*xPMy_{Bqes?r{!y|jpMSHjcX`uJX z!n-DTC#9&L>Q(X!tceCkEP`9xDf92WE`p5CkKQ^N_;AKc=S*je;gshyx9pIHz2S$c zeaHxJ5ERFZRt9I!Kw12J#wK0o$#uN}t!UO7&}9Iy4LeyAk3|V9oZi`~Up=N!+JSBO zACVv2xqAcbFkWsX?eD%lmP4NC1+i(p0J6iT6LoLrmYW$-U*76FYa;s`FG-B{dk%j6jQ%Y#`YlFD4{9#Y2AX5+wM^+t z3E;Ho!tvOmr@mPg#1s;}GRyCQ`6XzE|rlX!d)k<7Ag~33R4PTIk-Feri2g95i!kZ}6y!VDH z{SkLBa`LsJd;TX_P!C5lI-t~~rq+`39>KEE|^8TSVpa^!ocdk0> z1o*9HX6l+gGmVNPMjR$$CjOh&Xm_$}Vuk9P5p#|Ix#2O(J=1^-UKSqjQm@?~wumYJ zBIGPm#-D#f%|pUd0pU)r^*+FKuQbeetg1zx-6A*bb?4&m9E-hh%nl9C(b%~*U(q@x zx4E}W0>dov@-(2=xQRA}Tk#mY1d`8+m{~!LfRYr#U@W;o6S9}R=DZvU9O&$TSiyh( zKVk(JChpq38C~qX(kqx-Ji#MEMTzBGz2G%#rK*z|l8(GfQkpmIu4;dZ{gMBNw>OPy z@?87Aceh)pMWKj*A||a=sWOQQ5=cU=RoWs@i_Ak5MCKs`1VRW^1O$Xst$+{`6#;2*fycR6Nd0p3e9>?$a{k5`A zjTP0-y``&nXG}b8`J{@_53>jkax`RB3FhV%cRpoIXAyFJN+8<$g(Bhe@!pqsbNc4z z{QcCpQ+!_GZG&yI+aszILhO}tdW%_Iy}A2UqKLhn=uxo#>xmP9n{12Y8Ay8g*O zOBtuf#7?1x1^d_pQS^*&4Ul$IcXl@Uy9;|~6~f-0WcODoWntjbQ{~6xf5G(8zdsv# zbacf5Y}sQd043NPdpB(#kwg0Sz%1|3xSG2?B>+623q3kbhq=(j3hWI_jZG=#yog_@ zaDrl(A>DOLMwZ$9c(ZfRs<$5f49WnpxR7Be~gNjDxm! z0i}}jC<(JDo%-pzuO;{W z8;LNgoMd{sLR;q07pwyJFCqlT2vIAOcAQc+dMA~M%4!Q%s_3%8>{fkz9R@v5Lj)#Ny z&M|ldf*o*ezx%-zb z$1p9(UN5_G#f-^08}pcqg3-mSjk%JPra<l;AVLU# zmvgyy$ZvZYd#jx4vsLl?IFB6z`VhQMt*;8cpfM`C3a1du8ON9rnHx7QEry$}Li97L zf{)<`j)vZuTyOC4Zc&thCS4=Ow0*_hd>!up$FtmPxeZ-lE_9O9VVyne^_x;%Vqaqm z+06Fq{}V_VU^#}+A|l$Q(Zg+`^K-mqQNG^xGF~zhzrN77df3{ZLP@`t>g2H!=Kbgb z&Fs=UU{2ykfl5@fK01eQ23r*?@e)0$<8lp`qCt=y`|}L_k!))?XJn&PM^QrqY=)tBo3bmQ!rZr3yHqoX7p7I z-LjBwvveTxbduhCoQ!?%sIOZPRubf_N_AVlkd_Q@<6Im3Cv?+JJqmqvuc2;Ci@Mzq z(DUl*MCsglo)LP+WZ1p%S-nUZqm3Euur4%w^GdNImqz(Zl9IvxXU+0?GAU9Q6`c-x zQ$VO-);-C2HljNu*iuTUy0mwDiU9%U}(y zcBBR~q(}sqiH_=Z{iVvbD$kQIXTiM+{17DZw|;!V*z8Zbp$W8&Crl^1>bLtDzQ3ob zi?LFHqlyLPxNxqFe)7M%#BYL1emo}HzS0LuVc zPO99ICC|4F*wEp^QG>M`pEir~BRI+I{g_f%Ukx1px-&A|*E zWW}3qs&;;V^Y5l^Zx^C~8a84n36}nr+?$^d#5i_I{>=%#o$sBZn&PW|Q2^N)tj%~U z3vx_YG7O5W9yV@z@3-`ApVP!hlDkt>TZ8@Y)&|qolz4@BQmNPKSciL-ehO*!UHCis0GRfMFZbnTC2Y`S(2a^9S2{m4$$d?Er!mzI7Qy`wo@X7u<&GfNLB(Jc z%R2A?Dm3aPdB{&ZueQ<;;w}uLbhlgwe=_k=v(%Rt-zgs7PC75jz=eg7Y7V z?|=0JTaJpVEpOLlL(}lj6^xbGmtOsh0B~p(f1PGX<#K(RJ0+|CuJmtZ?VNY<>6n#+ zZr%(HnFGE6Fq#%S@KUB0fipT5eK;$^SD3%&KQQf7BA*$0eoqHCloa*rVGQM?; z7BMfyc6b_m==M3c*CuIdiN72*JN*|etu3D6o(1Fx=&a&XM46)-PFL;tr0$iJwmjrU zPZpurNHW)ChTOmyt~AwA-KHn(9vg+Tx!~O@Xk(aT4y~3z!sK@nZKC7#e(EKNnDXdBGv<)2B0Awx_1Ud7vAaC3*a_BJ!z z?LS;EEvoCyv+uMZ+#RhA`ulNu1AjTf^4+qbU2jfk{&NRxBCO5eW}g$l{*}H zuQ$Em=e{@>Oz~;ApgWUv>`C$-AZjnXm@1h0fchO{<1d!ibHpkpsvFFJ>~<%fLI26q zJba-4UUr2WGL4V!b-H4o{I&}066nH({U#J6!pqYgQ;0jst023=qv`kKIzAWDWb7H; zZY1U)MH~YOElq6sqD3v8?!Y*FuWG9X+hzT1YBbR2LYOv;07D6x;x%Jtlkn<3OSNH!riQv%2J@ir-^QLodiHmQ5B{`I z8^f)(!uQ=(|8MZf=++7U)f+2Dr9H;Q9569qkV0z;7)Q_GBDLZ$RM4^Z+LRb!%@F5_QIRTaF$%C7QzUimDb%b&Ovv?Bi=z8m0a8 z`OP_r`|hmpF!yg=272dX-t?d%ojmHvy*Z3~D5~Mt`6>~_H{$5H1hMfGGep}7yCgHb zzhxs;x1_k}sQn5=M1m8FX^wc?mI_UT%XMb$OX@Zbqf0_Xu%FYqpqv+$1&=__ zZQRw40nbXS;zM|f_LwUQiKei4IaWc(m^J1&O8G;s{f5xKo7_@9l_9g$Fz;gUM%B00 z5Ecafe0E8IOyGw4)E~_wObTYYu%>&{#J)y&<%LMI<9PlUJ#L%-xx!Nux7~b!=GoBW z5%mXZ>=~FnWr}@wa&f~~nD#>spJGHl2rLnwHi%9MH~0PB+)(~~|DDgRC#?G1leXk^ ztEWF)AWM7Pp&-}>a+Z0e426<++@Y6jgVW(E5tFcRvNiyg)+j#pD!9D#7gMS(H`2Kx z7u@E+)kD$Fbu7A!;CBi!I9eA0p~V@SzoB{@oxzCX0Tg~Y3dUs3hMN{S4^ny^0(-J8 z5d1T4X+16qB;Nt6LIoA1C`ZLbI6+zX3CyvXx`V1jeWh3f-}m_k>GnOe_eQifrP09^ zTP&?XB5$a?tm|QN|Gx2;!6>0*H)Ls~ben=>Yeh?+n(NNU{Qx`GuJmfYb&fZet>_-p zC~95ST&T9&8+KJ9BnYL_v5l=D`A1yq6uH@EeWPn-ptjy`4QF9UCmFNg)M)6q`j51X zxfkyF`>aHc(O$P^UY_cH1ZzV8Q%^XxN_OGg$4m~}t$MZ60PG3JtBaDj;{@-1=qzYH zUSWs5-|>H4+UsO-37?j--lnc~d)-}c$|(>+QB<9qu7q4PyWW#je&?m8{C0INxbi?%$jh19;>!vZxI=PQ z(y5*4JBT)7h`W`dl4$nMK1gMn8F^M5>=t#=XKO?$JS3d~N|%L| zC4t++fl;sE%&q>F$c-OLcO8HlApooiMV)vB=yJp`Y_oq{H5_|4#YP>K+T{AD^@M2J zr!pR@UrgW0hH_gcU*{bSXWY@5BPJ2zL>-;4Z*-ds3tO|e6>e7g@hZlcVQF(M5>~kW zP*(!Pc#f+_K*+`KL}CzN&-7xp59*-J3mJt$2a%*HUgM>I_zNjN}90$z)Fz%1#sgVAw%jV zrC{7`NWR3BB`Tj%Sex|~Z#C)9ke^hmf}H{Bs&2KHRQmx%h#=?{b=VaSX9tf4A=op3 zBB&m`qkG%{uDbo05a-i|70ld_J1+843>F@t^cZSPL11B zAV@Mt-gef$HWWDq7L6g)SDlRK=3mq-1xSl+cxknR&A>8ahL<~z8GI*J5hBT~mxpBQ z3uQz@e(U_DD>qNN7MPLnr8hJ)V~V^z)d`=KnFeh0u;RQL+~B|Tx?e_fUgW4sj^!%H z=sm_!5>NwcU=N&ZR`UaX{tWO{wSk9%C)HUu9dsvN@%2>cRvT##PrB|bBS))w^}`od zy#TvlPv-ppKp?ZuFnBz zyjNAFcfl?EMW6^g6XtT0=GZ?<*F?RcRS{B+tp_Xn-6#BA3rfA6D;5Il@^th!PRida zR)NnDWB4l3mgSf95YQWBxbHvBokbnDqd#9nk-kx#6@mwK1JKD4XP8^u)Qq?wk&BFBV#3ALzxmgB0+DfSDlW(}+UOR_d0XcUEyukw)?PXvO_Nm8$%(4gh(mb+U= zF@>AcN8CYy+SV#)60rTUSDZ0Y5Uv7OAptDGt{fl@DI3R5CwZtrFe#h2{^zA>{D|8Z z)yos-_y*K$7iQG$zF$G9a@mwRL$?0=j(1g~7SxkMEDc-(*X+y}EB40UjNSk^4YOBR zz%~QfVZz@C%J+9D=QdlW3c~`oBv zn5jwhH7)4Aq}xXrUToV(S^TN!!VBM4EuTv(*3IBaIpeDI?&xVG^;FgS@0mi$d2t8Nm z_J|pg=7cqW~%3w736=Ap_g-_KlFHzsL-;!+C8U4cWk2bw{R5~NNL z!GgdixHziqkh^)ZefjOYUi_;!J6LH0j&NmacV`_XX;Q!oD2t|F*Y7Ex06{K%Y~{}m zJugstV0rRjTa=~qFe|2U>P5945|!P)Bc*~fWYnG3D4`T65TML75nFQGf(qI0F|d;_ zIEs;~k({nB@^!QkJ)nE;J!CR(f?v37SX`C!878JZYIxf6PKNh@RoSk3nnP5Ln)J8K zO7H}#G`)S36d=liAh2&I(D)|@K2JO0l+wgWNxH^!M`)Vh;H1G6cY^*Tj)0H5Ou!ms zq7gE5_Z7r4zO{l=Se~Yb(;Ma`wmiZG+pm!$=B^^8Ih8pr)St^^3x*!j)j*<+5FpLj zXLJCl)R(0cF;}8b_7)F@BD}pUcY({NB`NAXN3d`|VlG_0@En9dwBQt{Rs;YcUi!U$wH}1*IJbtw7l$^U%j`pnQe)$l!<4AtPXDN3TV6C}*!4V#vq{=n z%_DzIdzhN}DHjP2iC`Sw?4})^&8y+ES&`#JO@A8rVHo-uPDJoXx>+{pUH0FVx5BVX5-+4t zW@>ES>`XO(Y9XGkPPJ`_vAO09)_5fbg1JRh)!(x>Mz)(msXyok^rVw%U`>Q=x0Tg1 zzo)2XX?EkR9BAELS4Ck`>@qN69N+6?HO{mqC=u#dDJFOkK-Qw)&V~N?F-hs@k=YC_ zS(yT(ql7cXmo0ZdeTj9nX+wWjzs&&9?qmBtw@J2epQG@r7|%PV(QX?=FE8pHBUAhi z+-_ihcE%ItK)k3)simw^n_}Ms+=(F`tPZz%6H4XqW2mnL_epzq?a!$ekmV*7Hlq)QFyf$={AJ{cJ2z-{LxRN7t@9`bMZci z(w)L82)+O%X&ziOLlO(gkHj@1p9;qe1dhUBW#{9|NRP}5hMa7>D}0^L9cxsHiOIz} zpFhd0@xmUA;(A1~i9O7R^c~MAV4u9!U`x4m9s(QYr%y`eyV{?$z2(;rXS_ZwvXHt$ ziy-EE|NlldJJ-cTULcmU#wvr*qS zQmpo>O5n)QIUgVjz72GkS@<7d%f@p7ZBpQzIop}(FHMzz*+=UOx%($)*dYf^-@ z6$TZO;#flN>g!ytPwlOb&rZc9*QWI1!pqcVHy=sUMKxO;gb1?rfV;#s%|J2xS`s0} ziJSe)6vn{i-0V+CV;vqYsI^4D&)Luou7W`?+e;4yjU4sVJ+8mm4(8_&EvCM}v3MKn z;k|r_Eq+&C+3Ast_c#?{mse~cIXYz)Gd`=PO}a6P{31gFtu`Qom^sU}%F+Zd&J zpGvGOOJ9nAeSB+Z`SEs=S?9*lq!(ZgV(r@Id8BDUwmS}g5ASNE``(0lsWm~W9$k_B zdA%d-J$KGrm1nedDs<*fYVF8d^ZFt4T=RoedcGnikr6ELh*b>pw#tK#JG+6m*kJt9 z@ct0Q>#Jdz(C?!kp`4e0t^2L|-28=ys#c@>{02|ycGm)N=VHA!<>=8BMD49K`;dGt zX6rh^faaW}R9X>1kwFZ|Rpy#cM6|x%e`O+ag$NGJZvB1>XJjoaW5tl^4}by7LDrgM zg=&I?8q1!1&*9@3L1dAre`#ie8bQH0FY2&cT696zLzCUVzW`?7W+`-(-#M+)o8!z6 zP3d;LDF-oReNuu00>$-lQ_Jh)=uvg~8dqH-VdO?=y^mC#3^A-2aO~Q@A{S6EY}a5r za8cSjU^TeF85&Nj&^ADiz!y}b-#LNV>Rq!JZcA;S@YA<7$km0x_Ctf;=%J(?c5wNS zk3Y85w6=LKo7 zC4!MYnI(7W(n+R}^i0pCkR?bPj8*de-tyq_(w-CMfe;f7aJHO?hPRk%fyGe#scmI9 zryde!Ygk>MPdL)GS5qn*XQkm6(sVaxRU0MiU3yEtAO?61r4?4VAoqhoNbvNVrUW^Y zFAg76XA4Uc4^i*kMvP>7#dZMTVK_4Fvtnc_`^fRlJQsU~H7&<)%SJ{T#Zw-Utt1av z+r7Hz7jYN!lay1Qv~`H>CHCC#9!Bc_oq5m~cDD)l#lk@yu!*QA^E}HHq}o5HzIWE( zB_M4dO*U9X9Z9(UjCi)%)UH1=WyDt3Ev?VR#K}rUq*mA;IuTC@4d|sy4E$8qNo6<{ zQHDM<)2Xc8KHCsT)d3=i4N1YRX|6QYq`G%hX^%BmGiSpA{LNT>_{yx1*DI}?iEJ40 zEzlhS+*4P`d3@aXcX5@~k|I2u%UdXFP{m?t)+ zPxpBi_W67=H~!A~tad*Xiy7#MWA%1EcW^f$l+6PPG~tvou~Ff0RuV(ZdE+4p%mEHZg3m5+EOdRv5zW*VY3gmb(Gc^QBBJ)n29p9xcby z{L0ccV1_q0tI-nPV|8uz5S2gGhjP6G#Jwp>Oxd-&>ZVJrU3VkrN`=z#hyW8i0u-N8 zu@eSS&cowR>dmt1ZS`i2hL3>vS}Cb^uuG!VHdM#Msv}ED8Mpf1RL%;(lyc1@hO-_+ zMk9IgW1FBzeQkGw`9R4Mtm#bb{2s$5g;RW z!cGNR=?Dz8BT$})cxY_0KDi1!bA5C5y#LhTG#uVH@a~sBX=~~T2=N8ZRWi<^T!nx& z=MKixb|OG+r}aYoKv|uG(zbYbABq=WzdkoM=et#7R9iec`f9UVdPs?dK@4G&jnOH^vy0|>(A8hHIT}#s?%LB) z?pbMVf5r2MBQSV9IuCFs=^-4MifK8k!uH-0ho#3NDJ`n#i6V%yyLRv8mj6afP6^O; zKfUnj!<6dwohMs6!A;Kei%iHmXn4PhhhXPJPYHDNu>DC>d-HPelIN>R%1BK`&V$3O zH?6YgB9!9#=1ba&MtyF2dSSI40y|C+Q zf^Yqfrq4yZx_W$;M#sf z3mKMSrTPg7_N3jqbxTIym9Lim;{R-Prp)p|af45Ah3XuT60Q=3jx`6Fi8ttxYZV_( zK{0(4@qU>iwG`a@Y4^{M+$|}BN9*?3=b^}qPv4}3y0pz-=r*Zjm|2IvpLv>uUcsb7 zoVFm38BbDW8k$g`r->k@l0;6`BW<||Yr-}Uka=*N*oN1pFNmd?nU`9a5o`-m_AWsA z_bRG#2Sp7D>BB_uO%7g})MmUhlShhdqt4m;oadJ=Q5fhGE30hS!m}{E)gWB-&$-FgzodN{Iep8`#CyOa&BDfb|Djys(JTM#twaC$FyYSV{Y)W0 zidw#VVL2VsTS2d>RVZ?(SUZY&yt_+F7Zp|z`aac0))8{u`WQs#6fN4z6!+-^F$(go z^yV*O422|Hy?EEkPoAJNZ|SO!{emw&%dPG*QvxiEybJx+Rj>$Bm30Z~*}B8RV+GDB zO)ba(-1f5p4{ej6zNH_w@U;dhy9R2tdMR@3T&W(-apyU1U<>SPBkxXJ+|7|(*@Q87 zx0$=7YVVz#57Nwi$iRbT>T@S=2E(a>OO20Gx5u~4;`$Vm^D*AA=v0vz_e+L6w`FlI z;sMzd|G5M@a+U_Mg@r%w-Q*t)PJETrE51lJ+2Vf2`P@Qq4TyYUDgkT&oGG!2AXA06 zRoLKJoXLt~FzFkw&mo_BMuIg15iG88VFW=OE@p$FIGXbPj|flf;gq8`PjBIdwmCC-gac zAn}D;W~neE#=(?iuknJ`erQB- zu&eCyk@)&**(NjoH`=~Np`hbOG76sS@PRba?Vv*|9U27nvF%27Cb@jExutKkQ4v`i zksPt>Slu&#>)WxbeSsQ!>-O(Nikkl5mcgF+2w(6>(*av zdM7ih`iL}Kn9T%J$&z*9SGtuEn5B1)@5}jdRPrM(j0v_c)e9` z5}L@edXf?fNzwa9R22NxTBQVF+T3+Ke;qFX2cHepMD5R^^FMMPh?5+VveGX<&uDLX z?52u5Yw+RG_EV;-@->k9unqC6$Bmw~l!?KeQhKwG5i~l>q4Cod4lI`)sh9F9MZ4C1 z@c?tS&UOvVpal*7*$WGKv<@aHT&yvYm1Bt>>afL**=Ns`8B&t3v;YzkGw}ts*7?$K z=)5G$Og-i1Ex9?AbCC=q1k9gQgDuCvVPVwWV>k~!iP zQ~TQ=+-H*QK_r7&_$^NG{P9d_2Jag}4v8}-?EK8&xPHt|DU?67gdL8KMG5UG!9^R0 zP$SpuculiiK|=T0Yp$ZDXJjX(q8i*{$0s@44C{T=pchdUyMCmE z%r|!VD`j)O1%a&oRg?F$Nf%Au9Onw>A|}jCUju(oDR;f`t2S%y`8u41jLddNka;|vD<*&vR6+d_PWZKtZiQ5Emz;(X{_UPKGUQ~1@Wd^BB9*IsW4{L zdf+nLL-*0tH%93gMJ-Yk?ZLWz+ZUQTVC-e2*))ninzy%VXcXl>If4#@uEg8uhrN77 zjx-3T|JKLs*78#>FdFo6VB||k6dZO9Gm0KOmC7Cb&eW~nYv`}I_2&jN+-mwlLDJA6 z^zpn|PIbUj-ona|+57qEKWGEo0*#%INHwxQUOUA+CPp{v*Sl|XhmNE3_YHGb@_)g% zzV2t0>y~KLW~Zm-GVZwCavJu%o5FQO8a$6@HropQji{+AWa zZLT)|!96R(nmqAnGA^bV>n&U;XfBb_#%A9;4k7xP`F^FTiwkcEZT`Zk7jcPUr>C(= z4i%{d<9(=ypq7=^6&;=s%o@sQ?SZ;;;cSt5y59vP{Q?OVl|0)P6Qk!OEI6vp4!Qn0 zR)CQ)urma^iFxRDKQsyvkWQ|hf1M=Xww}BY{g`L|qg5N2g#N_GIkcZjD-3Y>czj0D z+@%DWMmO$sAMJ+7_<3ZJMN=`{>F=+hbP7cREf6k|bwwUo)AgVz7~-zeTvsf@1U%%Y zllbBbeUSon^|tw%*iZ<*?LMRuA}y_f)383ZnfRz-Gu0^|Vo4T1Ejtz6a_G|hnUJY} z-GTk2QG7`m*JkjjQ*-ZVY&5dP`3o%<-QXF40HZe1IyG1_=cM9HV8JNn>WBOaY*W@HpH>{bBClgx`%hZ| z*e-YIkSObo5$@Rh@&HE|xgCV78DYmg;f0=!mZj>IFM66aF|H76NBZ3mz(6tV{MlCF zlivc?V$lQcT*yGnQ@L7D;;JAP(>QxZMpnBrmM(;#9I4mdD;LZoW&y1tqdgX{qau-qz9YL0bFug|*dbw@CY7;FjodceyoPEq3OZ1QZi= z5w~)#G6R zX0Cxz@oc1mP4APVYIPMXRJ7@t9mB@&NQS0`d3|E`OY9;X$;5>|e7k-M((uZlN*CK_ zmZokyHkh5leI)kd#MoHyn?kc#=xXa>n52fpNF}iZm=ov@4}AN1)u~cts7tWD_j}2_ z)o70_CBp{QWfJeIo^-9d`Leko6 z%Vm}lO;y*V<_h#RJAw$@5wm*%71$1g3x?d8 zqJT$y%X`GEyk7Cumj$?yp+h0t=o92*Y{VA2D7xtdqucrHVBqlN83WqO7qCR%-=YI7 zxY?bK>D~Wv0UVx)5Y}QUTxd~@n{Xbd{#+}7F`Q|(Fm}PWg&_tXp))P_O`9F;MmN9G zbHXZSs2kk)rVrOR?ECua_2KRQvA!p{;jK7bCM#n-u0+it@I)3qYj!~Ho+DcAvc;d- zksWFa`;#o`4{|`m<*x3bl483ycw-TBQ5Lc2rX0U7&fpxmtoYOtUTQ7=EAMneIdkyt zvVAZFL!Hfz*~s2YW^0WcE?sWv)JNr=gDC`>s#rKA58-Ldc{|)*n9MUt+MT@FgcXh3 zjmNBrF^HVZdEuRnuj)jnUd=vDGc|b2nEewq^kwO=>w8Jj#{5mVPxJon3E1*8a+z{` zdg10^s*Q8Z7Pb;E2J*%HEmE#v4g`34-H}fOTW5 zXXqpMS))M;IVqDBxf2zJyV#9k$^F3G_$v?2-rZx&r<9n@I)1#@gU6o+@3jBLec~z^ zd+4UUSw%FJVmmQehKV-rdz)2FvR*{7=vItyh~ZVS$4mWty!p6@9=l7u;$v@xCc9qnoO=`J z>g;ENaZcQOPsdf19 z_@_UjziudqTMf2goR&@5DB5vEhuhE8TPCHkR!gBsX9qs50t05=X%r22idPHNWwWMa zH@hKa=^+Ib&XIuQc%gy-6M2{pTdu=*GgIl<`Qrt~7;F&e))EHzMB_fizyJ%MPR@P9 zjKZvHR%e7?BXD7~F?qCEcSovPBU7yCua*Zy2)FG_3$ijfu7R0&oJ-$&wa-V@opQaY ztd5y@E@K7GnfTzS62S|4#e50Rn`a%yZ+7mjty~*LqSB@9@ zDmqCrQ4b@m_FfzDM9n3|R7vno7T!Xa3pNs4Gio0zUN)&-{HXq_pP`--(qQXq-FJX2zHpk`_Ts`vrFguvHFb9GVW!E) zAQ#5Vcw1_0Y~GevbkI9euw`vc-s8>)^t&$+VsL5bMTk7 zldKM_QAK?FTNMq8KE0{ts+GQ=xYMx%rV2g8ee&#T_VchpR)PuLmrV+m*9plj6vc){ z1>5rvxCm_IuUF2WaTVs|7{O+6MkpbyA~p<(H0TE-M-lSNg)7pDYX()1J!Jbjk1kb;>8+IxbKD*_gQ)@C}!%n=F{M;$`|Hx zh(g|Bv>-|n#V1(&N-?x{3AX+j6A)D8k;Xr;iXZYaC!4Doqa5SA^Qs%Bxc3hHXI%5WrRXvmcDu~ z`f*B1Vp1COI2M;CLr#*;Gx*XW&n#ZPNK%j4K)xaPmOfZn7wFj4C{IaOTucELY}tMj zBhW!g{c>{B<(^TDCa85C8=botQC?dgeW;wXJH{^m^JS-+`l@Z6`YfT=!s;qLYRFUXN@MRTPN zG2xZdWyPQ$1j~&eP__m;a6@k4E`%C|MpcclG0#k1Zp4JPX_+XbW@(WyFL8IYkE)dF zPa>GgBTEOq9a<+PKp%Q++cVyr=28B;MS=n>5`|VIgZrn7BRDrV$O1fS|IwJ5iyaO_{y5ySy5>8_{NT* zx=+WNM1!}EoLpBM->AV;82J^~#nV7Q)kq7SGUV}vX1th8Yp8Z*)wSRT*QV7%Mled9 zaksBFy&HR7v@K7m8@GnL;5&<|rmzdDAlb-Fw_){D%Z8oDZ98&c@q;zAj+P}n6#qRW zb)2nmaleYw4SV0%Z{vz2Fpm9t)0y^;h~Ng&bZu;WtU_Ehpm_MmaBVoZTA|pZ$xTaL ztaV+v;36DkJvM#+KQ7f{ikiKQ?w-g;IpNIesGH5iXIt#{nq7&??gvnwn1U<1nL=re zP&4XL`NBSjuQ$wYht|1D*EPo=!F_i`{*6sj^KxLLa*@EdFlb!=WG@P|(YJ4ar- zZiK6ni!R^y?~}!ay=OrZjua%r2JZ>KH9uIiA&9I<*vq*~aBupPHSumGB@`M}Ra8&2 zG0$#u@*Jn=AhB~dej|d4tn%>_f|;N9nR4GOMD%Jso>gm@P%9O^JI>O7Bt5h`WFeAV z*_gKhot07fmpMs4Xc2atwGf9^8RcTFzgZ0(z-lm=L?Dt#<=m|Q^dFIg_U1sBN#%;d zQ`CZ8sVl|C5`n)UzsG7o1_7(_46qs&|7JDb)lNI!JN~~}4G#6}!I9K|vl@E^3)A@j z&T5dQtz00Jc=vCa1Rd9w`?pNO5742;^b?mrUY0 z*;=9KjMI?mY9ScQPozgJW1@5QWGAKIwcy+xfLc5CYM#&e@}i%DncnLSItmkvpavDq z;4a>DUtKqA3mjUh7QG{rxmjEuB|POhJtG)Sk2K=9@v_OA9U|v$Zt-Wt*LiW{id6Tr z;KNSwZHwB*3?~@kIIc8IYb=JTPr^K=l}BHbbSGo{Md#&1_VxmjE?`{8EvX}tt_pca}`ksyF4>^-lCyiOw{$HfOj^m}r?8~J!s z?O@1@XV&VVS`eB7ybkd;eIktwWf{a`g#L&$#0(Qg%sN;0Um-RY&G-!l92m;+H(>fX32Td!olSj{LT=+c?H|H0#S{6 z>;0K6d9s`rEObe8I2=>?qVArn0<6$yebEzN0A1|>X{zKhjPR3aClVKQj3q2&EZV6Z z1OY@KQ)0qj@@|Ir1Hry~4Lfeg-L?+P2^9lfDdbWQq225~?!u0l^jkzIgd9;EeLMGf zFFaHpq-LPJFS>p>n+5VIm;>}aXZ3R{7f_|cf5a=N8TY-?O;v~YV&t!TMB4MC|COdM zz|=3sq?dpnh{#LlcHYK7k^vlYH4_HkiwEi3iw7BgvgWH`u3()pjdlDiKYR>rP{JFX zis-wKc5RnTL~$WUqifKls?ZmK4g1h7TZ`Z9{-|zRU(r$X%T})!&y1BTRjqH>OVyYM zl2r)o#w79b!gn_mHL_*0)Ws?SF1Pvu=?fC|}Xh6*&fF!T9zU2pnS{cJ?xJAQwtd$qJR@Ibg8dc_5ts0VPN8ZK6uG}CS>&TOBbdEgt(u4G5X5lxB#x2nH4!|VO< zFL=}8&0J*Z6mmUSW6PB;m|PQd^)}U}itHP?{eAiz4O~gKO7Ad4DUDQukr|tPUwx~? zJu>usUPYQta!;7E4K#|Yh*|!t@ep~NvY}R_>72wzyyBK_51Q#YF(|>Xc2^+1XkX)u zuT)L$Tg=y#4*i2QyzTE}f->MPJqHU9v_jcY{Ys_4(mwW_P#K&jRze-dN+RfyQwe)C z#)c}VAo_ud)eCYWb63l6LNwCClvby{vrK8qKJB|dP1IT{NcThvyY3dd*9Vv@A%~^U z33tUJ4NX^bg@X|e1e;nL=-!Dmq6kK=K~f|zKE}H$j*+A37LkQG!3Y$_ejCq+pIc{3b#z`l^ zju2#8MzgLcAXZZ(EUDgJk`X^4lS2;Bj=5x#6M6%4TdVJ~r6D12}5k{?TG<&)#}_PFB&~V)b>6Jf{dG$!)0werIWAZIA7^r%P!zA5ftEW>wnnnuP+P z6Kize`;_;=2MZ;Vk;hpV%=VeYYx!}c&Qxe~Ii7X~8D<3SRZR9@CtxvBK?w$X!a-_o@(M4fv1%nOD8~FI|zDkL7LW z9$X?0d1s$v*?FZqUq!ya7?&htM8pdNfCVZqvQ~vKy?6hd6W`B%|TFSQ| zsm`~!MZekNkU($(gpvTbVj)5L=qkOYwPb#-X12BO*v?8T2rX+1sMx!?H@>0jr0^$y zot`+gUGDYSLKrC|1Sjn^QYVEp5sH9%3&jrsg^)0-UN^vHWb~{{+m^-4<`4P7i8{E? z&38*sqhH-<1E<3!mkP5bhv(LQqd*<;Kfk=>$43ptU|$Co20cD|EugiTW=wOZUb5K> zQRoW8Yf-{;UTnUV*c84?uzh}|1!H5{dMC_`>Ro)C^&K0t1oy`qArn8(f}~8-1J~^- z1?L)OBPSm#-!+YK91PM4P6VROF1~oA+r|;&R_s!gmso@J4LPwsMkD~d>L6~1BD} z-pf=w$BfOnn7GI0y9HHMtWJ-$zKJ+XGH(11$=g~1BiZ1yC3rhT!HiIc)pjj{7QuY& zI#uBiGL#yx6k3n;9UYKuI>D>?%f~YR+kz(s^_nHVa~lr}`&n?BoHBJCi zT=~eT$=8>9nMdF3o|cdLsXO-ks&p% zJXgapL}|PIcp#iATfg4$UCzB-`PkIH)0R(|^E6%}?L)Hb1Lhz>t=@lW8mv(M2vUD0dY_M>gSARAaj;rd+TrrDq zMN#8uZ!Q?T-H!@)(+P+za`VgrYanp@%hYhpUMY~eDw;Cd`BfO~!izPQ_S=+cBh5A6PmQOT&6TjK$`ep5%nt#80LZ(%IiDmzn`xb?stv38c5y6w~l z?IYlNrP4BI5MROGfOV`Z^j%uBF(fA?df((SjW28`o;G$(Q|GOycLA$Gpab@59cVtv zP+9P)ch+s?wsO{O${6JK_k9`n*1y5$X;Do=+=&Uel}0Fh+`xruAEQFiMQH~{O&QSDl4 zR==WStdV~UC4>p?F4p=Rg)1p1#QjGg{?&8A#I3(_XprcCu|nVETn-d4`geF=0`1Qh zL^rI|pFZfmd(F3bp8_hX0*gL~n-TW^?l-RgdZ>T}E?8$cV%pg-F)r|Y?xj2$q_O$8 zsxI;3lNfrv9rR#oMvs~HCNI=E9v&58xiObz`g_<{SF&=KD;Tbk-nbj{Z9tgPff5Wx zOu%<@k-0h8Mclh-OH$}R*Eg1*g_+YKnJYP+e-KXTnxkN{%*gJez`$tHMg*ogb-R?y zCukp(WT5Kxq}Y8j{OZGMHht*lgug%dTGExIqeo|Tw45QZ zYk<7FU|XXe6CX7p>GmXU+UnuMz;ckz7~!>l*a&|r_c^y_$Lzyrumb?;B~3||B)F6# zVM{Q3Rw;h;dRX*&{JnsT&8u)W=5}}Rb@V@LH?Nffe&Of6MuORc{}+D2p^qHp0tkju zG9Vb}FT0uw{C1?UIHKFU8wSzKl{ZBJzf>W&K2C&~TIp}OOXO9Yo4pA`XOSxu*m=F6 z`}In)9sQHxPB^l(C5*&qqH(Yp{IHjo4`~a3gw&|ER=Krw)_sAuNFih#<%s*#l@%QBYEgh(bt2 zRLU9_S;CUYW{@QjSptXz5|RKx0t83`B+NJVzJJes&-2WjIcH|hocYIdIHffW;kv%p z=kt2M-dKUrA_iV&v6y5~z<0qHUyX0A_VUF=NdhwXkekUE1>RiBlbq@=Yy?O&h z^NV6vs!fL#VFc2E7zejd-}q>A_Kl+>;Py_!DQ1$Al7rez5fIn4yG4S+Ts5ugW@l;_ zB^r7HUR!}UpS;t$JQP1Wve(FivF+$~(N26>m+u`=fc+n;h~>V8R%!@?YZLW#@FS%0 zpVGGZjy;oWXYk()D|^5aI-9Bhf4)Q|ETo6PL1|P1>l;AZe=I>&*rF7tJ-AoH4KcHq9_*!rw(osExL&GgPvva8-~%O@B7tYR00<>x$v zQv5V%)NXs~7)G>cI3Xy>Q=n^C$Kxy%0r^-*>c3T4R98RG096*!{-UY1E>LArGc8qB zSs4CZWr6!tW#QwIzfd#o2dXTv{q2@QzkgO)R4!NJVhgXrAAYK`FmAl4tOivUnV`y| z1XNiVtEwzctEw#QezU;+v&y1#KqMRiQkhdom*weS!C0uR2jqwDex4tRDCM6YIf;aj zqm<&CTSRPuTE5kU3QM60jOt7v2apsJ_Ebgvm z`CZWg2O^#76evUSMSaSC6sWa$*fVln<`Mc`8r|?3LG|I7TRXEx=vme*$`**D8FtF< z+jO3)_}q^(cgtqYBCHpK%`Zv)B`MVu+n2RHT}R6-;YOqnc%d$`PGy*bnUEE(m?Mn~ ze;+l8MvY_6ojHmF3JPrPO?njNrHTIP2joF#Z##?Oz^%orYsJpj?&!_SsT*!`D#k9F zf(0^}^jw=0*5_mbBp@OBRZJmR?q(j0N)ZhxRT3BNIJa#ax zt=+32uWljY563I?ma2;C@IIoWMzj7LSa1X@gBL-P8vUn|aHr3h3I_e^$yzuukkXvEBB&kRfo;5qfV5?RP}M{0 z3&Osuh%94#fN$#Sziw)ihEqEI97g9mwcqs`#%jT- z0W_Yz1rw5sska1o@8mN#;sEE3p?QxUJ%d&=+sVxvkU!?Zf3S})X8d?4P>#V*f0az$ zFURx>FO<1vgCo>A5B&I~8WzejEzNyY_Lwr#9-8nvPP^lrk*NG`w;Mu_T-Q2Ya|PJi zCtrdkx1`p)k459TB?xMrQ+e}XF}+aBj-M6a>iPERtO9+HA?tB zZ0?mB8nO8HC{l-vjTGfXjml{%sX^|m$)9^SzS#&~O}HWY%DBZU1DY$@fOO{{gq6xw zQ^fDYsL^a9Ry9FbfO6SrW;ZanI`_?w@SrsH5m@FH=s^P> z;(Mu&2cd59*M6gto27xdEZS2R{(SvST)Y=X537rnjpRp9w)@!v4SnYq`A4>1wU>qN zQ~q+5`<#)FP*_Tp-=XkN`+gm+nsc&{?zLRmx$PDeP>gdF81w z!@ZDv+9Y8wRvb&twgl=qbV1MPHwnb5rCqlEFVi;UUqj&++9u2`Sj9D2e z_GZh+Jg}Cbf7?AAKiNG*Z!v1{Vn$99{ZbWnT(f5Z7awYf6oNUVWLaCWIs1+@F-H%% zi-BUCQ}j+qVnPz^vexedOme8Fjp3JV_fPTuB^~Fr-=J4drWz*za9V}i4UtV6=fxFN6#pOrbFxV7e4 z75W{jrV1_-jYq0=7xzq?@Z4}h&GfkCIw<=cF{NH`{_M-K_B!m+F(Oepxc+2l}E3s|Zdm2b3Z2u*dh?I={z}b2uFI$jh>c681&9H4Bj~iFKqn3ZC#K;%}+MxJoLa!=d8v6szPSFI93YvP;6h@ zC8D5YJa+$?v^XrF9BfBX7MV-#xPfemzauNIV-SjCCkcla(?v-)S@_c9XqeRf@GhV< zX6b{O^XTx3i3=?F5mx`Sa>_R0+ceFO4YHHPQ}@82O1outmpGPP9~=WjYKhA!rlqn< zRc(@ZNNy%sJMpcSrMxcMI{XZdUiN`Cc#}SZMVNeIW!K;>3Vf-V*vM~Pkwm_p;2;aW zL#Y&@OXv3qZKVo7up~#dL(w#eHQCWUdMoI;z~y|v)cki|fs-e+>1h$ZrYbjie)uV~ z5%joI?&|yh#X;OI08YP6_{eRv<25@$GaNH@r=uIu?; z6{_$C4VGQ{7XYQL<3G1?>p^?}MeAf^4@w660j}9kq2dq(TNYb$jo1$;V2>}*I*4Ig zPv&NXc#ZEx4jT~*^NH!fvwMBQJ&6IYTGAFK9UIO$loC#)lH)!nXi0R9Ms6>;#hitj zG=d9PIIUj|HuD3@Hteb`L*ab3%^h#MsP?ed{h(mrn9l>0#aJ9X_v0b)eOAxw3SGgw z4Jc-nRFvm2^|qxzm3VYnBP>#0I|?{&&xU<~5m>fpo#l0;w|75qazV>J-rY(`w!L2U-+pdChdp{TENe#R1)DRC{Rf_{+mi-pT-{d z#T^vc%topqmI{ys)>6;c4)FkAr1-@NCx|>HuNg~&JTU6sKKS~qB$KhQ9s^lF4$*se zRua-0n}A5mbh7D2fu~b6?^I5$cS;;lZ3EEDb^LJ~_FUar0H0(Vi zRVR#?`>afu20)jx4P1aAdS$$>oqd{=^qvUUSXY_`_0Km!vT=*g6YMqID&Pneb3mKE z)OFs1d6N)qjW%b8uAOY`($m<=pRhtZB*j!0T^xa+F(V#9h^IHRCo4vdB`&0s@sE|z z<&=hknq+!-4D~Sg!ecVGWEA;8~K0=l1!K!rpg1ziBuS(Oy)Y z2K&S=Bn))ou7)>Qv*KTd8s@7H;1=$jcK;VD5iFf{TX3p(+g-cQ#_93WV(6swz{F%a z6_9GB$LX%=G1bhE^7jkRHcQXU&|mhT_YYWLjalrTk65Q7Hx2l&1Zc)1ztc3owxL_e zdqxUF4!|{$KDT{vp19?_4yW=jIKB32TkwL3{Ng$8^xIGxUNETRFTB|xfzz?{!l|qx zJib(Z|2;_E-S}$d&$k9ege!aH_bfK+Sn%S_$?)Iqz{c!MdZav>Sa zFvP-OF=z)Z^7**#3#0=z4J#n7B38|^@^8J-dxm{Eu_K+LX0-W0mmb2dJf_l@_4oK{ zBlFKsv&+bs^}!hpp}MeZ2*3U-x{q_UHil5NFq)VV1*Xbg3gS;1_}M#+-x9j@TPrta zs>(0AExY6J{QMJwf0bY4x7D6=_34Z+lE@@j6oAf+!%iejXG+UXen?C1tt$j%MS{3D zo>E>y7D;1s+&a%|m)_G|io*zlDwT$bFA=rSr6%vV!0*^1oinW1{nECuAVF~|6*!SO z;yD0DRSc+Tl{Hl|f%bxRkgz@vNTzJBC8%)zB{g=J;?G|Lyow@zr8j@s;=Bg=TP-mG zqk8^NY6*75g>s#=6`dC;PXAI%{O`Z@pK6J;KFa=oswGY-r{8PGZ%kcp9lTx}hW9I8 zwBbgdg~%_$IX2@;msfyRq6U-1y8zQ>L8w|+sGcgY2`o^8g}j&FWu$p+fVHt>_wV3S zXFDatr}1I9@q>?iaCf7tO&6N6%NES*c+V9oH{mrO7X)2rqcg;hS38wKqm%(V;MqXQ ziQkew%DeKT%!D@un4=RThnYM_1nkOdAP2~Wv%jX3?$J}kNSjBKxhTv-B3>AX_;IW= z;8$z{^M0o9`JM4wQWqu`4pZRUUnICUArTx#Vq!>4jGPHxfd>Khd&{7 z54ZZ(?AlKfa}uP955$4+%)wB zD=MB*@K9@^2m@vk2T9+pS85pH=Pa6$JFr_~_XR&?B>qf%mxzX>5W-yzHcd(1@{Yh? zRJ`+BPW)z~mX#^-t5gHng0f25CcT{GR*K|gCLK!p|FNxIf5o*KR1xw2>;rYs)R5XZ4U+@SWdAJ6^=N{XSmEA{wA_vWKrum0w ziypFBQ1M2LHcv*f*s5OF^=5AxD!BEqJq`oCgMgEcSYT< z!XL1*bH!|(zRSaok_>UKid(Xx_iM*ajC>KD;>q=f^Tqusb~dXtE!hRw|4n3J>2ng}tVEo~|FE0kXz|Kd=~g_&01pc2g<)=< zD@jfTq>Ud>dpubTvUt)~z1X#wX4%cx+3D_0RKE%5eBEqFC_%c_q5l!Zl=AzJJoGUVic~BG7rV|6!EBCEGW6t zo&zjo!w}{d+fffGT>M2%qyDc@$p&{UKC6e3^m#nd+nEx_;btc_+WRkTOdeK6vg?fh zl;jOFJG1;Z;a;3@BD++rFZOiao9ihs!`J9AeQ;&_M-Q!vBi!*68*bjvun+g$SCP!0 z+=;q+TVk$I90Xk-QoE#XPVs=0=%P9*58;>T(}5r!0UQuFNQ`AiqsA*9^bY>cxQ{UJ zUGK9)IysTrf8~=V&}w(xr8NZ~@%_X~GFrj_-psw#&rXh}Gt7|CfGVvVhinz-Tx(v3w z^o1VG$J3t??Hyo*daa!c6^2Du!S=xV>OEW4A-JsV=g&~dc$^%cP+B~n>eHk)=y2GQVK5qmOOR%OukTIyo z>+j_+s0r5_B{^dJQM_{Sz31XnJw+}e%NI=lMz5{izAQPLZDV=>^9TTI$usw^7=nv@ z?Be9OY*P*IkLIUfl5i6A zIcUBP0{O8t)K*smSGMGxuQ}c3m6vI8c*6NdNw>@Q#P(n`B+mDo4HHsrzRJ(vYX-k) zmx&&KK9%hASN@2qX(glX~i0+xmKwlJOBxrvYPL7NH%&u;I@gLfvwfhOE2WdZ4MD zvyBuGO?Je@ex4~ew$49LdXG?2TMwVwE2*V~ej7|QN?VU~Y2!^v_SnRq`oY%KVDh(K zNs6TuhH3lJi0FR6A8G`Fb~mN>Vv>E@m&~GNX-g`^V@M;ZyYUj9)Y5VZ5f=UFbv)K) z?ce$GZRi$g+mD_&gS2hI0oRhn(VyO16bh`$VwvCHI&Q+!F^Oc(WwOAwI^z0pZOj_l z=Q7=pL66*EJ|E?CmZM|Sg?z-0T$p$hh*-E!SZkCan=KMPf^ooZRW~1f=T7sVT-9+$}tFI$s<#OO8*LXr+?KsFt3>?_T0Z(Gjtt4dH~BLcP~|A!0$Vc-6EJCic6b} zYUx|zfdpY#>3v{1SsJ;mtu2DIEr<{Di%9!ufmAV`z;mp8_nk&$-*P~jAW~`^eAh8b zr+58VDeDkt9&HI&RaFHC&(i$n#fR43r@E(35xeaDc6S=0vnB-7X{COpvpYsb&Z2K_ zb;r^?4`hI4HAS_ouJRsr)J*4j;@*!Ctp)mkN_AoE6$F;35Z81$$;75`3bPhu*61{{ zFaMF$&1>I&@5d;7>u*v25bcb;0xZD7aXa$h5!aU<6gENVCJHN=@k?N$x*M_mM!Q1Y z6wYw!@{Ytp4I#=aLz-}6E-g2tSO}V}0dLy979^l0;Mr5lJ5V{;#c|Mc6*v#{f#9qc zM)!K2%d%q&iJ}*EW-SQeNJK{I!1<-5^A_Owt^Y|d^Rk0hw&mjOZg~L|R?O2W8aQU* zB5Y4~ynLycHNLG#woA>qIul1+EiNy-c}ZJMTQqD8cwpR)qJd{Sq0uhF8UQJv<{_yh z27pvZCLxno%Z2M&twzZ;@ zhVQ;jQtR9sK-9%aI}vH~Na_ed%CDqDEyRF_R{3eaVO^6Au!}SuI5`b2?cVOMHSd1q3yC z_%_McWZq&SUNarqbu(nX=jTjnt*oMW8*w2&5@f}6)<2XrPhZA;zxa}h$UE3<&o%yF zjxOHm?|r@a;G^$OJLno7I#QGMlx%H{PV-5#ZEVi)9YaG8tX92aitg_TY<7;A)TBvI zZ*iXo0|mb`*7@p+^B~PiOrboI8Y6I0D=al>XJ3BJFOF4>2{-3=MiZ!%hS!j@<5N2E zS0C)&^_UFJFt@%qWE}dKlWj*&4&+bfWk{ookYcRt;U&{q>*{&;RTO;X(ky(RKw)?3 znVyg^W?(!EK}54d!StAYF{rhv_?i`VtnL!(^9D0}Z80?Ag$w^Jj_B=#oGW7v4UpZ` z6d7=knbqS&z7JyXPDzf=bF`C<;%3TqJW(W(6%*&U+y{kT@w5m$Z+N$J8znpq2Nu_3 zUN|#p9t>ZMn?P-i&WKDsominmz^8IjQW@Wz8F+za)ar%}^;~~3H&<4g>oRK}11v0e zL3|`g7>AOL_U^#CT^Nh&3Z(ukJL}X1okb7si}aV@#c`@NTM4@bNXTjVY8XuZx$B=6 zJZL3WBp!WdyX+gfBNK*jy_hc+fP&c(fIIpucC+y_lUyifdH?HO%V*%rAusp9=H~j* zMS6@^dWJ^(+o}zW-5L+8z9F&1+7Cl=WJ&k<#Nxnz#B@tU5r$$21&r%b(*@Av)mlOK zWJI+0W(uF7M&-s4`3L%@rko!+kpcZKng@mF+Y|Lsk41E2hxxGmvD28FcA!^}>yGo} z#3#+vEmrQ{8T#!1RobE7Xp<*?o|R{Cd$#~Z;MqLoC+=k2jO@j5!0IKe;bq-rL$a^3 z0jwQ5=UK%eD@{ggO^Fbj?)C4=F#Z@9m8#)oYM@**QF4Md!x3b@Wa|AlRRb6@OIB9q z1Ic8Q>W(n2^D0||kl@q4_m=q~b}xQ*PSP*$dlkzJwB_*j8^N!#{@{k?#DE59gfj%Kb4v_xGlcy zU0bsKSuXWZEve*cTy%h!)xgq?%j0eUUCtr^;Td-9g8OhvQqxKuQ5ZJ;QpS8gkZ*Kl zU_QZZr`STG9b0NRsJGIT))#JuaIT|yPM_4irKCeCj6=;mbp}^tz}rPLy?7EoVO~?D!Qd*JNSh=|3^BPzjJAekG)W(UuBOeHH#)XzMBtT5uI_5AMs9zD zZZoP*G)`kcc8U<;AYrcvZA}<&vq+dn(uJhB1QR8Sg6Mm&ebnL$Ib`B{6Kt5P)TeG$ zJ()gd6Zah6GY7|Ep&#{<8ht2t>=^NUJw*M>QO)IFS6fy8MDDvj_}q8hHtHgH(!_bn zta-FA9oYnN-W-#GCN{CYmb6QYrCi(T_NS@ONpt&YfxaB*tfu|eA>z^GXl*s;0c-1I z3v#Z@>-%|Wq#qb2Q9pRwM}i$DHvU+uAa)q0{0yPH?pET2(syzQ`{W%+QPZyfe1^Bt zAfWxLqYoir0ubtk=+byP#)PG{1pE}07TBZtkcgYqFx?Vu*09Y~3pTS!y9=Wg?_-6< z8BCP-^%7wSs$zIVGq&%3f9`b;)(U0L)KKJ9>O{}iVgxRN<|ZRVm}^^mASr$U7x>gV z6J_8U+w==A;FX@a1h1I28<0CzoscZv4@_Yx+ciwENuC$y(RZ5kY%B6wpmSx$`f%Dn zhv9|FJ@_{J>8EM~a@YE-RPo3cy(xFz^LjN`GPD$EYLIu|j?6lj74Y{;`+!D1;rHFb z&lmatG`l|dP*$sZ^{??I_KmYf7r+ov9gPD{=dFMpq5@ZhIQFrax)(bV5N#kwfW!1A z4t2kgL4cP5YD=*Ym_ln;(~9t_@6AeQMCEizF`at$YW1Wb&jRD3qiUz&ZEkqJTOM~} zXVtTDnqZf^swe}Hbf9spxzxMUzRG_$leZ1vlR6(cAWV~BXpzTWv9Mo2rtB7AJD-5n z<;tpAi5w@apM46fVw`uNZ3{BQrlhnkDZQ;f~R7*EG7LxB*y9Ax#?XeOP? z{X%iLBDgfQK`)^MtT3|U7aH5+UO>dA8dZrPy8`Y zV%z2#+Z3x;zuAXLi=dbq|LTCJYUb>((**k{*}Q*TZNUpKf%^?*O;-GFpjYtrFUO^u zhrmPnL@Yj_tI9vszChX!Hi)XvzRIM3j|D!cyFKEpeJ>0Z-W%e6Z+{j3(Ph32|@sXpdH6!H4r`C+S!(Bc( z&`+%yfSjHha{gCqMn=>XzF)%4H>%c*?%IKdHp;+I?<~LYQ)`B?sx@QZM@W&a(|@&Q zh#aj%=Nw}fvU$US6!@~V6|0Ie zD7KA;IHUf$F~@Z1NZ}spm8RcJgz;L3*r39lnW1fj6y^)ywCR-#aGiX1USPXD11jrV zq|W_Q+0gh;WdoQ%l?EZT?MDtE^%BAx zxnKLWeI@?u;H-7}b@s;RN0U-JIa>xEH`;vus>wqp^6>s!&j6l5M>jAxciW;sV4_hE zkn}5%@rE(Xecvy8AtUlwW!avAW)@a5kafpyAYz|UnyA9>|5Vo?etq>QOnp8h63pzs zF-Q@Q91yCnjLUAT` zladSaXJSUrE=o0R&|>&@oQ*dGZI*RS&iaF4~c zR7Bn4HSnwc^prW(C`(Y_gFpy5e&EepbkC3+UA7)#?tFx6p=exXw z-!g|5Uvo5u|&7 zlKb6XuEzs2wt*G@db;7OM3dl0iO}t%irFZm)R0mo%UH^_6E{fIROckLTApSaAnFi3 zaFZ=D_?j`_U0`fcGn28b&MD!}Q1JIa)ecD9jA}kMp&&+V)hfDz7)=Bx#=h#ANQu7L*?_N`5Pi=gpJbz|mK)JsgLgT8N*Zst zwMc~086!BoPhB`1XO)foQ6~x#KM^gc5iE*CpNoc5u758s|3JDb!3#nD&QXvhQm;q6 zUsK`ui20W>PCjV6F9Zk!v8{OiYy978hJj~^1AG{JS$0I`9~UogZM;RvL^L_!h0OUz zCWPcO#qfbAe!+@$*PqjV8rA=YXX(`N#H(}keypjMwkeT)c|M$oSZ+x+6)9>XnU_n) zWf2!=bb@4gfj~u)_>z4;XKqQ81tBl}n7OneAsD41;@BZz)#<7o@8jg>pv??inhaaX zab!Tb-6f~?55eA^NUz!+1%nbkvh&TIWAh@k80&cYgaE9G7FF2>A6P_bwqWEZI&f!u zpoeMZ6kb?pg(`e%sVH=7JVG8#=jF@NGRSexT~$4K=7)F(L$+?qIRqY=nL7e3v`gZK+D~}Df=rz2+{0h_z ztigSIx|%sN8R9lD#PAt7y886K^r9+T$Dr(zN~je?q;P$yg>`^#G*`LD9Fiox{jUW( z(GT3=`GUR^sfJ^}rNeM$5o4D}r?t15L0(?m1)Bo1EpJab>D$KbeRUiXY4IVbh03?Nj zLoHQpD?4IqtUuq~CAx#KtdT#xSNJSDuHz9=FJE8fURc=?@*rK5*TWT(Ugfnkv}xFQ zf08|%vS4>TB8Dt|1|$yK9UunaaOUJVuWO{Gxc2?5?men?&rW`?rpy!NU*8=!fqPkA ze3N?hRXXmYV#ObQc=2sv{V+j@kWx($peqp}K;=kUsmEfbVY5QwyUZJgc9D18OcTzO zrSLj`Y|xg1Cum`<7)I!1Eydy3P4+0DRR~qT=R8`z(6k*u>K$-C#BK77 zt58z}Y70lV*NqhcAytoK1GiG|?;nURf^DBEyKucOKz=Dpr!kUgN2pem(7I zJ%V?_5n<}7Pg4sYu?4|*{gBXpG`s)O$C=DEfX9h%V|~DlgNSUPPtVNZeB!IGEDL|G zOTc&2W+5gfA`u%OP?qUmEh8~9BL$`pDd@J?mZcj>D2uM1Cwp*1#pBc&G)N_zvXit4 zZgod!t1n}~YH(jL$;j!9O%JdBT-wo@!QwYr1sgJAX7@{)#EjpPJRjwqIxDDH6qe7l z1bV#@#=80e&6E2uDHDMUumnMB_#Ujk`{*3j+;T3|=!?0J-S7FY2b4nM zB*HCj;!%fvO`C~D(e(&2DMQk5p#RI)A}D9x(G5x{J&560yCb4w-`KL5(C%?G)pLu7 zti+mMd+<(=mBbSs-PhaDX3qkisI7CrS`^y%k4#}J(6reVtuVp-U`)@g zmfb%b^dw#W*_*&L1l8G~&0gJ>vVq{{($?e^hrb$oNYb+eenCdIaJKhu=WoL0!Ga%( zD!U`B6u-hYN1j^yCT{PeTTbx-9n-(wr8R%(=EX7P9YzyR^oj#bUmUUMV)rZ;@i3Xu zI)O#qohP#od)KjuE5)g`#p?2IOTV~og}drSy5=;fh-hL&R;N5hSfTXKbl44fyZn0(t2#^2#+ zc>2uplM|)l_*xX4Kn3xNo1ll!5w^g6YgN8i6fvR~a;!7(QUc{r0~K;mI7iI0o@&Q; z!v!?i#JFkXmo1`Ni;vXR#KrF|V&2@Tbxk;F#Qt^z9egB?+OVQ%-yLNCq1hmD2>>i$GrpDpN+G!1f*+AwBU%0_p7gBz=L@*aiBn1=D{f>9D-j&F} z^U3TEY%T2V{Ro8ZLRPv7dpbRS1G{2Bjfab8XEov5EMp*GU`3J`Wc)K!jVb zDI_o|i0^LT7#$zV^971*Rqe)=$PlrdI>QN9hNhXZSvTVplkn?Jt4V^^@(b-@!RKQb zbp+ab=TTn2Tqxg5Z_C$SnEb&3lnkfb(~^ZgyH3WvTWk>2@BDB;SlR6x(E>{|wjv#p zDscw=-ZKN=mHF7q?;L{qBHu=R-uS}_!v>xk0&h#3{qO#UVhWuL{g=OC!0kp!`1CoH zZ7k)2ueNvehX5nsZ-CE#3b9)|MKo0vi{JdfVROOG8e&};d~?J5iqHp{l)q;d!cfdM z!-qr)hkXhTAZ4-)l6uI^$s_#TQiI?zWw7s>F=TjfuQ_pqu}OQ&67KABO-3@I8_yjA zA3RS_KayV>E8bu_AOfBc8#t_Pp=(Yt9i}7%EK_8XL{DH5OIi#;{c`} z^35zEoeVj6+=5CIOyEQGfAk%c`}^O^qa*hvxc;y)2d!9xiTj3D#S>|)Vbj|Hf4I2> z83}+-R7B9EKVhP|F6_@t-1!C~nxrrRE(VnxZMZA^7879v%pPMaHQ+%R(Xds&8z9fe zK14oh9GpczJRIW(K_Qce54Srb^t_Q@*>tU+`aTwnu|6pI7K!o@)deDzO)Ws* zt{)hYYJSUz*Fq2QzypR=3>Hs2vVT>$3Jwz4R>q&K4*a$GcrefGetcirCfwaejZwZW zT8H&l{vY8Gt0?V?m_~RIs{naoHUr{p?Tq^4=pX%Cac#Uo#aF+604|?H%G-@s0ZzSq z?B(cBsGU;lsCz_5(uUIH4R*fIn|{iKLfhs+TwT~61>8n_81gCB>usKAr!$7oBzc4< z)RV&+p&|%h6PdD9$35^P8S+r!M~ZojN+|s}Rc7&SX57tsyi#4T3x$7qYtH`{&4ht& zobaL{^a>O0W*p&x($DH$-@%d0g&Q?O@v#?3P(uyVy9_J8Y-*rz>5rDeNJ@gBX5|P0 z1_LK~J3R}yn9k71v@~SJmLxoHy2fho131HnTNHho*5d7|E0mfb+$b`_biYdZaCH9r zTs-*MRZ)A65xZ z+p~F5ua8n6(LOtf=v?EZ$^vI=d1;*ZaZRjjXf9%dtnCZXYD@q1K~l1gxz8AI4G(@% zIcH<{hxB25i#c$$fOSlY<80@L@cY+c45k03z*P#&}WJFnpR+Te$W!I~We!r|_I@ku-bVsEf z1;AOl^0yK&&wJ<@E80POuE8l0h4B3L4-lN0+sPGxlL);Db<8V76%Qw_O!802CeP~v zmO@w#9n=lUR!Hmi)7ZP`d#-%6477hg8j5uxhjkPB4315LZ%&SYa9qM)oG| zMyz6&tldzxx}3P5Sw5=;1kdVHEI<5iW29mE-H+Wh{E&K$K1b9-(T3M0tMB_FX#vb3 z(=e&kn2$&2>QfW%_r<+crba>h!i3wsn!1L%#F^ap!Sx?o^O1@v)sJ2uz)>f$TlA&z zf8Ci)F|wHa(?fte;zf5nYrIpiffMw45%}(oZaHnv(h;|Xo3mJ(J{=rIX2a3qwVJ1E?|HT3 zX4PSPPA6KoMzpM5FKn;pC}#8Hx!cLIA=A=Y?rxPrmV$}scOvXcv(dhJ^_>5ldIhNj zTcoLO2AgS?=D07T?8=D9rHCp_VzxAgukcZLmNz8M#?!|d-peXeCM`1ir`K$f9Sg@P)M;?qRWGDmA7yZQHT$bs8Al;fGP2nHqK<-joS{9&gn z=aWcN8{IF*cEtc(dyA#`4bD)b{@(G*{CtS*kl{ewH8oBNPp~q{oN5bvWg<8X%_q5r zFq@33nD)3EqE$hoLs)@Lrna_SKD&VQz+SId(AN%abBD^_yBrjTH?sGd2cFv>J(zMD z1=gJ)MX9cx8vNP`XFG9%I@W45#hx$Z6aCh#Yh>uwFH?#F017zY&ra5@KaMR6i ztaq5)>UI&NJ+~p`=qP71O=2=r*JU%n5=uXmw*F0_!VRJ~eOAIrscI~X=v@PY1WFtj zBye`ECofx35*4DvK;a9h-tFSmg!_NA?8_{7GQUuCM5`W_Ne6ZRpSn+;)RFx$~ZE9!(Ex{*?r`v9LmUYBw8R{w%iWdv+ zN3`!XPrQ1q?J(hyS+dGEjfzX^c5__a1Ab-Z%R5k0n_57=77@_a3+ylobeW6&_H_Q& zVk$K72GSRJ9z4r~rYmoC*}KPtJ9&g=9CwGt7KN4o=dwL(>5kVF^|?n|!8dkMC7#+j zg(uR=Z|Raf-Lil`dNn8REWW1iMVb%~2OP9)?xHXalL(5O{xa1%ESs3ze0p@%`3iGx z#TXWw#K7MW#cP7~fv~DB7%)EW{-BuiABxv8BU0D? zKl*Q*ye+EA&584#jp>WaKaY!iD67p@EVNFK6k-|^l@IUynW943$ncLkCK%FZ{vujS1RLMmnc0?&&*}PQMY>=$){(@rQgQZRb_#` zKA&mA92#W|y^iDWemar3n_*4BO)-i_^3F|~@S@#E4ocIboYp-+zQSof`6H?g=^MKe zl^~2#4m*Od6~)yD)0*%UIDbi==`=QUsi9w1)w?w~- zj#a1ZWk&Fv=X)$WBr9t~*q)q%BPA(f4138I?`>?|^z>9v+xT{O*AJUm)Z0_nzl=Yh zdH@zg1D^w#Sx+bLvLr8Mx5Y^A5p9=~i>)L3p_EK{8d;Q=ZEc-jeGo@OYjmfew%DQT z(V*!3v5#xId$`MrcVm}FI)q3nk-=fm*c-^2J<-Cv0{vo*(_2J%Jb&5hFHWx{!9L)6 zh}WCd!|pDG-oP|@gU~O*(<=T{62wxRvGbAV*>I-GAqI227dzmmm~hW3i5|$d%SV8x z31Hv+kpv}@KCrSTLtYxnoRJe?hp>mkMYZ)rbQ>nex_H@Bo6lLeQ%*5`fNSI+9; zedcm!)C7vB8vHYmi@Dlxm-thEkq#0-jmk3<7CMT_`+jqob2C&NfzxuRE`1YQ*8FtJ zl6~#}3BLm@Y;tnC*67%$Hw5x}cR$)@nkEay8C+fr?_lkk zjAO}4kKP?^hmvXSUOIY&B-vj}`o@shprzj4CulDsVNVz+5d`=Ya=^M#`|`g0+*)b< z7g`Ok-qblP=^KW~{hL~<=M42gTs=&O7g~y!$#jsogHqDGDJCsfJ2?hO9{>tBce5qx zE`y)mlAI?`P;YDxzX<16#Qbo=V(iBkfbIVzAh~UoZ+JK~*1GYQWP&g^UVA*H+)g%Jr zCk?WvFSJ5SMb^*&S(9=fy#*VlZs{t#FLnh#5|~@-dgAiv#=&aQzTSH6Q`OJnzIRVJ zSzUh7$9VUR4-Y$E!yvnBEPYSvZGCqAn$cTWp_<2cxlgWr;ql?}lXtmwKYt-vwoqM`3#vEyPDIXKCv(P_m(fAx3J?=4sm(A}Cu)vuj^8kOPdl_A`4^?~ zhcy&e)>P|dp6J)W-ycF1%+`yQ%bRF3nzS)ZWj;$W!cz3kMOaRbO@Inwm|<@YRk$ya zFP>%BCDyN=%dw)_i{zE{SelKovMy1ilv^JPXW9zF5s3?ReKvU=m-p*C1$XpOz{SN? z>SW6H@kAHoai56rZ3hcS9z6EU0gW5v2&>>cJ)2g-q-yKf^VN6oAX>~jOk&JEfj*=Ok+4`0}GV%=JF>EP0bOI?3Lmjt#m zzOTyq~SUVoShLsBHcKBxn-NWQR)d&Qrj28)u+*c*V12{cnBFz-6(pJVf4En@fXb$;RqVR_9-Qn>4(B>z+W`pdU+lPD*_EH^k>y` zi+7#O2>a}F_GQYurnZ}hnYmTWYHBCj;%afguNwcQaazO{go~h}bydsO+^(g1{aiq(*5L zf)!b2{7`1&61Odtd;nsSUwq5qqPMKo*ZLLLZ={2~Y$@)%BpFb+vy2>WB;mdxn~0Vw zJ&}h^7Gjz%SJKuU?8aB0Y+`Q>;~@Fg?5~mCuRSYui-A{Ru^`_im4XShWyFs+1~YT* zN6IJmiEP8h?FM|ZBUZpMNV5R=V7D%o3Hhf@Xh{Bw8ob*E230${bg*G|$79b%Kkj6U zQ$t&_RY1>ToohBEY~^v$25n7FjN$J7hy+%C@bl9iAYsdpHwRuE-SLs$4A90J)i@C zlT3!bd!FEA%pj6uM(L}4U*GB;US&=dyjyaa)iVrZq%Hm_Uk(2&5kp(?dpW>`6Z($# z#_SIYsE?Qd(YStyq3&JjF*A1x8MoTixJPke$aJcD`fy^tQWYi&TC=DD2@WACdU7q@ zPnFcF1j+6zun3y`_Cpbcp5U`&cRKcSgYLphX+0u`kFRemy=wYAA80L1CFA!7i#IX? ze*<^_gTVeSay{4>{5riTK;SY94U~@rnv$q}-;)A;X@NC(TUSkdX+bSpgUwB+m{q|u zefsoX$9G%(t+V(W;`q=yKnUnL1pCQ&bQ7y>KIfZt`!J#)TY%gy>b0+YVAIXZbEWN3 zezoeT^4`?bmILX_HCn)!{Cm6JO~!=iJHfHngtuN-_<=UnJ|E~Gp;aWLXsIRc7Fn~- zEgI#@K~{?m76zmQUSnceGOg$^`(W9uP!ghcr9npB@{feh-_uJzRc|~*;2G!8mi%~! zzbzIgfW;!2jGg_tE{2&~izxhFkU4W17hg?Pho1{fS;o31wte$(f5cw}&_@YX<;8)% zLHx;>GeJM+4)Gi{XTDNEubg(Yww~0a`(^l)>FtjX4K66yiD$9otD%#Gh*<4D$1^cy zt-gRRwM*#p+h0oHROAhhz4e-HRP}CjL)h88qRg)3yxN5ew>vA;Xa3AmJvO0AuJr7z znrm`&50iJjvGatIlZM#U0lyI3oEjmWaMn_~92dzu+7sKKAq{=cHJXq1Um8VijJz<%s^V`ev3_Eh61W%zx3;=zUP z`Gob|PDjC&?za6|%jDDFo7l5E51pT2=q(;? zb3OUk6(21v18$eFSfp8Rkyx50oO(RmFNi}!_#^KZNg zC=IuGbH4LUA+O?S6N;<5`g_`UPNS(?o3Nz08zz|BoFfP`1CU>~FrhyKCNb~^D(;`I z^C~6Yn*XcdOGM0cuMsXU%42SBLp{xVYy{oK>$tZ?I96mBn6AFmv)w`M3{!~7;B0!P zH=V~Ck@t03AJibr3(nxO5`FuR?_l-MPv5&r$nG!B~ zBZnGas@qfQkr+C(ZBt5=xaL5LSgQ?{#JA#Ft?8FA*|T6j^F;0_vLLhu5?WUnF|tC^ zo{&tgZdCm_$wy_2-hAhL;--ToSKW~{ugYiceY~sY%$4?GP?k}^k#!Mi(?V}8Nu%eL5U(!nzO7;$h7>4_;{^_&pnS_tupx!{Q zh%Qwbf@uslil40C)pAH1K6P;Ch%S7&mcFPUtwJS;$0ZJ#HYy` ztDT&imN{Q)ZjEsI1tRyj{-QbCnSL=YF5Ym=-fi`(yy*>8Zw39NljZc!iIwWq9q+FD z`uFC6NYGw_XOxG;vyeaz9@%wn49`XwRl%4Gsw*zW-a%*Ft9qyn4K0^eu9zPb0m3bn z0;B&SB z^74B!NzGTD{an7QtHDKh`7}vW_lIeJ9Z{!k?-cmrzAw%+Tm5CKiR#Ny{oY>%?aW-nD`TWtByk%7f9rfUh=7 zVL4O4>tWnrhe4=l}@Y_a~xl18Qq$Odv>(DGH|6=?3IVP-a+79ZV#N6YJ%P zYch~|Ty1zgp;a7lMtWy7>O7HNYKpE2yAIx3R^o1b^kmayN^r-iG}v3iB+bofmZiq5 z6^-DZmp6y6D%qXo_uN+swbgs98*qmH9@9a6lS(pIK8juX`45ZsFrg;Rs^>c10S)-ee@ zzb1|&ZS(*Wn=bbY+{7+f{5*fVwxEH^F)%l7Z~TJ;YjpA3hdWY~3j-yD{e({g-~D zy&4&bATJX>={LAw0Dvopvv7#L&`)zS20K7tJE8(UatY` z8Z1wY3w$1UoQ_xs9?uZO zoUf#nn36u$6P${KY}|?*e@CV80Y6#r96@k8NL(9*^hVzi0|ZO9U;gO{h>*GLDS@%u zK7lOIXZ{JYcpJivgwG)j=EqzIf@h0P+O+C?bvcyzl@%{5OHc}8<<&uSa!}QEX{QYu z9yLUm{hW*S>5y&CV+Id6mC!p6#CTE}Z`9XH~5-Q?i)I7pbIrU6}K zu-N^!;>G*}=&X)Yzf0Fio8uRx32DX^*FK}9 z`q3X*!no5LjBY$Iq1f7i2rhUiFhfF=8yttt3><@>Sia5EpRc2K-^f~iBfK2osfC^T z%|tlFlJ(H9Pd;`{U)d*JCoVIpW?y|UQmkv|b(NKAm8a?CD`SrTV7E5i$s%9vK`Eg{ zrxBwy&z8qx`myW$vlLmS+Na(o(vYxd<-oRH|AxU{HjEn3eR;yr6bi=(ql<@Kx*o@M zQ6iWx=+4?A#A7Yy+na6M5dg=BKT2o0hn&1Nh9z3vbwOh`^ZKqvI(5P3Q2PkXgZDPN z*Mw>Eh;v^ajrN9+Oj7!)X|%iLQ~W?CSm%lENwc@$!8XmhX8B?-`MYEBu;?q_ zqpvu|s8fy-uuVQslq<)^6$e|D0eBvP7Gr87jp=#tda-@*c9C_ToAX~K%6P`lF6BsTEuy-l+ zn9FG#_vkMKqGRQ5wpVrygJ$h&&*)UORo$=dV$5R|9gl?&Xf|8oz4AKsW8h5ta?H4e zVHb4lR^E2$mbtI)5Z`$4igDu?)3t5QW~o%{`e)h0_pN1ePiO4BBR*GO{_uu{K%JEJ zfyB0$wdcH*R>>eXq`e^7He=6Kbdg&eDkwc$>eGA@@;WBa2_`-4X4Dexe*fJpQ994) z=g?&A%DBuDz++HtZGVJL+&(?)7uqO)lc`4vLAVU zyH~>R-uu7{OcA`Bkq{A{_R`!(mI>t>3G6_m^lR^y*Ewyqjc%6ncnJs0YG1`2S$%Tj z+OILd(v`rsBDtxd%}PJL&;=4?=}it}bqLa+*I z#s7k~$UL!*wxC%@Umf@x)vU6}6k>TbC1`|iin7sG;BLWR7qr+efKD5APY5-XCwU2@ zUDNg(z{{fAmowizGqG*9W-GfiNoUf$JOF|m_o=p+SB0Jb$ZJB-{|ht6rvGT>fc>AC zIgtO}%%S>Z=BO&~_*XLr@-H)o_nH6B%)!@YWZ@0+Cm_p_$^=q#y?MwT5vhsj<(%CP zrnLPUcdAK?L5K+Ev5dXV2YmepZ^it5++%sef&WFa@qg~)NcdO2g}LKu5OYj~%Fva8 zPGjP+d2XxZBZe}7c(+SQ+R4)L0w~_)Y7S7eyq5{0hSVeO%!P;bH^TaSOzceT2P{tb zkABYF3Db7ij((l=;rB#a%ES6OsIU>YTEt;1S4)VfZofkd%&^WPG3~=juV0C?oJo4W zydtA4oy~dc{3wTUu8x^=H`Z8KJ`YyzYYKasolz>4H*OWl6c`^PNV+j3-9CrXD5Rj; zGbYLyL7l6f2J;bI^npM(Ipk>mJnH_|o>lwNfR`YIc z64Z3_)RPIMrKcJcT$2`mOM4+7JiXeRNiX!$1E|1KY{1LFu@fbJx+zizq%)@L27{al6;wm|c<6usvt_&F>MZ^_(t7HSfCGM@Rj2T$LhvH)(5cluut zJqbBo)w^ajwh=h)3AO{r0f*8X>D3i^5EC~3Zr4g%S8_+_SX}UVz2!`K?=8OiKC`+1 zhg~FH_}xI7SMx=00_*Jh=R)+OW%}!(!u%15Zxo zy+L(vh>PDmUe^O=L~C^g{0cDTE9zP}fUG$sGcAal=3#fF-B~!A|6IK4>;HGKu`A5RZ=OGm7OGN-w z1>`(1kCzlO4If#g%0g;?K4&^^023OF;&!l>34g&LFoba90oZ~s4dMo4lPBGGEI#Ly z>Tv?*;d{CKxj>)LE;|QBBiX->ZkyC$5`S^+QJ|k76@3M7H=3F=Gs*}|VKscsmvp=joEwTpjK3)O zSV&V8$8;O(=r|I(%v&7UDlw2F0TGH{Av);L=wUH9nqZd43hyv95dLN#MAx{KW#^AS zYx%TB`M?DZR#f%430j@aRbR345|Z7PdXvg^)yZ3 zI$Xr%>B>-3Zxdy2CDpAacK>>?BXhP3tDPkMzEwD9zuYX(lO3*-UNXdkRY3j0A7c8(Ag21w1ov4it>p07Ow_hy7ERPsO($kO*#H}j2_E2Zd_e)LKf_!#15U(5>=pW%=_ zU!F+Q`W3S|d?8!tamYy5FP5TyhynwOSaA=Sf-5TgNY&rH3Lvg!j2wPxyviIC>&@I} z4IT}5KR_d1E~X*+kvCys@kvtPI&q4ze!VYUp@(EqoKtqBmAgi_gd6#^KQS$2TcVmV zy1tggGyvL^>Ywi9A3nxN;W~!g<(}7uwY^Ws{W0KYi>>d*2<+(L+}Hck6e-@koRgik zgA{204ZlM7D=AmZ8(d}g@@a0)MfKCyZgWLjn1_m$k96{;O#+B>wQj{!!B<>Svix!Z zt-yrWJ1ukT51-wx|4U0~%jlo^M(If%k>;63$GFk`ez3fS<*~9gSG4P9@@WRgG$X+w zMP@IsMOK$apS7H}XH+~ZY9pYT9EafMGvM<(rfwSF*@HaevLmY0U=h`+WP~Z7-+0AZ zW_svacHS%RPrv9>1B$o%U1&SfqAGCekZ@#33U_(EI`2a0iY9c-?pZOekD>JhQlNw` z#fjz7vM$q86U67MlW%;4B}Nt0bS^*eV3dqCMwnh)(n$)|ZCa9dHN~40?q-rH>o5_v znz9VDM%)occD2-oAOv&&D;$)sTQMX7t?@fIW{k^TKz>l;$%I*k>-t|eF# zYf#V~a`Q3$Os5}`zm6Oqr~GNJKmC?=*6`eZFh zsoE@b9oXxHpz)ni_g8}j_Cwf(+{6gT>L1l%2ONE`4(u5b<@WB`NRnDbf8iUS*BOUU zN2SH)b+TL6Z9drR!=*O#2}PQ-MRal_UfcI-u6xkg%Bmd^C7$WFb?4Hj-J)K$O$;>y zPjfDnEh#i8E?=^J=%lx+|Ia{NgBwVAQUOctSO4!9UNet%iRXKI#2M%Om=N*crJ&-XaGn#?*nKqkfYBHaSpqoted|3#y4tJ8cX|E!; zcjo$tBU0ME&T1LG;`Qpni=?K0K=uA43)2tLt~zaQD{)Xp0LU(cX0%jZ)S`M^|8pu( z(>9xSIn99VmmqFEcL`0*;sq|kgryiMLHZv1`Lnz(AROHuVeLM9U)gv!e!D@}p6xG; zGe<|Y4u9XhP8fNd7~!+D9suc(z~EOdBBO0bt=KTkVJOx6eDiTFL*Z6kvaKbJuVrKN zJy-J2z)kwQxYXc%PTypebQn5@8sUFhpJT4_PsR)%T%G=^&Md{^=ls4SE4d!s=`E)) z#4VHeCC>mYAuY0&Z-_DoovR?VxD#4F07}m4cRwgT@7>gKZ`KV*1!R*uU`~01{Sw8r zK?aK90*{yzM%bCR+_~SxJ-F3tY#0jt(gBIem}_1@+Qm#b+qW7OgE8lZrN4h@m#N?1 zV9M0QSS&Fso4$X5F9G%QBI%$Fxs8Dkk@YQ~5pNw`4Vi8rNUx_M zuF*}pY#h|-!eAb$Y06ku&|u_R=OzcN`aPsUiw$Me*m&!~5p%px&>!9h<`97)7U?C9 zLLmN#-*H5w!Zn=D9RI#P(_Q^FCn4H-9Y)zn#5xXS1iutq_BYJSV3ar78bO@|cV1r_f)qT1PDe}`E@O%)I6-Pv(Oy8K9`l=ueHO>CPGEu9O& z>qRea4%?QDH^&XB&)hyz-}gLhJ@Lk=gA%5{hn7s=mz|9Q@cQ$~fH;xW)C8g{S57V7 z0#Ym6hnHHF5TlX=n&r8Rco?gSZBXcSdFc?~BOrL-LI-eR!u{Czh?w?xh8n^ynT(z( z9ZM%qbW0vy0Whpij5^U{&7u_}-9Ms9>_`BQ5e2r$v&DyznG+W!X5DL@>q!qC5DjI{ zKFbPG{y1v;DB?SJlQRF5`!8AWiiL9fnx^H170F;VsZa3~urvsoM8+HZ)sOWNYuAxs z@+xEQUnC7SZ5EI;`pi!;)=?Wbyq3t)Mvl`j!5y&?0oa%jZAR}6b3A_7JaNq|LxM#^7l)Vlwo7aZwkD|A} zU4GH*BG}0?V7CG#P;9_+Z!pzCW+pT=2{K+pgFUENz3%*Zc%$`u2lOl6eNEJr7XG&; z!F`1RK3SDBlRvmbMR{<3{U=xB1R?6-D`}kxK^&A~VRmR9At(om`F~`{c${=G1DbdY+7q710@Qy$Lz@n+yV-&;W==>agWCf$Du6TqOvbzl#B7jrpNoL< zW2vIC8_qI3<~Q*@h=4re%gdQJ!0Ky#%77x#x~)r?BnS~bkMJjfaaE4$Iz<|fxP&$} z1KV;`{j&~rut;dK7dE0_XY%0Q&D|rViwQScOiVTtSkbkvc?qE}d3S8Rb|r=UuAxn{ z_@afHytXCs6rp5b(aig^NHcX0BJ7CBSWq{%eBI&DW%AH)Dkre`onikr?TE37B zMbT{L_Qf|s$cn%g&NzBCXl)d4-JO=}9!1TPdXkHzJ=sWC%e}r#$!K-36rodo+V@H$K&l?KKgr?^k1YOfOzH{bjC<#hn`4?;QO$4n#b3 zSgeYY%F+tyalPyE`3TH774(B{cv(_*0Fp@_q7B;0*28`I4><(RZ3$j;Exd z=D3TcFxbhQ^)TR9mgW5I22D*y;Mi|Rv!a{}(~ntrPl24Oo(W?|-EYf;hghG9oO>yp zJ@Is5_jeobM74jN?vQd?UnKu`0SiTg8*8(aeV5PiS4uxELTO1dA_;;X22>2^M=1MM z>qS~iU>s5aY6Sh>0KVn)t2XMMkl=K+vg26DVK>0jR0&=)Ux3+Du@EZ!On9e@0wWw@ z)-|E7$aC>UyvIj4s`4>Yaa9`Cs~&FX69itO9&s=hYf7lOBp|n_btW7HexXPxO$opl z?wRKbd{S<<2x_N)ZvuG=#q*8$N1Xjg%a<>vV`IG4evGj0949h%7*hU%p03J2G>V5E z%5n30*M}u|ZCKn(>rkvfS4gMS4W)#mZhYyLE0nO$(5e^vYys9IDT~ND=iP*Dy+p zA{SCPH|<%wE#^+n_t) z_Zzvv3)!})zny0{y9nv2DtI&O`Iu0)Sm|mm-E}eLcJ7z%1M$M}Q?||7AoT|0u#vV= zgKo9Fru!}I$}4mOyU}x|S0A>k6TlWc)>L#X;_hi(Etaq=TiO!=v9u~lY0zx(*JDm3^-fjUxkn{(HjUJuut35=2=Yf?E2*!XkaOkE?IrfVO7Zt@ArHmqu zZAaJap>1%JJ|tbI4W?GDNQpDEdsJQj3dF!goFYtb;__Y+VSldtC_fakLU< z^xI~%O~;0KlDRe_h+co)uU8EUvZNp3k6mMS?5ovC)K;bTPHgLXmj3za;?2a$C*|_E z3pTfbI%8=3ZlANe?H~W06y#LTs_8I)zAincT(Ob|wJMpsGAFtY?O^^7l_1Oil@f&c zpOhd>$TakSuLMEhwBsCva8-QfJ{a+qpI{%|JU z{5`mhXbn}7DVpw{0~(rIZdgtvI-?`r#=mSkgz-rAnEJvP;N-RgFN$QmAQP5`@A5(d zfqbBO#67^26%Uy~od!Oq1s|A`HI&Q8O&zbX0b(T%gO(=!#l3K|6jq|o+mx6pTcc}j z5N0>VA~3Z-)?gCiSKHYnLzYhSDT%58L^?V{W6ppT=a`nhIYqT#v9^G&m9*|s9K<$6 zEKJ|-eND4}+yL|<4;dc^4VfmQRYQdErT0vtSg&UCFC2y`X=npCHTh-a^M7FhM63-+ zE$W2~4!dU=y7U~Ub2_Q^AV=S_zIC+XYRgSBo!yYbf_x*P>N&`_J76|?Oz)eEv5psQ z?=-fK$nml12)G)O1_h~8#q+d=yw3b%XooAG?Yl}&#h-A8gd<{3hwQuk>h(Lj5JM}# ztof?^x%c^{RPZW_C;x zfJMNfI2qEhSW&U=FKmI)LM^Ma&h{0@eI#*@wW|hFc0wLDxf4i1I^hG4_>=p)KC|z& zpir;%Z;SVm)ACI=uguTN!?|Tj z_7yZS1v{TVg&lK#vUkWcu~HeV04q)C)>S>lX)_Ry@PTmk?CB;9^pk8<3xDli`AR2% zA0UcBrbbnUQi)k4JzP^CZFO;(w89~+tevyzjQEG>xzpJet2b@oQG|)m<)2hf8mMp3 z%b_(;k>YT+PK;j|{mu7xgP0&&qi9mR@I&dW%9^a(%AeCV{VE5-(v? znso73Cb9my+;3UJU>j$Jyvl3gvtRQGDOR&uH6TH0{!Q`=aUcQvk8b#3jE#l4t<4cxNS$mzt6o)8uS(Z`*C~w}BDgr(bQ?SP z#&2oD(S?2Z7MBi94}du;_&<#BX=g+=dqK#th?nZ%f%Bs;?If#MR|x7` zk;(=`S;`WSwgjtn02jmN73ep+2-qutlOSh@R!yX70qFPI^ysrH^RKcG#hgFno)jf| z>ZK5^VwlZSr8_$~(!jbHa0;2V#)L)BWXM*eV{5DV(8=Lwrt}yzLyk8ITRXg?-i~xT z-Wh#4X>fXF7gf{~8xEVpR^}oqPn)ZE3;*^iddNqTfi+&aN_bTT*pBFg^4O8!UFDtK z?DNj|!#5KaJofK%mprtedlS*!j-ka)c`Az!IhG$tcKc;$CjC$}I@`gV@1-8e^s!M* z&bFtI^dhpFR72Q$zff&=Orb|VIhe0yQs3xa4LU}Ja9lz(97~+Dl~ZX_tQiN3wu>G~ z=j31J5PC{M^)0 ztagi6Q?ywU%g|W|P?XhJ;`mRI@HTuA0WPs{w_$MNL=< ze=RZ?E$}f-6a5DCP{>G>aFp#ikcGJ%;9c2~mF1{&>IFU7B1xSTN8?`xT?_v`B zBk7IYy;)ZX?i^i%V>Yc4%77E?iJZ~m#k2;1oIkz#>_;Rig`~A*(wewM|4gk~idvJd z3GG2;(OHAl_U3r1#oteENfk$RT5t1Kd?3yv?$^)JZk#s&w~pCkNE5K~t^?ZX{++xS zr27MQ37AWLEYrlT$#;$~AC56^jtiJSTo8V)^tiJmfo<0&lY`xN@^-}Q+`Z8PkLlNa zwf#_o!Og-^U>{^}UjKc-@_mjVjjt~P6Xm7N&4MDvQ4fi4taZhJkRa^rpPk6xbO+{! zS+)+96y#Z_8hmw~RlI14O2j{erkdetnmkjCvM)6LSj#tiaivg_w3oh6Vz~R zv+IH)X*4?UmM9;iNmE%_6iyR&C z)av24!cyV5icR)mFJPa!C5od7QJE zO8ws5$)+!2GRKRzoE|JoKgCa~9C5FJ>c(nNtq*Iytu5CdZ-D*<#mM&>hu`6r&U@AU z!IpX99C`1q2I2jxJMtUgQoZF2!shwDtE&z_=Fz8N`V=9t@eBLxoBm=e#t%-Cx|?htbJHm>!AV^2CN8^P)|NDnri*7c$4t~)_?Ptb<4+Q8CF zi)ZpUuY=a+JihJ2+Ma=>>8Mm34S!XgD++!#C~|mV?yzM z;c&5>9;c(Dg%TEKD%7`9t?veE(Wf8o0QyEh!_;8NBhekj(J&X3p!#0SNt=#`eOqk0 z(vjEZRt)pse_T9f9wda7TSOkU+CcqO>p$bri;2DunS?4Dl_?{CRoO67|h!d?Us%Jrq zbwW-OUkr{Iw8?N^_Lcdy6EQwnFpu#)*(WxVkhzB8R z!nmHWj&1p9Z-PS&Q`P8`rgn)0_TWG|xpQ^Qc9n0NhD_e}AiiII_PXjAMy(HC6pX?y z?&32W#Pq64yrwC+L->$RXiHbW1r6xtn$OcMv`@p1R{iaD*mrm;C4I4$cg}6~r6UtH z(^*aWU^u^W`T@d=O$#CuNP}6kbHyBnn7#g9p~HEjp;O=(c%!7vARgfF@QOaoFG z;vG$P7cHwPTwb4M^!05fpgPx*X&iDJ?=;w%PC8%|A4C2Ck1(ol_W>R|WJ{mma{CS0 zDayzR$-4}G`9cmM81p8Vw3z*)MZ$eeab=ngG{tHj>tsL;4eDw!^}UiHQWQ{yb!mS= zF`WNEPq~-;6N+KuTI>Fz)Wotjq?}CU=27KfYW}L`S%G`|myFuwA_Vcn>ib5^xRkOOw28{Jt_OuWz+4Inv1LqirF7Y!Gxhr4aPbo5 zt!Qnpa-;C~c4%a5N1dPV|OdE2Db>m=Bsj}rRm{!-F z6|BhNH$T6Q?Zool3ydfZDSj6bsJw^Lj-E~_#6&zGB9CU9LYb8aq%8&_#7v~v`*<@& zsi`f?1p4N^EGe9y5pbAkjZR2US?2O%+jo$KJ`Csc5wAnfBT|q)6H8->@oB2&12s=m ztQ_J+XDWENK3$WWlMx2t(SR4K?pvF7cJng(n$_Z-#|G7&Obl-VJhfBp;!W`xnw*kd z*G?KjZiP&@myFqJrK1kBE7X3pb)tr0*v`HLcZ24q4I4l`w3M26#K)6u&saDN{YC;` zuAG(+6Qj&buNFF!m#rFPAQsR(=8yG}QZ)EgNfN;FL|CroNAchz?jcEriaZR#dnDJz zmeZ!Ru4i(=^P`_bwbO!iW4X)3r-w`Mjz5N7k(bY)Z0G_0wVIddH?uFza<)U0i?SY$ z)^ui!)bgT>3dGStW%>@⪻H)5o^+EW7Da3SJ6t&>jZ`TYOJv9VjUb*13#ZWrD5MW z#3;(G=%N}CDrT<)JSuv~p-BS@YQ#03x|@Sgzc#6!Axo~TP35HT8q0Ch#nC?i&qB*-@rah- zU6)(|9VHO7eCi)DPu_^Bw|i4_dUjx*Ik=V-NA6U>9ma;aF8BWv3@jQGQs0iA7}^I+4I zwcwAby5oWE6N^GJjj@<(v@*2UsY58|btHF0)(XcR^+mSoJrQGPKXEK-Iqh3~KmHB% zRmee`4jtqNg4D`Q?ZkJ^(xMMlt={ZN*>a*f5oh<>@p-|~`pY$XCgh)u15OBlPtg}- z))3JMVe~NZP;>Y-9;b^baZN-a;p9V1ViOvl@1^nu>TnZgY)ko7z|t2Z;Y1CsQs}0>kzWw zwMFN(#Q^2=G!^LO_5mFJcR{_Gw2=teK(NT23%u-A~8AD9?w8RVDY%x9mU`kD?GdA3mKIEKBgH?JU!m ziSDoEp#jOm zUM-YseP|fDVEUsTNYvIu_8XN1x;m9ati1#uj=A{Xe;8jWrVTvg{25*DcHa8Usj>;i zdM|# z5toMyf4{>*hkpw{2uu9PUH93m7m&7`@NX2<QG zB!G&1_FqlE$)_tto zTQoJ%x# znyUEab61I>xY{V*`Rc1n!w_!1o>clBNIMaKbo_?6|2b3bt5Kx(ymr&SJN3ic^&fPnoO=b*ZHp=k05%EuE^JWL5(Sceb46f6Xwyf@82S2k2 z`W>v#w`%kip6pUIrw#5QDBG1qG=gK99vkN7AJjRuC-*2D3AWh_tKmE-{p?sRrL(3lS^gTk$Y|H55n)kPvZ@n}wa{ z+sd58sg$dxbAY1g4wL0JY1VCRS9EA{%IGJ#9zs{kiLsi95ef?6MHZ|9UZm=%nY>Xq z7z08L_%{ljLW}OCU4n{c$-rQFMKfj(SUq)m2+Meg(&#=o$h*Wz^gC#H;OA85yVooG z>$lo;inX;(o)>9v_Ft&_>P@tfQ)`hrh`ZkMrV*}z5cSf^MdF%mwSG)Ykr5nA(`ZFaDQA|>i>4DA6z@WM^i~{%Jb9Fxbg1Erjc^V z)aH)6dJcrjsuU|6Y$E-e#kxQOXZMNFaf&l~`~|S493{NNC2!HLd!?KT>MlIg<&awG ztpE|)7>FoyB;M*_-><`}k6&o|jb8B0!)+#45MGX+_l_cKiGuSh6EL>!NP;?n2FnDv z3_WvJcYG6^zW|{WY0DeO>|6N@ZDUP6YFj|;hm{&(-ov-$=!bz|O?E7LEIi4m+4GE! zp>18JUsLn~FrW`VIa%Zm{U$BbGnR0%Cy;gXJIO@ zBWq;wnL{i3K)osRrUFb18ueEP)(dzyUyGW1H)sOmW|&Qr5WD&oz078B$^HRJlY((` zWIb4Le*~2qn36gxe1lt=p<1kSB{Zr?F>?j_P*ja#DAs$YX!AFu6! zGu+z%M&bzIQA{PZPC8gyg%|IyR(*ZR#*1AVa^f_=gB^V25}MLCWIwQ1gp~6a?*ZkY z5QlK`E4O+M>wM-uo!Vr#u|8en@D;ol_-gVvRR&?VS@E$Ofg{2JX&bHc-Y@mb zUb_*?<=(kWo41-KqL}_v_ib((DU9H^zc7puw{l3nSX z%1`!k?5kMvabtFaf1H$fy4L#jNtc{n>i3`-TVcI$`7C7f75}_RwW&IK-1e3c0b!JS zhN|0?U_Z1g;%R93*yyBm-m2dz+T^cNUUEk+du7m|8M$N=j4a z({O;bO2Wc#${sLO)eKeojXodLg_!PAgP1dKgnzS0!VbHKOa$vcYZz&xt5|e!13@32 z3yuee2t4&uTcaHo<~4#M8rt=(C|O*;4Kg-Yir{h`Ar6L~h6Wx>-X+`7RRduusz#S% zM}*zR%-EjI68QBpxHjV2oSQS17Cp>2%FF9~{8L}BF0_PaM|xlk32uW7?9Ea=@gvh@ z0>R=~`Q3&+4iuOo?aTN$aa7A2K;(v?adffQ;;lVGh_c~p4I{14W?&7mZ`3GzaEv?H z!ST_IJ}9#?Av@1i9$CI+6mcQq^0_?EHNBXYfV#Kk)64J1qLPiMkd-DA^THj`on_83 zL8o4(E#wKP7n&Rg8`YcPAcP-D@fT+~LM`TTP=I zKjyGFUhg%o4%}wQfAYQl+71=$j+JD4pZBuF;0d^+^}UbR4pcZNW%ADGJJy4L*A87- zbyM5=hFlW&r%((Kh9VuR9j8;e+0TZ}pTd4Lq6v0_&>3I!kDyE;l z>3?!O&Qc&bX;#Ca#$O0XV*e7YJ2g{E4?=8ZYGS}d?q*aXHg3CPZrvLcGwk=ZH7Ij*&?R<|67PXiW zyL+UJ_Z647uj?~M!!7h5pgHTG;CbZ34u+Lg^^#l)@dbHVSvy2z-&g|nH^5~1} z^Kw5vgP8<6qJERAg4W(05iL1x4E7eH6`pt|vD&ygXUB9P+`7(!V2ccdcAwY26U7G6 zcsYX5HQUq{+?JWSth}WYN;4X*KF(U!p=Ba9#Rlsmn!1QvQ}2h5QI{*L^jS;FxA>B$ z&#t`A8~F;VjR*idiAO9uECkWA^PGb+uCJ^(llQ9@H=;K0fOzmNTm5xv0EkLtVTz*@ z(ZywXAKP8a^9v#6Ct_mGjkykiO-n%xpmF^shJgRAcX^iva-J=Yvy(fZ4Y7|0o^>6j zDLQto%E@c;5&4fd4`V3FY&duEd0v+_Z=_8cfp7RyxO;HL^sC;T1Qtm*FuXPAds)T+b&hh%w=yT~|ZiGj<&6UgqUMGu|{~ zqQcgQ^piY&{n^t-UNo4@VM)H5eXDn9L@$`&I(%r2>lM5*MO&R>ty5TYqWFZxcJ%5( z1#+o`ymI-R^q%%degfu6+m)#QkMI$#K_m4+aeajY`3=?YHT`EaF!Q^5JG3C2t-!<9 z({$k3h7$uTr%I)bb~p&TE$~|ogp|tB9gm*81mw7}0a#rGvm%at#DP}#CraRXggvDJ z$L(|n_kIgVCOyuAawlMzR?5NyWeD!nG6LnU_c4L3^n^-bomKFEBS#qg-$#x(KiXp5 zWADRmNz{ib0O4ab6HsdGjo@ofnW70F_`OvQZW{iQ-9r4cGd->#h5CaI_KoY+OTVSd zZf?YcHIBCP>?6A(wVBgX-9E9(zN(W3{lNHIJ4GK7Q9yp44gO#6^vRPO&P^$6DkaV=)7@k_)tD*l=I_BQI5j?Rdy z4|CkbU!L+@@Cb@B<8?8n58gXj)+_Zg`-PDrjcd2|IV{9g*FmfsF8E%-Q8H}jOD50V zv#0sAf2{>>K9NQ0El&L!Ab#$fO7Va9a63j}V)=Zky7{T|wV9tz$pI0USLUWL0)x}n zjbJ+s562QFmiwQbc-8xq9-f1UjZN%S_WO7YY|t@hSaGsE|)-3-Zn^#^4ojU_RPW}9SDt%SuPg9E3Y=#aVJIt~J@x$$>B;GO3H7yePJ*h<&NYV_g4SRgt#gB>! zeVDgzdDWxchNYq+>+2x(%EEfwM-_K%ReX=VM3_qiUR92BY-3eoIS3ms%5o`+SZff75CvzIE$0SwBm zqKNOwxCDE;9$Ve%W5cd`Y%YqY9?|)ISv7hWGDg?;~lWSA2YSt)5&o z_nn%^q@U7;$m;U8K#klWjKfcMe?xr3P1kWBP+?{%eLhVRm%nr&b!crBYDo0PNv@0o z)Nb6PcI9XFFHIyAK2uboCMt^JnI#2fPc?<*xJBC)^L#!;k~Z)(?W)n`oVKBR_EZWh zMdYFnRugtPw&EU6#BGwOxWW$#?ORBfsJh4cCcw(u0+Bry;O!IE?Or@`Zp8s-_cwr$ zc*RJi1m`&T7QIM`^?rYvf~~U<;(emTdFj|$DjRorxtqB2nGb5nk%ZrCcw`w|2 zVcQ`JPy|K^f9u-PrQ4+=7zA_c6^-<|0Q6v9#M(2%bEp?Hx+*Z+P_8z?{>0vv-j>F~ zmKtnHXT2kK$VW_I2Y1L|cHO!lJCqAy1~;*AA@A5eOFNnDxcQob{M7dFc`rp0^ikn6k%D4N zeC$ApZvQ&32>?Nlroa?@kCzuBx>1-QeyYniTo{ZFi4S*VA$^uEb3t>Lc=`7Lerk2_Vx)3zS2QPXj5?=_wQdUJ{RtUF*ML4y}gPCygKwgLb$hJ zz=fWke!`;OHM2G;PxE3=TgCy+8)vdfUpgZM^x_QdL-eniZ(&`;#chT1%d#s^HgIJi zZZhiP;@D$>?{{GgkMOYNTyH&_vSv^L(%8-B547lk=lwjq z5xV*j!=un)qF@a7wkc0v5SHKOb0m0Pa&Xr#!-oRt>#Knv=`IRkG$%`>*Zut$=r-e( z2T3_9RwfY4&n0J$@4C1>E+0rDwmb$Yi~GuXFOP*PD(5{X?~>yOX+I85*6FgI&_#hZ zYH-T8&kx`FGRI)V6mw9q{SLg&e@q-uwpa9asKdKXc7+_)EuQ*4Cs0tzny7IrL{Fd5 z5)D&n3dGf}(}n%sttvuF>=DR(sX<5Hd&z$(4cY%m8sg)O{eO{$nEWLTDW-aR0dtqb z;(Bs1Q5?mxpJOVg3vFz=_~&mqf-`N@kPozHA&BVXNI1Dqy`|8g;N(ijZf6URvH2-a ztiLBq*cgQn22$8%wBX046j7j`wWhPhPW})q5B3Qyp;cf043fUr5_f5&P?L{3#b<-Abs78N3H# z{KKRFPj_b?mUO;9`e|x%&RA08 zrkpgFq{%Techl4o$Q5%VQz1)5K}E$K5s>YEsB?bjoZs`i_qqSx+rRld^59qeEU)+L zl?UWB<-pS(rBwW7WAw>R{ zF__qJL9L?CePSiJW3Sp0W4w*vP*0Kr?n@VMes}R2lHXT6_iZ4NBzabON5D9cZ*?XI zFLfKi=pGLoRcDW4QD)p|skaf{3vW4&OJ}i9hr)JHcN{G0%)ohuY86OhVFSOtqJflOa&g7&1B1R^F2rZk{E0 zFh$eD*a$6u?Xq2<3%=5b*#rgn-0@+D_*Q@|Hc7w@C|EmE{(cqDcX*u(ZpLDc=7K@W z1LYe5aPjtzd04(~%su{6^{vEPko5W~PYb{C-`Z|;5orEUV{5L};>=p){Y=1LLK}Tk z^9-51zm5`s z=1vLQ>;#ZaW)B-K%L|u1r-H$`u(X>hy&WvNT{i@ljEC)Dr)=+@Prelsd1HIx^A)Cy zMMVEJcFNz|I-d-ZTJa=K;>=BGn8Y(&_Fz;A(hf83h|une6rJh5*Sr$ zs;<-Cud5qXaSIjHx(@7v1IrIq0Tt1}w?gWIW)AJ5Y0O?0827{e7H9tL^x=&xlemTP zN~iIp=bIpz==a8HLA~}+BwmhjYcHRaet9OC{5hr5~Ip z$*9P)Z`7f+?1B^qIGpAZSElb<+0*e8GZ5WS<7MSvn3CA<)q*aYfVYbh4`kpbuOOdF zA&-!r(%~$=SL`GVeTU;`@gir@wLkpnt=(LnF#HDp0jw2#gcR=bsTnr>F$F6a%e$-p z_FE08eJ2*(AAY8UZRF&AEhu%(c=#sjxgs3{Rl(~h-Z$8H#vAZM4|&yrlGH0NrEFM5@6Tv zoT%8r;+sHCxb~SaSlDcud^*?rf(5ntrysplOX``eiHWz6@3LSzmpH*URF>xoP~I=v zB92WKOcH3@Rh-jn?*b3mc!D!Dmy;8-0G@|Ss65(MeC(TkWHM)wcGt$>Kv9_VT;iORM>tTY!O6lW^zFh82*bNYIbT2KLBj?KD`{dMMo&9LOQP|qLfOQ zqnfNDlK^;pEEa4kVlGa^E{ipQ2NS3#fTGS~g(4!PM4#=228ihgLGN6xL<=w0$_3P7YpA6*pxJ+Gw?)3_($?|5KQyGJx!m42 z4q@-}Dr%f&U*=m{7Ab5g-0?|7G+wm&+5zvN=B7pT??vF5y}VtCXXY`o?qETJeiS(K z$6woni5`t7LQMS}@&#zw(S!}8D0*|tomUX76+v%$J8lRQESYMIpLIiz?Q7?-%_}UE zjwJN8(GG56(i9X)2!SCktara^ns2ALsvFuhJ-l1*uDx{SY?r zgZ@p-{(y+R7g`6wnbt^D@AXhjJ76fd`C5woQEYn7$QpD*N}YI;|Om z5)Oh(lwWZBgCkpZ%AF?Sr68UspKyK9Xu)@H*@1|;8fACEv}Zu*?_4i zXa>E&qdlj3cGo{cm<#%6lLhYNw51q$v*wdCNdEX~+4)lXL*}!=e%93|&6LzELbH)6%sZKyRRMwDBETzRN^0y@~cCK}bm{qV%L z>cx6>Dz0w*OM?ru>Mh?w%hXVA2c==HV5b3oT`QCX-iW5n8?zaFuK-w?s&~hs-u0|n zY`34FWz6Jcp;h(=xM?kx)IQOt7VROI9wF;S=P=j9AONKWThbxU<2QiM|0t4c zzn=(`WwpJ)iAYTM;uahk#hdu-WuHgb!FdGm8f|;Mt^FJ_@lgvN;w>TXb^T3q&HeS? zg1x7iBk|5-#Ti{z>8yK4WN;~eF!Z1_!iyIx`N)bJR64bSlc_NIyt2PamF00AoJlcp z6N&iOLiICRTTLHbwkDTLqp=KGZm-G1-2mJ6G2#g<<`bypi%_1#IowC7E)pJ(SFG}G z)t4Kx4zgPb>5I&>U34%re1dYdD!m2!tLBLd#VI{6b45*QD-VbF&n*>rO2MKssD3{x z*PWWRp7Znw_8qHu{|}z$TEojW?I{{435W!E!EU$zcU2Q7b|fUuuRth2$qd%(HDY@~ zQiE5_7a<(re??thayj5x5Wp_6sW^@V^9-UpXHYEHWGXW_tV}e^YFTVLO15 z@w~@K1vuj@Tlq#iI4L~t0=WM`;mE;p{9F=99>h-5*jpDFpnuIIt^856)MsqB0cJjY zv=fiWqK7CU?Cdp~u$?>ikfvJ_+igoi4b52bAJ}8eNzh{vzDt$qSaE;4c(gLHwb}=m z%oMV`CH{3h%`e@jLUB2ffFe|sPssSS90}>whvyDS=ah;82rse?hJ|AUrN#o=xApI2*@3r7SMsfyVESuzm}E^<#0sac7xj4I3X3vtxeGq9BX#vNy@QDkDiBo# zEOTqQ`DN4g`T(=b( z52k2cyP2QXrr_oP6?D44K_u~rE~!6r!hEr|`82w9A4!x{xbQW@eDyuxD|%ZZ5LFq~ zmtJ8ip!8Y>2R#I2FQnWU>NDiNv6}U==&*TPxi_Sj)bjJ9EOkupAj^aPCSo2W<#NT6 z?pT?q+=8i|R|sz?pA8p-xcKl0$oa59VLV(R=I4IAmTO2CNbaiv04t#{a@O1Gsp^1< zZ7Fx6-@uy7odR#K`>}BTBhA43?xpX#JxE;i4y0c+fnG~scnp4()5qPR2hWB?-md9XK(JFGQ2}u`P<_Lh_X=9$s&uu64N-llw@?? z;e~R@uYi9YTy@N~o|mC_ajFFCwt7qmlEx6z>H56LUKQYx62lvDpo8VH5OH9R@@om( z{#`gcF4?dPaw9kA&df#IhSeHz?Xu<}{i#QYoYgtmgf2hRvHyyySKG`6)!X?GUhU>e z{t%~QXa8GTGRh!njU5Z~C$KkR< zv)GvmxcCi7Vi>;ydR%+XIKV?P-` zQMlQdd8^bnF8!w`r^xZgvc>L}eakN=p3d0*H)(`kd&8*{=G5!y@%_hbW>hDvsu|yn z#1{4j)gb+j7sQMOtRCv-asGdhMN~xphAQu(g5l{3YUDC|aCvFc5Gh|Kf}^MGx~NWX z2=wsTsV5EJ@65~7Dpj!u=Vj}iwxUu0_WE?mrJtt=J#QxK!?w)AHs|jZjg1M6b@yIU zU%V^`o4#NayO~hRp4d^Kxs+cKmR>^m^j^Oe=%QO+ZwvMuU+FNP_0=Q&6P-YE@2?5K z{J%O!bbn02hn4>Uwv?@C>h7QiyaLZ0u-R0sGg;a;J&GZdy5X?-5{%$kyg*SGf%r4i z$5XpPc(};*{_N>ne?Rc;y`;m(_MZ2>^zHF&ZQG7qRQtPn!rP5I|Jr}*B}KytjcGL#+##k6nWchel4% zZxxo;GS?}=W#mN)_l(}cs|xVI28_39et;aBO30eLJAM>U!e3g5Ua9uIr-sTSk<+rr zO_IN+61a1FNgWBuHDba^Th+X*(6}H92^%+G>9@DRGu`6%$sbtUW*{pDmWr!YA%ult zeXNc)N$c82_Xh2Sm+GXQ6V*poF7t^v_XFIxpp>h{T2k%GUJ4xE}P zvh!L?Wx5YAMkWC?`1gh;0lqP-O-D7M`c}!b4`XQS{ww3fx6(YA>Q8Q$v=v~kjCN_J z$6ik;yKJPknFn;uv|?9|eQ+5H`Ti+KHn4XTJ3(6WhF6-cCd?Ouylv^#Sn|MKQ>{`C zI=l~rwMN-LbHm3>LpxGpbO@^_TB>iCR=ls6+7jtOzy8KpNjYizzdR)eiM)r*Akt)Iv+(!G3IV{q$1tJU8U$Qv$c(H$vVG-dYneZhFcdx$Q(clT{U9?u!7 z>kw#?zdYW-cJ{V*-wGc)YY~{4B2Cr&Pf>->%72L}S^^E@zxYDq=Oc&qpZ=eu6%|lv zGC!4PvNUoBM#F+Asutal6fvHoHQ8&@}B@j3t@vRP1% z346XsA|)_9$A&|0|3D;ktz+!c$=8&=3M}W9+v;au#njtuO3sCZK^3bf6(N0Tf}XV1 z75dYH0wopOyLDH<#h3bi4+p%e*#UDc37l~M`{JRP9|2z9h9khpz|*j^_RaPpQXxD{bxUp=kVM~p=tf2Z2tQnED zN5SmJTAXke{~azAUN284VVC{?#=Qme-@KC(m$r+`{RY!>F)tORw=``| zhn;=w=n^X0&S^N}Wz%Nk#|}vt4$kDcPEGdz>g-;Dfl~nZwqT6yU(r5%5oZ-6*;lM? z`ckrR>rf_a^~V&m(VQH%AT`H&83dnPIY#BNZ=arjq7iJv!~C} zJ&8l;lSwZnD}6)E=#kQkPnaoP^>@buvD|!C^Ee3a*$%c**7Ep3;6zFOZ5sEme6Bu+WWl|Z##ufiB~zaj4sS!4 z63zYyPXb5FH2%umS5#-wV8 zo4eGmE!7(F&!Q~-Nbl`Ex3bUD{A`?|wxF3AAa{96wD|W@|V@oK!!oIDGdP`(8 z^;c~}GDTL?5I0#b-I=^-EkwL6R4LuNLeAuR8?1-CwjkCAF6a`*-~JwswGFxBPuZK8 z{`9ku!fZ%GDWq5%yscSgiF=93h~5s-Z|4RJ&0APN?I$c?RhHfqA z=o0OzllCe|Mhe_k4awM+=sn?Vj33v_UGCeRc;6|FD8H9RSbCN%C~U+}w^dylFxIU( zuYBJ_Ea`;HHJf$M1t4l~CdYy2qvLM+ZDDBxei+-v;+3E~xAGT_wo1=MNq@I%aJ-H1 zl)su>HUbZeg25onyeoXw1;vSKSBxwmnaD5J{UHd^SiEK_=KJ^!*)E$|Wo-F@eVR@i zOC_zZx5#VGd@QO`yh_>Ze<6=F5|a$qUL=W4EXtuDU1$@jJX(ER$dxhlI1`058B1yt zzWWx6>9GU(QcofI1zTqVZsR{oujNBF_FOJU-4EVuB^WfOO`69#ri2md8s@+TuWZp; zMb$l1OW;QzXtS%EvS-M25bfiUX07L~e5u{{H-au1MEjCc8XCFXJr@Wm-aluiHRMeF zI&78oSx8Z8xZRlQ;Fz`WDW3wVsQ4(IqdB~ z0|{~+I?Vxx$hI$~jjctRbJgs9H*&s@5&mxVPF3S!=2tFPYM%CZ>zws5ONojr!}9(m zq`+1KA;q84!st%djM1Us01Kt3-WIz&x?hHIP%a-#cpk#>)&~`?4;~~&BssdeCCHvw z<0oI=<9n=H1#g`No`L+1`&1RY@{mulnh1@H6s&y=Mw-SST+HyLhwvTZ*wRf=5l^1K zT;0^hECxKD3iZ5&8hHK159g`O>je)a>2C<@k13_b z;$DwZV*%VppqMwD=c!1wUjHd7&*P$=JKsXTN{7ZdTbGI2cx7X@YtRFhn?BV$OmSNI zfx?eB@zfJruVT$#RMHaJwVIAvOU;+}LZum+ zvZ#m?2%_xcL(OX!m5&FCd(f{@F%_Fc=g2HZk=|yoo!vA#i9$kts4L`ciTQ|&T^tu# zZ9&E;zJZV^Z>Otl1i2f@6IH# zbf(KDU1C@-T_UkD414Kr@Ae+w>8Re?4r@A>+8uePiJw6o?aP=Z-PveZl zef9cHx9dlPiZybqyiG8BvKDf2V}RO#0~f`g9@eifG@y+c8@QougoU{7CTw-74f}07 zBjj$KWtM)yh+>6;pq1BN! zK!afEzXTK`-y7Nt?PID~{fHo0BM}HEW>xFk9N5lZy7$aQG2alDg-tFAIn&9DIxDw| zFWa-Crpu}ZZUUsJUXsIHckNY?HD_ID&12`Q)U`iObIfY6oK*HY#CI}Wk8Mol!x7i* zNN<06p6G;?g#5*;W#{;w5Iu#On=1!R;i1zsE9IBh$9|4>oa|zPXvZRmb}(GKkJzkz z2fprv_1L)>5beO288Vy;+KHc{9chqqT69_clLr}?Qf+f{EN_GUi!2cBh=$Q*=;O*2 z?drzNdN0ehvScSS66SSX^ns68h7CvsX%|eo3peKH;h?hx4`<#UEHjmy>T*85)S7L! zT!iRMw4~o>4fF@EJlun2hLNRZ4-8^yw!U)b0~Ov4VeJ$y7)3^$_9S+(W`n}Y8bqOw zieS;71cJWV!wnSXrAU zR+_QGGiQD?3OP+M-|dWuS>9m)(a4+9nMjUFYhukSB^1YVZPtSGNIm<;>TWg6{oAVl% zKC&(uE8KEc2*+K-TgjXiD--S)hMD<(cOpwQLu+jblase7ncQc=cY{X`^f$IU z)2p*v)y{6&AOx+GawbuayX?$r83q+REz zE?K_LLwd>$ME#S@3!`!CGewHpFJz8au{v?}9iiJSX_{^uyB&5)tK#!+jtq@;r}DvP zf8JLo-qgocsz29b5=Y`ftYH?M^(y)LpFS59*X$c#Ir&Gi6vm5o3oR|{*&xy}m(0v@ zunyQp)bJkIk^cU?V5VqWE+RZAbh0QEthr~6(5+rNRTTVF>R;pHSX)XwsB>IR#_205 zikg2=6gmG+Q9K28j;E-6tLwYVqbANvpyKKC*PwwZP)TRyomwSDaUsV=iXL$T6veQT zqHr;rLQ6f2!f>A`3M}V*C`_BGanP_UqXbYCWT_RXbG#72c|yd9PzNXTpbqlhp)&%+hfd{yyCo;7`PVw(#2XqXWRNT_NSQ zZ`P9G3Ix9T_Nx&X6Y7DydkNK;DXH`}ntD@ZXijvh0lQ+QP9nhRlTPC9qG&pyt-W!| zWJJTP{~tPu?feP!|Dco5eM7>1)=3bYS5TIoLEn%}(&TPYQbJT9(&V%>H0Vbj20%#;xwwk@E&-dsRC9Zban|-=@Gz^=VmyTGEl+ z9CCKVkHiFRiOu3W7*cH8w;=M=USx?IMfpGN>qW(#sIj5AbEKD?Pb?%)+3>~7g7L14 zEy7)0Oy6Ekqb-B4Ps4U5lnizFt6}1$c%G*Jx<3EgjE6yw;z7UNdA&7CyDrvUyZM)| zHLiGW#Rhk`Ne^9exFFq3$VIdDa#$L(S5Ko7;OEP=$Q}NX`5ryZiTE4|%gch@Xt=17 z$4zeV>9n`zqY_9n7pvULjEiKVi&5wOclBe{`7d#6@x@P8y;^v6A+^JxPuUI^=+?61 z&TCa#sX9lAC2AsE{j=KEl=bczd@}gRf1LJYF}V8(ouA{c)#kM^eeb}PaX&S=j;R&L zuCe`|oD#0bdd7nftULUH?H7EY$YW<4oVp@pTbLR2$lCYCa|&=Squ?Y!5cSbuBaZ51 zZpMNjj^HiyYXS1x0PNtsvV)Q#3EzOjWK4&0FI14Y4-;7#Dj)p{X-Tq3lS#|hF+sh< zk+NO+L#bxEq0&?r(>1S_Xx-Sl+D6(k&S8bj2!HPtn(U06z0q<{*dUpxny54{kLtcY zH1&c6GqdT5uRo-CAYJ^w|w;S21jlRdZr+271})JEbE4ib$1}ET$~>t6BAu7Q0}`R~g%dZCv{S7+@ke z(zz2(!2XFC;U)t5;&lQABgDMdVImZ z!4Fe?Pr*0%5BMQ{faK*7?eT6C^WC$Ez5W1x=zX5Sf3T6$nDj{!VI{vZdAmWb&M#aM z5u$3oc{bf+i7-tO_pFHK!})9Z+951H=>TdLH)xD=~$jY3^~ zkMzyKg~-}_`_}PkM7M#oqe~-B$8h<}4w-}QaT3}ulUdk3hyqkD$*AB=U znqB*ITSDONWi9dmBfHH4VMh-4F<3ukRF0f7pjt;@25#bYWCc5}xRE??B(DbjxVaYY z(nvIdF9djb6mE^0xG0DwSmI)id83;bEZ%AqwSRR`|Kl@t+gdWfX(^oQ^=W(J1ALa$ zim-;{mDJ^jSW$#G^J!|uL`+RNY0@{9d`-V9=}HfCg}JanFpwb){4JCx&-u{n-V?ia zbod~+O~6HAR}TgD*!kG=``iE%4l)ko=bGNEZHXK>RF`Pf-TDe#VTi#faEUZc;MY@x z%8mH?q(#Ed&SvkE5{PMHn6qoNPOpI`M?HkUX>)!lZJ!Uf10wm)qkcaX(Fvsu`gjoK6QwpS8#-O!WUaCao+eG$ ze{o8NL^x3s2a}v@%2$UL-!v8fukWX0$ypBQS11vN3T1rqi_yAPNI(xhh%F7j_)!A2 zSLk%!VwI>3v=Rgw8D;!#Z4?Y3H9o#$&8hbb`#wx9Z^UiyBuUeQTP zBTlIB?G%)!i8)^Qf8zB!1j#G3o(6=4KZ*#mpJ_9P(4rv%8Pm-rZiKMssHYm_U^NpG zVuU~akH@=V%h9PTJ5^>2cX3F=mRbh1FUD=jc>>TNEYbd{*G8a`3O1JE71NHFXPFAL zUmxVy{JCF$2QezpKZaliN+T!XS~F{r#rRI@F4zPttQ9@Sn#Ym^*IpllI{QMTUlIS_ z=-<&t$BI#bhXzwb!J-~TsogK7zs4zIE`fT@7{>Hv8C#^1JR+MdzU-|mBO6kkkU{kS z?fzdc6sQRAd{)U=1kGqzRCq~lSDy`*Pn&KoXN=U1+MT`;+JD33KfVU1rN_{?oscsc z5Vbpcs2O9jX<#_v<)_V1h!#Qz7Vz9Z6?y>0Wn2`fWbwHlg~|UPZ%#|Vg$^TWVVz*c z9+~LvpON5r2|+!olP=x7OAWb6ORX?PYz`NgxPJBjCHmj*e;(;ijD5i9_cEq7A}y2H zxu$fED2n1uAXq*DJBC*WckFnF?K^&h=&FZRYZ5L0@e+(^=&)-X@iureL!U$Ua!NVn z&>-CC7zEFWFuaytyd0OYTdcPyeyEnr9cCr*@9b4mhh*QjpnYwWYL*e>V6a?fBs~)A zgbF`DWd9p7rpc(Y61id9S7@f9AMsz0zk?3L##C@?sJLpZYCB$9I)<FfP>OUu9J(9*oD$=xNE53jRkCVBR+5Hemu$D4ejAQ~6AP!YTG z1Nkzy1zX@hHs2)BA9IZddMMYO38Spl3Q7DZ=bVoTVuZk9 zNH;fDL>7sQ@~bk>UW%F|(Gkb_5BN)GM91sxi}k*R{gFx|(>SJ^ga-8-q%^$m{S@PO zrK=sbYT39^VFV>X|5|q&8am#mb-7%HUFes(3ug5nWEMC-Q=EVZvaj@w)|2zo6)VL2 znTiJAEf!Vi|0WI^Mu-YLU^|R434DD)Vc$T$T54J92kK*i3U5=x36tn)zBw@(vur{$ z;v~KQqpH6VH)@EyCoB(15UzuBF1`l#Dos&)5KNw}Hx$Yin|7F8`)0#zuFVl`tB!mmYCM+0mKfB>Xw|V-^z?PP=FVQSF9<3=lq8D1vhnX{d#J!Kt-2sDV(yG{a9X6% zpZ4#CzM@0zJR?)Oc@ev5MP*a)8{;D}*VNRn;})X-di!)63<}{3wWtNYbo_&T9;k($ z8!YfAKEmrD`!A|Zm5r```C`-OBB~XHo9yzxhvsD+g!@5n3>)6Vmm3jYQq-D+@dWIs zqC;Q++3#-FsTe!E&9QI-4N9RfC`sr2->;(~6ll}YowSi;NObwSO$O+<``9CSa;QC) z2e>nP71>26+~iE+?xG=?we!EUITZi}rROlr5NW zsy1%&e_0p&4TSrXh$La>=X(Q+b*8(Pls2#1P|-&NTrS<*4KJkRht0a!m32{_wjtKq zr5OBwCE#;^f6SU{#@0B>_`r3Wy!o5-`Iz!3(1WKFVy}?nqdSSkLPmCev~=&QO#g=v=kL3#9_pDCAu_w8ySDdm~%!s*kf6gSd2{&xe>5dIKu z{}NVDttd|Hv585iL-|5XHb~!N+6RZ!uwGj7O(9z)2Mn)LV~z<9?9qwgAHj^(M3i_v zKi~0>l^{GoSqT7ozJJvGVY~Bg`njXGfXi z`A2gl-Cml!|Ju@YGITsG)mOsg^JrsKGi-_%^abi{&K!i{@Hd^U#5|N>O=NB%-=AcN zU@O7-CSv}vq@VxXfx`oa#G}-5C0M+$%|~-?v`IcGcq9es z)Lgr)@l;1M1j&J@i)rV|Op-Fe(qcpx`H`d;7vsSivr(@7E?)bw2n_dMg+@&derd2H zDzA&W7L(+}z5V?flYp;o4s7={*4OT`g=>bqo8#S`Wo?R~uSe1Yoq=@ehi{dmn$l+} zE@&(hRaE84u(%-@^6lk+w;ahRMh10^wLy7#aD(xxR z?#Ow9K>`vCf_z4dbI$Jyg&6IBQZHH;42m~q%p=iJtdgpRZ0$~lhDGAVFd4@XRoZ^C zPdm8ZSJa&5g~mcWTv+d>SYKpa)PH!p!@4oKvy6pEfTkb5IEz$$HO*c?A|buZy4iPN zgv6)AQwPY6bL-_*&K(>X1;;;9Zs1lrV$C6T$6P)Dt5Yz)iqE=Va0>b8WPdf+LPYnN z#`%>07CwTANhQWYNnBj~OTs4seTa~l@2SVYJ!BpkY~P)0J96s?x^@Q&&5?U&xqOla zYbaIElKE0k^ihBU_rkfc)M!SB`mH#v8FqGx>!=>5TtuUFzByd?ScGA95ubHoQnc#z z$O^7$8yyx1iWG)4=ZQk`CFwuAF7I_0HjMh8 zLr?n}%c9?s)JyD@Fk6U}fN7jnB^xK6ROH${)78P8>Kgkw-^$LqV(YQey&wClmG4d+ zL*(C<5c9O>RS(Bxib5?&{DSghzFPJq@!2ONa5vd%8yU?a%39C8T4OS_Pf4-_IjabG z!qhcmPU1sNhSM;Y%M~6Vqo6l7r|X@cyPT^kC33HBdHE6lpfYGaz^|7Iu8&e`#2;LQ z&6Y$>Aa<{EUCRU^rY3;H*3hLY{^)GB}Nx<^urG_*COdzmF? zhED2_eUK>LHV75d*~;UTP?7~i;4K42(~1a&{GW8>718aW7^mZ)uc9F-vh(LTZCTu( zg&(|T-Xd0xr^#9PG+JVCk!9TKOCuE}VEHJ`-+<1Fhxc-RYfyfxgjQ0q*2Zvw=3SVW zRlD!HN#3&xQjsRt^-)S#lrr5Kv$V3fel}UVKDXQE4Ib=p|I{0>3W{d$zEqL;m9rfo zy>Jfvn1J`CQ5P=qL+~#-M-#I3#`3BCjV#+L4mpf%H$fAdjHWQ~i9G7kKNZXW3WPgd zSaBl3)gltBvP<2|pmHNkMYICnmQJxI*fd3FFEfn8s{sV3X7w`1JM6mH%v`kUTS5xz zdcmYBX?(2en$OK1KTf9a`f`FD0cGilmNtyzr!LYi(s`vZTuxaH+t*BOJsFUt2_JSjVTZwBhmkk=?8+J~nm;BY`-)|P8$NW_pGUs`xYAtR@|V0sO$aiA zPO0J#&Wd6RuWF1|W}>E`uQvD3Dt6x>Ob3WRlHWBOPjslYTu9c%yheR$AG8qV5BJ1T zhsoiNT|ZDxsy(=E-T8Dpw}%OxYAeZO`}4aj0Cb;Jl$CqjV=@FMmlW@Xc||5svWEDl z-W)OV_!9K)$KjTksX*OWM*~)$+T3QiPqdqy~E@)W}C(!R4!IZ~%w4041`N z6Hb3Jp1)K91!y|r5zXb^I2Se^4F`1I%R8cYj5My9eJMh<2siu|T~d*aUXjCT0THkL z@zp>_B^!))%u*?qdm5oSu_TV6B@Fs`Dk*Cr%C{OyDq;ISzHbQ8TdPlnw- zs&0}fem*;#6SM6}Wvb67O4UNo$`h;DM@!K($E{}Xt)ETL8 z74!pyV5JNhvig4j@f$3QH}_PrXaP zvAQk!;?^xh9d~xHAsV5RF`m}-F!7&xX*=l+VE9sfRT~r03@NpM)7K*uhEK(0_HujG zR_Bkr^`j8E$sv81`tr#>mIeDvB4_jd;Gwg#bL0A%b8WHAhM`vXs-bybim}3G^my^} z2Pt}?qRgK6JZW%wukQdF+K(kQiH=voZSqHnV-!KhBjmgRF>o$%4ZLmBe{=;&MZrzV zB4SFVZ!nr67H>Q^q$=jK>A9Rz3wzHcM{N$lfJv2L=Mo>lB*Suhk|eZ7GpbFY6rCN+ zjxyOMMU9U>Mw~UeZ;6t9(jT@mA%*NGaW{Y-}-VbyUN_~?JLYQJMWO3Who z#C~RCy?IQ}w@=Py}`~n5Ut`ki7ZQhQOn{jCRq1yWKFg(>ZyY5VBco3`BsxE<`QVOFGK?kCqx_@4L?= zILR<1GmpkLx+?41V?2D^5=T|m_# zXg-Y7H@omG@^M2<*2kHV;l?$k1k!$BQrs4(@jva)KqPyu_dbJb6w zz#D_J_0(z0cB;n5nCCTX*np>(-vsxOiArB)*w>vZ#$leCT38Qcv0h1*5+vy@^q9ru{%>X&Z~Xy$pliZl0v@TH7$msvjkWi8Dn_Ekczu;$tmBi8I63M~ZZrz+&%*RaaS%*orTpM%YRhV^3QkIl~kn{Ssbalt5%vwu%K_|)KztmPZ?p(Wgz?$>u)Sxvjj0K^}q zy$iU)Ihv~w)YvQZg)%zQ-vDNXqn7oVS^8{@u-bAjoPtNedZHr7_9Q5b3lVVT8ubA8 zNpnq2eim8mhz0s+raGqT_dBwmLAp12jFlQ*IuQL)SuAsLJ^!hf-(;|q!4n}7H4k#% z?+^QnW#VJ52h#$iMFYV_Pyc-RpJtAL0v&H@k|hXli36M6^zC>JV(=2hXOXXgR(Ep* zCzX)J4^LdyM>kgY`ovn>C~Q^kM<6BBg@f|-LIiKJzIM`jY~`{xTu|?pWKO9iE*1@H z@33fiyQjMSgRs}IEYQrYxm03=Sqj$0<7%8w z9q`t8`8_Q+`ZpVVrG`>!uTt`FZ&eVAtby`ngkcwy|LQiY`p-;ovsD1ZV6y7CH${jq z*444(YmUwiyO`70PwL89eI5E$^AnmT->&!X!Ay7N+s`U1D}St=9e>J}kB-AE%z1D3 zvej0DY^^xVCZ}F~tJ@FKc>}1`>HHw1?Vb*Qh7<^nlY+1{O8G6?=opfo+;>xG{l(&{ z_oVcKb)sEYJYx5<+%_gf+>y}u)3H-WAcNZFW?%?FL7CQoJkY>W%O6N36Kt<2Bo)q3@LHHL-tA5hw zE@HD*FNzzb5LwlVgze*FM}#QA`*PQCZ*WjXMMpbF`2IKyzsa|0>uzw+!jsZd5_N?! z!w%m(bTn=Cn9umi8W?#5R@%Tt^e;2d!6}4|1}M-zCoypX?GOZSdS% z;u&p-JnTv=lir$bUbZ;<$j0=70YZt|?JR<72LqwuQmUN%4c@fZuP5LfJ@S3!PFP>N zKv7^(9GyGXc#*olAz}Yf!ZaTyU1D|~st%xk*+|{0ov448uo~3T*rL7N-G&vPCwZe3 zXP*plkCO_1_y7W$(Gq-(rN=gk+-r+e@9{dt6-4$ee+}*ed$I6;rW=by{qSx!&2GUe z>*Ml((49gP!#spu1ksbF?$zXA>en__veFfZ&w_2ZN{ET zm^60FuGtv&r&-+AscL!c_C@(@Daqb0e(o3`e}eO7{jx8)C0(|v5{k4^;i^}XX`imm zG`id0>Uv~w>BfyqkjHFZ8rET(gBL$Q8GZEmnOaZ+V|vP}rYX?&mXhWXV_w>0UF%}~u;=PKLM9mACKeYmI zu-FWq?C?b;F&gcYC=VRJ`Ra?;gfn)>pvBws0BpQU)Z8`h{wLo-o26gkObJnd63Ee6 zy;6p)RpPrwz;X#EEa?wK$cb~PbD$?PYK{GqR5(RU`c~EP%wvEZRbcD@fMWdNSpCD56eo} z*Oan8>T~0yBe@=8u^Bd0^^F<(`Q*f1dd*`uU1y#g`QjXJxY9no)b^RIv)=`6--eH^ zPF5O(Jk5eY4h!@yMDx6ZSihG_Ac~HcO#!PeQRcmMdOtL$N;xVuYI@$@lMAF4O<^%j zt4Pj5ybjhTyz1)6ZoL5t*^EX6wX=Q0 zW6d?&5743pK(O4xtMk?0LRry!-dI$aw1-~z>h&p#6xHmAplTfIk=PpV*uC4nqUL^& zV2oE}&dlvpX3H+F5*vd|eLfAq?NMv+PgVaf)*7e`zm!j>AS@Y0?RKl3$ZjB~gzBVp zLBzZ_IalNU4CiIpN>QJa?pK3WkwhKWF-)&Juu3bVTkQY@gGqotl#}cyt1O$BfEvTb zs`}m};O#30*$B&_9Fcor9UW)sq>hs5g}ls7QbTJ$iaPv~xh)5A5mu${KO(={Yp#9p zq_$HNtfcVaRGU2#r+tM2g6u|lgWo^^ST^?qF6fFeqZk&K{Oti!=D~Y-+4zF5s$UO6 z1zU?87dp1CQVF^gur+sw5??_$VaMd5(saDa)AU}JW}Zq9Pjk#2m3o&)4DW9kdzT-+ zMO+FlCk+q(A^)6z#a`eC=V-vudt9njcjUA)`%Sei<bH&Wu+)s7H(*no=WtfF=v&Ul5 zt+wg+_|!ZEe2rPAXSce#LS%14=A*!l*EQK{QT!I*0>OYSOEb2USEHhbtjUR2?IZ(J zsWIiMc~7G2Gh&@<)>pOqf-_Vw-vP6^+`3BD(KzH%!Mbv2tDgn3d_*Rl(@|#@0y@^3_ zRWGfNSG}UZ;h-5=9jg4QRqqnxRDVXla++xKv(5%}Ur8aiZ%1Qc91RxXs7!rF$gE0d zrIQKtfewY51#gnGS*z8$KuF%+I>CkIb> zMMRn{4Aq(NWwBypX~_W94nK*>3~KDLp7d_W?HOa{w15979~z+5ueSfFZ^jdpRi3V-|jF5r8)Q)eJHkxspJse7$nsQ$&<(VINDgK9Gz(Az}= znbmEQJ^n`o&o84^`h`R7%0DZmL&tM#U=d0h^-T?)@Xc*{W{sxBT?ZQ1yu{TLaXm+# zVXfo(yc9S6kQsXswzOixWVjyCVFM?%Jb!W+p5_LfV0@}XD1ThGrICtC?-zE1ns16I z?Jc+WNABPw_C)Sh42m@`tL8bCK)DB#+^`+N3>oJT0WE z#v*QW@6V#!W9BmesXyjsV1ZQK^_j_0j5o^Tk-fR@w-{0W=%eo@hn&xqsn~NzB$@lY zmtz8<=Ai@20WVa!vD&VJHs+2qYd+TRz8fpeACt$N`G6AX{=P3qN?}UtVIZcUy&zqs zd7sLV)-h~%eWFOWOu#(Zv4a;yY~KTx0Ap!=U#^gDxyPGJJu7+3=(4d zvhRL?b&rp76<__3sO4<3(pz9r(OaJJ<4#ZR0@ft|=He z8O*?j^DLOflBk@j!HTWd?@nj71lV>22Ee~r7kN_IOpwJ!Z3Lsh*$Km z_^NV6IL^SMNf*m&qnYJTBJ=gUiSAWAMg{@!BP%{U;kJFh&qswT#(Pw&&^P(8!B=7M z)0|k~-WZ8{^6o5!1VyGq`g_1+OB}uuWBuk?^bG0mLX~gUxJuf;@+hG6l0FU}rR{Kw zWp}B--$-9CsKA-wd+^r3)hcgG62-HmB;J+~R5vLdTasqFZ7L-l+Lmf*>tw<@PL@G*abFugKN&B#Z8+- z>5J-2sLE$QRLGl=>Ygh5bh15mM4dsiU;Qx&BZb| zF0)9TA!xe%3bT#Uw`osxn0v`$%kTWe{U9(M(9fuYUH!e*Kv{S|lxEECL*&&q(?>cWWb$~fkk|J#9Wz1Dq&brS}^T6I&2zAZVekMok5@%{WOU$td&7#zP$0O*v z7GqSR&%?={C1QPz+*1`k^u#%*7>WCs-707G*kusa)9$seLsL+<_l&yv z8vwSG{V^E=Vph536|dbD%V?sG9#`3wzJ!_@<*!c-4GkHOnJIJ;8$AwLd^qtqwhbk_ zNk064vRkd?9?)0q3ZaxXns@F;5%dSYep+okW+s2^DG@pl-D0@1aWDTWPfmWuw(g5g zPWhF7B`mPB*2g+eR&(Mp7r%bp*GXGIAfuUDzi^13e^+0_N6th!qp1 z?|Zn+kEKNcur~Ht>eK(%K&~9MNZ2lqndN-MVSQYxadz+0D+U#-4GzE3Qks0@*7HI- z$!Baa(y4l{Kz<0I^1}?eHgyk~+p9aURS_3w|Hg7Jbu8%WqqLtTcS9=8G&K4_iFAqf zy%!zl%{k8iVCZD=kh1H$j36#uQ5n0K6h_uZbcR^h!5987)n!byG7 zM|kjo?GQ}JgXVK@|1P-z{_wbMYIQZA8R@xozm#-mX$MNXk+X)vgqrhWXRMg!>$66; z4MF4e;8OSZ{1R`iQN8#jr6kq(s8oRgqq!ISovK5g*X)5zoc4&_YG~1i6veRye6kC7 zWIxZi&uuh;>FISahO_^=xOnzu)WDwoBw?*e<}BFRRn&NJUPeI+hvnh)h%;W6S=S%^8mFjSmgaf5ubZa@`B3IG0gxw17gFd&N9Vbcn zLk#`*nY|UJU8MpZ+Yby5$Twe(tXR3bj=0Om&e1R~K)HR*=-I0Zep6GG5lHvXa(Lgl2$k8 zAaR_==P95YyO8sF?w8`Z^ja0=+klQ@XpiSu<**MpTP2jRt2KzpZ|bxzswH^7yox~w zNDBoa2mL>K>lV;kANt&>EPm4yv*sD^{7|KAeM=6H&5i%KH&vuD$j!x9P9bR0=g0Sy zsa)kG`mUe6)k7J@TOZL`k!I=3a^;}9FKYnHGwTg6jZXkSJ2U**M`gc%LA!z=gjAi%p0AA*xj$sr z$H1c|$S1}KyTQ5H=)By^s&zz^sB&=#kL|DY$vmZr&AyCtZLrU+u2tJ7Ihl5W2oFOX zm7T=5Q1>qWS|MT^oFg^K0zX*2tj68bWQ^Qtwz-?!YDbYog5bH6`tduYNGMPM{TcwD zx|ss_R6Z6;ZHcw)RQ-D-XzvU)kgX~lt+P#zi!*B^TcA~AK`*gRV1+8BPU&mW_~7LA zPMu_)Yp$>}~CDz?=D*&D4A}LqxcH6uG9CGLDvE5kLC+uDKhGnK_{l zEcpBS*w*na~ImG?25I*flqM z={w>`RNfZYR4+rD)P2&59q!Un0il{%nu?I}ca`!Fh72Fq;$NUV4o0e1Y7lS9@UTKL zsc=cz^4&haMGREbHD&;>kYDT9C`C~XN=gVz@=vdWWRC`SyLyCGjrYO#jVZpdJ2~%J z6%mf|v`kFPpX1mKoHR8x_ms)km}P(<(={cZL-hP@UYf7hS}=_-zdnsQUy+#8ML6GV zUEhrGL1e=xP*h)Uz9A?*WZ6_5zUIXd$SoBF#|EoaqlL6xm zGD>pEc3J7qDB!(UNU~V?$_L~6%Zi-N1)_Mt-QdKJ*;~*w6{|28q*$X`{d3_A?#2 z>+U+N@d~3@w8u=JV7hP*%X{9N%ub0MVp^o+wU%o;gMbAz84rH3_bFZIIR+=7D~Y|paN6wQhvwd%ZOuq;Coze1Weiuq=* zwxi?&0Bk=89$U+ci>}&Yt12Zt`X-h%$5T#{t?^26Qkhx$rTYuRx+fZ7nDmsM0C|lg zALBXXcV9#J+Fx+bZ1MZ^#}dSoo=TpgjP-MKC*n8*Taz)|dgIMvV27nOB9>$`Y$^g# zIv0+*q6KM2L{L5qHAyg^^scp=Nwh=;CyL*Ykix3Nq7?SnHrVh^c?77#5VTm@@MT>f z{3=2J=DwjRkD!FMC-m;!JyoEd39psLooMX&BME#NkuQ%T zSW&YciN7>N_*cjc`N zv$s%9H@Ly|R~khA5@2$B_&~80_ww@6HywRlK@{*76sk(o@b4w9)%o@;XGplvfI(3? zsq%{_s;u*2C}+kRip_|4A8i-tUptBbZ2QK6eR5pBv9|HDszRyz>3iW)t%mY7Nn5PD zBFLyf(1SD94{#IxI%->3`9rf>^=IOQmU$v-Io%cSh)Ze<@7l*@25lDPrLJ+9u4uue zYmFS+NpLB+Ew)QgvRtfuIvWVD1XOxxNtv#2&Y@>WMTotbYh7s~MDp{eR}3G;fJ{1L zsu!kjt*pLQMUj&)`4qfw>f4+4O#_PS=oe}}1((;ByOa4H=N;YIy=hX+KefIFF}ALh zX_nnh=oGjvA((mVI-m#gE|r!nzxd%RA~o4FibWHhtIG6!B~thXi_QUpTU&y3C>*N+ zg<@y-hdQt}UAXPE-|(A9F)&jiEE&4Bd(RWwSAdLC_)~J zMj|W7`T4Pk832hT!{_)%?tXx=mR$R{=YjsaVLGKvfWI(P-s(_ZZItWEhYBl}6)^fa z)hW?m6a@V(0WL5SN!xZdjj;Dud6q!OY>Uuxy3^Z_Y+sg-B}^I9Ju+ zT=k0NK|{nJ0H5WJm8_0ftDay{uTExltrvuR}1#ecDjgWjKcS{B$>`atAzLrh`k5mOH0{$5&)#QtK?i? zl`n4h{@X}5KV@P!llLNtaGSDK}R%R=lJN6Z5y}5UF?WXtNmUuV%T&r&-A^Qd%C2+;TRm`arSyXQYUTw z1HsUB5pmR{uK%VYxGeS;5JGgz9XT5($B|o=|Z!njxwN$5M zvH%6__mz2O7f~BuOn}mk*PoxLCUG(|=Z^wGZRx~NH!PM{EwYWCHmFm6!>(B|w3jHN zIv*yU^BAV}EKy@v|63WEG%WF6E4n_>9E6nPzDJ0t-BmT#bAHRg>>JZ1>S^8ky0r?_ zFNYn2gB?=J>RO{u_0P%}=&~8CFo1fH=+75>>le!*AV+s?(v11Qh_r_eB&P*ix(mS;7WilNR>F{qVeFW3xSqlJ;7u-aq_W0@E!{$_L zlqiY=rgJFxm}J&jQxzeM_a}yFR}r0Yh!{s+v1Yg8enX}_JqKYA6T|R|&t?O1qra%r z{rro?;Ofy8E_c>p-AcVHhYG&Xf-m^jzD%-xx?ro=@Yx~PSXoZ1S)>m2^-)yXMRe_ z;9b|0An(Q08TMtK8xWDjmX^}VSqLH3A zW7*-<9zB=iqO(0kO+dsBLlb`m`tu!h*KBJR#UwA+c*dwz-JFr`TvNR(Kl0Wd+|cvy z1$?YJ*HbhT{iIxxv)RQLWj~3DLq8{YPV$#Sro`@-K4WCPFbYJ3MOe9p-`Xo-h?BE( zq{5v<;P5f05E;!xI$u~?&R@S*ZXz9gus#;4)w(eQOf_?O)WSz^8e?&Oq@t$fbsr>} zW($s@N9+xVQDLS7rNYr;D4*+(Qn7q|f6>G`*ey)B)?dJzeeTto7U$u$6kyG(-ffis zYg0MMzELcyReaoq6TO^zX`h;Jw+EvbRj~TyL!xg=^ZX*@ z+t2(3yIo_3nxl;6=u^zJ^>fa1{0G+LZj|^POgs1S47l`Osp>GS1lBD-JK)Z6kB=ks z!)hZ$k5@6{`SrU1fI)K2OeYh?bi_9%^N35VhL#$EzgsClr?Ra>JY56JVsgXLwxOyK z90upR#wKd-L#v!^n0Hn2Vh1Z6!V0oGdKklk?@(%&Qk- zYg-oy^~*YOz92$H7#kH~r>y*2e?*w+SYnY&aZq%38e{2=ZVS;&$}*^OhuRZ|+_sbZ zAZ7In5$*#ris;Voh%oL*p>6v8w|?z7_@$QO8?> zR2zUOmM$@=X~}QZ7+%&baLomGe$%}%CMG6af!`ww_&xZBUIYqtMAEd*rYM}1cI;M? zi%ZTte0ZNziy}#*l@++BLLP#y;?dEP8qY5Ytcfl?q8w&H9d&w-u;jdtwe!gf!S1=0 zdn-$QX~wz=34 zbkySdf^D&}^wT+uv=ErnGXUnLnlDjQ$}lSeaDf37>eIfbn70TJDEq`WFrB)eR+`_i!kV@ABwvk&}pdE8=}VtsCnAE8(X3p^Y`$hDqdswnL&cK+RI zW7`BeZ0oAQe%Bl71de&=`1x{o3{efinhH}=lYeq2<7MnL)|`|-yGN{n)a-!jg} z2&y8p_2;7nnt5KuH6dP5n*V2>#bVcbX2PE6-HNTBd=FA%JLT31Sej$NtT>N`hDPou z;P|*=aqv;UaKxE0{z<>r4=lUNr!}50Z|G@pfs}~#zQp|NVhCb|Ka9DA7IXZv@U(auxb*8Z65Ss?qsF8RDuV_j^OeQuT6it zc(aEUgR8PP1{W!N|750~mrB}OeeRttK6YRVL^-|Pf&W%i%jeB1xTE2vaWvnU6l>5At zxTI6Qc!Q}Ea89d44_XxFT2WKqe(=`2q{yTH*COex4)}6_D|)X2zhtJx=SS|&u*_N_ z054#iwG7=jA08g|P7>sVy@Bn4o$s^vkGpjR0nD=%$Rzs~0gbH!$&-r~>u=-bLNn~T zH01#R!+PC=gB;J|2483!Z-=2!0uyLB;fN$S$uG`>LWzc4NVRL0?`P!*bm!yyEoM|F zuZRkrimVz=BVCdit?Pq8qvAdGbD0bTFC>QjCcVKev1$&(2JSJl8zb{2CBu9ISfBK( zIzjeU>^F*(y4vGX=2+-ihf$D^-cXL1yHcXWkD+bsz0Z3lRm>SP1I+}<=gn3slOJBDr#rIh4R<*Y3xpWZ;nmjBoHDy z^o95a3!cY`;A5yWIDl&v44}&$xBfYO^yyR|B@L%=<$4BRyne6JOu6F zO@Yu__&$Fw^h}H24ci8IX=;J-d^(Bab$dQgNO{Jtl$xv)n6Ohc9!4jMrwe1qMo<>y zR?A$m!VVYJUq9mmV#86bQ25C!GuX+SuV(V0Lc(q9S)mu!$gDM*Ne#t1GB7FO?yx5q z`E|vV_BOh!NeRuPB<6|9)PqYOciY@UoX9hJH$<6gFXNI9Pl1aE#CWN#Lw}EXF@;_V zI`DU}{~S(*{xzH$scKsT48EtIqTvN>{(C8tZhH=`K%sJc1?VtKf2df~ZGQ=-sWEK! zI*>b{60;pGo{$8t@#^rXP=O#r+DOkRw|0#8jYnls;p%ga+8#)GZFR`XTPSotJ4p5&CM<|e;wCt(b{BFckPqG!9qlg~I()CnVnDmT zzJ6{%cB8Qxd+3QB;hOPi>|7e-BUEij%E{MDKbP^5ucU2nrv=z`$3rup@K-rQVCPp_ z4JG=ry=DnnqIg!udZE77W;a&e@3TK3%OiSzw2n+DX`^W(`0VraZbepzjSnoMH0|8xLFZ<K#DFAjgN}|8)G%ew= zHfv4QRc7Eu&>)XbYPl5U+~MQW69E2B)g2FvXsy*3O#XHOAz!?xk)+MQ`Zm|v`h74* zv21|i!^ZGjQf9S`qLQ<2>(FRdDqa0#K*v<#Ud{B72uoQY;b_1ql3oeJ>^Q*A<<$I!Pfw=2?qq;LdR<9VqI7(dZoM;WX} zZ&eb4ODoFQR%4<$7TQU?oQkVvC-4V1HNh>Zcu3Vv*YiT{qKYbNyB6XsCZERssd6=P z3Ja91v#_h9X^9mh|G9^6PS^(s{bR7f%)5QUdm)v*g6nlch?A#dom=uDH+L5(CccIba!8z+IoQ&cOlnl+t*+t{SD7F*Oh`0_RNZOYH|D$NdbKORK@kZtiD z(bi?xOwKIWA1K5+mPpS;neKR4Q4V2nRSZaG6krH%2b@+UhT5G0{>$LEE{GMlUUpwS z_QSAN@7sx@gUm;%`v$KQnLXW66_WdqG-q?F6(wxf_$!>m0`i z{D;%d=4rkstHw`sD9FWWpP{ZX9i;L4fl_K!6Oo_WBfG~Sef4@K3la`r$Dy7Cn(5DC zY`)fH&w^?vwlAfJ6F6KSuP{{%sGaq)4s2#Pm~Gt4O|m=bB*_UqDab?Gw|vELzn3sJ zy4eLz4cMps;cdxy2T@lb1 z+JAR)uwF*Z_4pI6#yRmO^8!t?o1FS43p5%giR53XvI+Y(n

lfk)MO4qiMUJjH~la?pZ|^FK?H)B#-s&XTy7`NwA$JnZa_JGImwObmE1pD#v{ zRERJtV`Zahwl`NO>Tu}<%)2AS!iGz?ZT>!lHPZZ2~>as7Tg&8ujhlW zD+-%fcEK=5iP?<+ZyZHP7eU2cpOQW73ps^_)kx?_XvA%2}S>RrWNvTq$aazp2T+J zd&h~*>g(ERtD@T-3C<6L0^RBq=9mj=Q;=;+1P^!`CxrF?Zqufwwxz9@=VMcp*K*BP z_ai28Tv)>fo+gQVxj);699p*=NMRyW32YCOa0SkzkEFPcs>ie00!Du)dPs4k4RrrnBzx;7v?(_`**4pW=XrqG7W5;t3((!9G4h=n#F`b@m0LV zG0MfhGIy;n_6^hRvQ#Hc_3l%X=}H zTn2NF*Enh*Ia*l~)Iv^+e;(?36lH5AudxY}Xe5_0-{zS~#q)L)pi zY?n1&AUL-+99P^BcT0<=a(3d@OSk7=x*3n)#l~+Eb5xP^%1UP9K)IFXzN{4|D)b1uNq}BCLfv#r zKuqu;k9xj=i(HE0?5-a{4%LSBP0EFtNF5*7*vR*Ifb&KW(YF2zjNsjpOliD*Hj!?Q zLg-m;eT7V}3P;-`C*x}82Zf+a8_!=*28d(R8K!b15S0q8KHlHFWyYix8LHf&nj$=8 zzZOm!GbJxA5=Pw8*48!xaDEX&2xEZ|HsdllPeDPX;C_TAAd@&Y<#!EpcIvgt2CUv? zC!dervuncM3bEsx4-~=NT8`OM^cwf%;kz{;I=jfYkdixkyf6G%iPf9Cb|@y8DiSs8 zST9bPCl``xJ>zy3T@(TWyR+nv8)7CPvb(XcK)sfzoem4Qhc`JhlZI7Y*LN?b0{)Nid@hl%WFl(p$wY+7@Y^MW4gW)V zVoQaa?%z@*?^fXSWybI$>Fb7_Pk5?sT4191TxM-{7Um)Yk=QoPev@$BGajQpZmWaN7ys0uFNkb^zSaajNxfV$TD?Dp$P!5Cpb zGq-6Eg`1or+?6_T`CwRA70)1K{yWx6wUJTN zwsKjK2YK@qiL(w&TLs0Q{9i<4*e}B)R*&-k?G?ULeBfnWEUs#=ZgO8>CpGdtAEH`0N${V%3dNjG@J%0?8@%dg_GG?Bwd#Uy^K!#M zmG}l$i=t)44~V!rAEa{aZHyZg+{bZDjYFpJF9fim|3&G*NMgVqAhy1&0CXmuIsp!w zY?Mu3_9!gq$gOs7qlf=6n-ZPDV-)baLxw=L`r+0OZx<>jaL*aYV?hv0Pe^0)^UKl%uzYjV&x zn5Aizrv?dT{h*%3BHFit0CT zqE>GO+rmnIvdbd=8$*GDY<`pKFW6y~%BgL7V)Q zHJJMO-HZUTzP@-U&0xw)TA@2{WKzsR*<|~Ado@RZvb^*JV&pao0OaR2fFO&4PXt*8 z41*jEjauKtT;fXO;H8azgIYH!I{0vo=e)-FrftW-dxyP0zgOPt=N)>5?xjW>tq_EL z9}XvA&W|$wpd|2AbVB$6`n>H=N}~9`xswRSC)40KNf)v=q!2wNZi;<4#` zbu)2ZRNVIDEjF1Mu*J<+(4VJ?f);=Sfn0VD*^USA53Ajgv4wVNCMNyF9(%k1X&7xi z1^S|@ww^q!%ObN0X=Z|6_J#6jN}*E{Pq zy(?bDB`o-KX?a)XciDNZWIbj@$L?(QJvpudkT%O#K)uC*Y2sw_uWzo2PE>`RLxKl4 z)d1$&t*);^hmrFDx$?3+dhf?W0vseoT?qaE)zN?~Tr>Dak#2Enq2V)tpupPD<;0Py zRic?Nz;+8G)Vk*bIYj%;gZSeYZJje%|!Sd+|wnN&>*-&YoSJBH=4>fo$Zj*)G z)fMIT$xagp5RZjCq2puLXox#+HB|OWLZQ~EChv`scY5O$EdIzWjUq@>9{h4Mg*tPr z1{nyk64t2q5t*MLhJ?sv0Kvhj=X$s zRXhx^&I|r5ieOms69t3LI$Pt12V3PqgfyMqXW~Vg!Y`K=Jqc&m!J0ZSHGn${va&O* zOKSZrKHN`5fAXK;g%05QqZ4b4ane z(1%2=5~6+jJJzD$SoSuj1B#id*W!FwTpAQD%tsb-RU6VUMs7P)YYz-#Zj%gPeylMw zp<1=Ib;m?UR$(} zCnVEFR2zUpYRO$KEqUWvilig0>1O=kq(6kL+8kmT9g z6L@Hfw%qLO!mVy+npQL9uh=d?Df?;(IrumD_p5g1OBq@i>|-!w5y^&V^xwKJel{MkGfqk4_8Ni5vG#+r)jj0CuaiRJfYKR|j*HYuZc5%RNEQGa03crTd2%&Q`qd zdAy|B-Q^mF{xd>vEL&3m11qn00RU(}arKE@Z?>MKIYm(1o^A}wx3;e>B@roD;N)gZ z)JgxwCT##+<1o0)iryTruk?R7kXZXHOr0Hx9Xs60*F^VC*ar1CbMt9{-o?Res)SwZr{!DG)Km(glLkp=l`_`U?iJOVRq_g9{4tgg>G9rTDb81{s^*T2&tH~@6kUhC$n2ji+cDA;OCrPywHA0)POX+-nD-l3}wamlthL__A6&4p9 z(eDMdTNGSgR_szRFLc-EcZro481f=U07(a0-;biDy6}H>2)p;j@@S1<-x)lfK?;t# zrvZ|*`1s})7E^HGuXovTEvT-0@ zjrV&TWc;3JZkXnl_OefATD5FdaMcSKq+zRrA&-!2X)hHbHTjwCPsaacGoPqQreyTR zFHnUP@@f-z*3*vjB<4qI_6S=;wWHdf{yPB%20NZ@P+qH{J;xF~OaiGN(}b<%srHUwyl?_xNfh z#Hw#&!t8$`E2KqDOFH`w-Ln#-jh$w%u-V&~zf?H*t_76*g}Hk<*6v+1h=-gdfMrqS zr<`zc@K9)EaE$~6MulPimg%vd$IvEvz^Erg~V7wO1g(Ep_c65uN1^C3kOep;u zMu-$o8EFf8=0Q$T%_k^WsVgP*Po04ccHoe6n*YXI@qhSR`#-p*=M}lgCJ(;R@4IpPBmABQbGplZz7@-k@g~9f0RwD)z-OyChx0=+w5@n= zjH*f|fCQ6M;N6J~C-O%0KMeM$d4{jrI}%Ei??2MNuXxwE!niee)2g)TXIlnYM8OE! z;%{sP<|S53o^DIgK2|%9Z}MEci@&hs%ADTh{mxfIxBWl8rlh)h83@@UivYCWD;T?% zB84i2E93uFr69v=jO~lq^mBCdkgjl;$9+?DSMe}e>NL}iut#+1EF_NmVC!_x*1Q1{)-xsM>lm@xWE?Tf%bxKw^ z;U~+SzOff+KU~IkY|QosO}ZV~cLVR!4L>N(`n{IQ2a6;;|2$;a=vuiX^7xIu6Zs=b zW#_nN&(eu&W2I zPGtcM5IMfkD}o2^6UjTEjT=g;-}$SiRjj+BW+?gUGku7ko!7-CI99~q<%yUv=!3(g zRsj5zj7;Z0AAo{}M^GjB?J33}sQ$aTyPM1BdY4Pypd-Q?5HC-sgWFaDDE62}Kw&6r zHwFwD-mK6HT6}x&Xj;`icxgfe5u=S#lmFNt$WF_13hUqtyQbC^12yt_rpxfTNCv?u zOQytUu-{F}a&uN@f3Z7KO_>pS>s@DTPWzTHbW$=qKWn`K^gYBjaep3QXMb^$0^(;k zQrK8aY6;nmy^&oqI!rEyKWo)D?a%Fxgx7Vv|7KZELBXKeaqq~rC(I0rMu-~7@MmU#NMI`RLO zIGtasg*1i+6-j*2RLjXAcUH>9BsAxv&tIC>%DrEQnG1rB&~)Y8UOy|v06Kly=I)1v;8ldrP;g?qyXu}2HH}7u!P`@M6y?eum?_AH(93!uDY2H~>OziQbYmsGtw!!IzEszxG zO*W5N>PnU4Gcpf=H?yFhn7W<(WmSmB~rm$qCq*1^(fZ=^Skw<`v2}g!RhBZqY6?UjJ` zPO@>gcTr=PWQH9%bEM+2eiZu+QSrP%i#01hgI|_MVH@%`i+%PNLP55_IUqFo&(Sbz zr@_GuvyN~9%)7Wj%_*BJymqb$hQx!gq)+)Qjvf-SHf=gVP~nJ~>Al_4#G~!3KDzfO z`Y*pTo(_AJ({5T6CIZ5@&8CaGM(=Kgf=>cEjNTEd1le1((VE)cf&1%F)FP-`D<;$a z)2Ub-h)e>wJ5MywB0b6Fvqx<#pZlO(p{hA@ZAm&mE{*q}yN3Fa!v>jYvzZH6$m--* zDD;FQbZqr`MrP78j6G%vSc^>+?$0Oc+pe(?w&T6LsMO=D_Y1ko1d^dP6^_d_P3H$Aw)W9~IitSm z?DK^T*;b@0){@YL!0aQ8fl?prt#xfBmgg0+SlfgpeXY74G3Il&uK#4VRoU|CZBUm^ z!8H^GIgj%i=D|=xj9>h{B_J|~j=4SWvjg|06?UpVioQ1~5^Z|D$RpOmk;e&yS73<3 z-!2CPXU&)}r;5nWZar)nSfd2iPr}rn$%WEDms zY$5hCnq?1|Fqsc5$CAuh#Afj%ZZiB;u2Ua*k39s=c9TF*h*b}7`X?eglt|$Y zF30URv-HYaSNK(*7CCgryGZ~xr*692L7QRrkByTp7cRy{P7AO2OO z^i}Uc-KxsqbBO)M@|x*2tEEVjng+{+;~{Q&i+hBc`1T~r>J=;i)oun7&UHsy+TAmBRx9y;4m;j5(&@$%A{O|C6@bDBe9%?6Z|2IU6l2kkkuN2R3 zadA-?@>$JvcZQ6e`88hj?aYGFQ#PV~s@`i%b)$E$8a3pKHd%cs`QbApLMp@ob04nb z&&G7E-0zM{N#Rp!H@-)odg|Ns$()MJ727H_#2nJY*mP0l-sAKuC|>i+%*-03U-GBJ zc#{>wiTyGE1Qupw=u=V}Jg7hPn7N&6zhUS8gIi}yd}FsxyZ?3dOzq6;oczv)u}7*@ ztMmNlWP4P59{wE&jJ|~H?)UP|D=y)6>JYY!KBJ|n5A{3s^Wri+8D?=63K|(I$lOe& zjkWbHAq$Wfktj5BgeK8ie@4f|QlDg3FU-OcWWR=Af5V*6PnO8)!2>r#V~s13 zgc+=yVWsyJ<0+VZVwC%M{>a&d*{NKCpJ|`#4c^r%_Lu4PK{N*p_WTQq={vUi9FryA4r#_!S%^F|DRq5ot@v5q*k95SyIer-a%?m zr0B)uhQNS$>Ri||fFy0z}zg)dA@MP__NXz}~!x-C)Ej_ADJE6C`7HNGon(gl~7B&pTSe6te?Di$5d_W{W$~ppa-i9k-fdW4PdLeC7-0tM&}=2({2uX z;tvI~C*(PmupvYO#Mn&+jMe**J@ER;C(|KcQ9O4rMP>*wUK5{HudJhqy#M-+9R?j6 znhF;i`JssP8oa$W9DH_1IGi19uzHzkRX?6xsqhHX*fo3BYm4_z3R%?gbkU*#u?@kx zj&mAim6Ly{|9f1qKb9O-sxN}i_=J;;#M<8KzOt@Kw2^(=>~QkIV%lNvyR|5ZgFiv4 z68q~LOAUA6Z75LU6ti06=3TVMvM5u+JKr`!AO>KPvpXu=gK(PX$HfMYg*)7WTW zU|>*6(V9UeF;^1V9vP(FPl>)`X3`P|zoWXwA#>ieJ~NuD_;SEKOx-=Om%LqkR*XEz z>&odbs|RtzQXOI)gc@bJpM+?R<2vkttDF1rwxdGaQI0}AiV|8l@%y ziZyX>=zY=hW|VAY%EjVI;jm1@tYT9zMl9oV)!&qP3AOI)QyjB|V|sDoA$_dv`IN5N z9}W{6Wjw1aS<9=svw@SLa9ct#G_i6Mw>OcyRQHf_QRXQJm%{cqkL#W`x8_f?_x)*3PL7tq!0ZyG z&HCV2A6E6X#;{Z3Mv?NT66r+mTT7XvqpegLWg>AxXZ~GR$;k}+Q338yWL14Man?2( zeTIy?PZEk=Q^&N4g|fDaExakc8pk^PgQIZQvjVvpi6odQl$~pj;A+9hUNoJ|PJBYb z$Rvsro`jMVtP4Iq4#_MWQ%rcHT&MEhT&GfhZWJ$=+@hs-k_pYJ0_o5!hQ(&xg1BCuItie)}gsa<12T5O= zS`?@6kunaQ3+SMy5zy}i3>P5ziSqJtiDVGH^2E-OA-5D#<9{NNUE(A~GxTJ13Y(8k zhlPc$$%kL!O*d1`f{XDkI`ba$ZMVh!{f}L3k=AMdSNsfA#vtv+a40v9(m0 zWz5C_Y41U^xogYnx8|Q^bu!y~xowAOdhmcv7-`DmGv6p9NoebF-#{>mr$v*Op)4Y5 zjZUoFj;d!fyT0B#sfnO26NC9Vv{k=VC!wiZ^Kt3S5Y$wf(v2L!NujsbOwePt!3vr9rq{=JMMOKI*bzERnWb<+p=l=ba{ZJFtL@bEvM(+ z?`DZ~k1^VE3;O}R%!S$wEkm29z4c7Vi(=%t`!sB6S9A_;yLty>>?v*k)&P)UW!%GK z652b1k-fS3yVe;L2Fa0Vfi+b4?QA$K&mf-0}2tsl$YulbpQsil4RF4Z5)tCPj zEIWA`FpK=%obdB=XKrK>of&^MU2#|(g66nhuLtwE;%}CvzD^H0*w?oUU-b7UQkJ^a zHV&G&Wb*PV&mSKG9jc6PCl?fNO0ew4aT1GJ+7<;y1RsC z!X08pnK*t?sWvT}u}_{Ad+%CxuJ6lgv*P)>%DgC6|t{EH74cu}^ajv`TIu0Ay(;_+#2wR)nqdq?vf2vZXwe3I~ z+7!Y%bi85RiMu~O!C0Fc59DU0-}lg-_L-I1w{snW>FCxW=*Dzb?G8Zg-{1<)u?It5 zuj~N*FGtlr&2uv&&QJ}=!^gl+F3Gz7wEXwKyu?Ym!$xdol}&y+8(!fkGn7_u)ujKq z>QI(PFZF$IhzXS9}gV{Fg5}JoxgfVmX}4`X+C^ z)r{y(1cwi51SO;1+Ac7uXGc#~&ed;L6%qdk-($BznX zNduzpj~mW9lQ{aA)2rf?xi_fyLKn42WHaxZV$GFSG+nE^kb4%kz*^7yO?vwGUp;(3 z!O$pL__#P-Ym(K-ZLehrHK^Rq&(B|-pP!Gxy4`Ap#iqgM2T1=7_?#s~aLqesvKU~a zbkC+Cl^{{Kht@1yY?9Ld_3INkRx$%;V1|YQ6g0wy?faGT5;`J;yW6Q{drY2ASRU;{ zB3oSdbn=4Ju5I=)*+1R>?kJNC%}?#H>_G;ZBYu4Qf0EveBO2UZ<7-jRm=t$V=t;35#cveA%pD zQe)5}cNpOgQ@m?_4F?;=GHKw=#W6fQY@(e!%iW>w5Zf)sW!-L^9l+DBlu5AukmX`T z@%dY7cvByj8tm)u zK4P%?$eD9iLN10HEeBcWN!hT+p}{BN5uXut3uT(|kFDbBY|X)1@pL9$pYg4kw;mtz z7!0y-ZMRJgzRCrK+K11uHDH~Hv~k_<48OmwY<^NpJ18yxTRWrYjq3KnFRL;F_dCS~ zm{jl0=7Trl?sOj35=40d~*TH8b~IU0N|~J#6%5>GapH*;Zhv*(a^Z_-cWPOIrPOl8tT5a30#O zZX)hi^kRy}nd+}nWJ|b2K}W<5?N_KI`H4R?C2wz$^_!=))hXVa^&eYZSXkg0(7Sn< zU7RYB3T3y}*u)})-2+CX_n8Q;uIX4fbnA3%rq<1**rxIsz$=DTYasp#%KcQ}Z&t!C za#`08H)~h2QYx+)3j9I}LdkD9GS+yriLHz6*LY}oPWV2skGTlG|c{4hi6 z=gbI+Tqd&-A1_u`qrI6coP=wby5tqylZi_7y`RIQiJfhD@TCWbGIM_#(ZkeLid&yF zD9h{kac#`wOHCB(Jky8cv2awX@6~_-^jLM9VZydH=Vt#Z_fQIn?8r9)R^jzq=!ntV z`uf|3=%53=3or8~mLDNsaZmoZo-j#br3@i(K>(2K>})jPt_w2_N#BX#)VShaxNu+ zYk{%xG8G#P+RN4DAzVYJAmArB_9SyLgeCR;trbhJb*b6DP)e_kh1lU|mK=83U+(9x zy#4ib00$rczcc*(Lc(~v`AklWPuL$L&fS-&p1j|7FSw0`6(4L_Vd8Z`MO2;xg`|3@ zXO*Uu`v6Yi{Ktsvga?jCJ#<3WdM7pJ&aPW){=o5*D&V@e43#dP9`Y)|km>w%iMKHeI*@SP1{Bbo=ECWE^|_T;q17cAQ{rHE z$9i!iyR!lR30i|xvcpWC%q5D+y0l{p<_?`f7V$b%Z%go2EwESavXW+D_Jegf<#~B| zT=c=imoo4AVXM0h?>lF%5NoQ!p6Lzu9X5(rgT5ITJs?=%^ zp@$B;Qa9kpNfJY~SkBth@=0mHWo-V12zantyQIw+i>T{TTGD-2L;A!sgTm}hY zP9FYgmN3cKDiu6?_N;iroqwLDm{4F-YmFY5%8+fu+&zW@JXItK-;z#!KReXQ=Dg0r zzH5!2cEO&e9`HqN_M`~{m%9Z?UV=}+?8<6u zT>>ex4b6WaO;M7NE3CR&|8dwGhtOBwik&35c-L*lRuee&og%NkPwN+YdIW}Q|P&urnwUb#^i;s_$=Dwj#4d@*Rzqd^RmGPpR8l1g?Sw- zanuyAhx(#=u5WytD(R_fqZOCf2`WkC;a%rhUW5{obMfctp+Mw3r(Po!4jyg_0f!f}9upaLaj zWMmxE(uKm(jy^oP9>w_VcHU#tIOF)A1_zQ;rd(3al_P{5oTk}{Q!DDUdJQmQ`sjJ} z7s2YNQm_WgV!-nV;~^8_Feao44YbUPVhY! zMF));=;&;GS{y3X&41oAEf(Yjf8h_RRs$2+az_J0%*#(DFmG#v7x8L%*kCvPBN9q! z=TJLaE2i&ZQs=%`Ixk(Bit+5nE!HhP%;N^9l@YH7%TN6GH=8RN8uzciOiV-${WvnJv5C{Bwp{eGX~dB zZcc#V=hE&B039;(+!B@_0`SL$_t*OdtBx0d2FD>Tk0H1zl%)S1CqAJU&{%D~Q78cj z=T8+RV~=X?!~iIY8I${FVeWxFv;(ARN6+|F607@5mP|7BXa}Bv#ow%brx>@K z5T6s>GQvJWFXI4(^~h5D>QuXYfs~`e-Me>V0myj_Qoe&te_L3$2a14{88E4c{yK}f zF;d%S=M5aIPUzJx6=hoOv#_j;N7t1u!HpF@CMKy7T<)?1_dfurM#^24i7t!@=b~&; zj_8AY^a`JdjnXpR90{-|aC;z{M{2h@4Gs0k$JB3?C;{*xQLTLApWCBTGs<{Xk6}hn z;w5;zTwk6*(6dCDMwEuDo!vNZ*oWRfUfFmUduim?y=l`G$CVK85nn3}38M?15Nw{x z($0T|tBNN$j>6%eWZzFs(V~0Ni&ypUhSnKptR8AToyDo7f&TW5hU{14&{Wn$u(4?a z1b^B27-TWU9b?syCvuSwk)xNDNz!Ahfy$`3`t?BGuIG+)#(nrcckuc7`4_>`xLq93 zpfSf1U_9vMLdY*HPJMQSBO-+gCQ~8OD?u(^jBbUmdo_0_naIr`^ro%Owyx6o{lvkj zot+(hAdk{0L8Dg8T|G-LVqaQb0?Tt*GF=4W)AC(jV2Y(fKjq63b@)mU=$HCt4+uA09# zx~lahVuVZfrx~@d#oH;WNbTUaI_nwBFxj#Vd^5@r& z0lU<#=`VYI=>tS~C_lIj!xmkdU<+V=l=ye5$0+rh+z0sMZp@$O9>MevS zzUL=+Toa%4zrKzHB@|IKt+4)(f%B{gNwk+*$+yf{3C5mB@JsVR8#X0Zwq z;3(5`2I~^0m2IT?o0Cs3Wz{Hn9fH?6T-|9{={Cx;+TPx-{Pzs>M))r4d?t}k-r&vc z_@q9QIvq(+&c7x8!K!-yqB@9>(^*hNXb4! z64DN!7(>j#!xc@J2+n1a(^+HkvTXnZgf#g2>e)}<5D1XAn+w-{bgl-}%>JRy4y7~! z(iv}uD(GcPZwZxqq-BeQZGN2V6t_XnVWKo`Ke1TiheY?I7{viG%I?PYhy~5_{e?nd zf%3hA&=ja0(5}B%dCQ<3Y%j0ZoWSuu1T5gt|G0LzPkQY~AKjf1`%?QgCMKr9`B3XE z;iHb%kN(=j?~NrFuH4`se%Vr88OZRxu)X%t_*x|JJZ(QXkzFA~V&!u=+$`1n_%6K% zw#7kby8X{(%U8d@=V@eOm<^rM+M%e5 zJ~&EO*Y5PBL%M1Y0SUF?R+Kp0y!5(9jIp1_tM~Ayx(u92IuuefGy$XJ@8;%a7kX8U z-sbvUYz4IjR;(iL=091=_*G=)Ac6Sv^2BqfPlb^BRI*VG#Yhs@mgZq`&f@h!-lp32 z!^BVBmSvF!P&)9a3%*su4h$R^jZXPw_}_>mN63Q=q(AikhbvevpvRU}_97Ey46T75 z?R@k-$n2=+k}fVT`etSm8Ne+J*L87(pMF>L=SYxKiR{+D2x1E@Qm+(LD_i(`sV_OS z23=tazER_);cS)IE6#DnWB5U?mjyz-9Fv1EJ@<-LBj_1J@bK^_e?ScHah>XPJj#+! z71H5{gNlmE54f;r(}t?&;ox@5{z`B_H|OrPN!f7WjnXIu*)U;#M6Hl0>B}vZ_%Qx8 zOyr&LGa-q-G;CU-BysqTv;XPreyz!&&BR~g1#c+Lz2azn=A3Be> zaz13IrS+e>{8;&i;&>ScMZB>e*+ zd`wtqXlMnPBThuZjPQ#*(yz#&`%eEoGQ7lm#Ptg%@7ejwnwaIBs-m>F$e0T4FBCgF zyAmZO<>rF8rSa@YrYxd5sOzqy`Jva z5uQS(PiJ{X>sy+;;R37Tft?q`4059GKLRNZvfjS^Ww&+nC`GC?USYDn;LY$ek_4i} z1@!$_UA!xXxFOjGzux&lC~s6qrHh0xTq5y1ZpGc);JMc%D5WBRVq0EoUT=IZ9T z>SU-}ySf~%-_^EBcAg9F3mjv5@r?J{oTl)BfI17DJ{8~PwZ9Zv%Qbj2OA}vRN_bk7 zJk|Fb+Jm;;ANY(dgjKh9K_#~RlKH|DPnbezSiNeA^wyG=C{Af?_6~iQeX^c`0yv!Icw9WnN#!&n8~W-~CS9&*SOi9MI#O$KwLAnzq{*HyAU@ z^w|xG+yH{0dV2DEPnN(s2!!G7=PWib1z&aAEq(I)=h?bEpWAZ`0?&IBRDpdcJg!@a z9^yHZGg&vQpj-x+@u-BISq(9gCT?z3G~#$Sb?zV*zz~&`fOTwdYfCDBNdz*Q>sRW~ zVb9vj_+88LMzuo7Ra&NKwO}DwP?v;SStxJ?k+jYj1|1buV#ineo|oQ4vZe_%GYadq ztsKDv{rxFLyhZiJ34i>-+*U7uHt9_RNt>VKFFa>vgrUj$y^?Cgro5Hh4So6Usp6a` zN0G-B#ZT&$h;B))0`|79XF0yEJ>C>SvGBNY=+XWjOTUnNSR|wH70##R(dawRvWXoy z-t+z?W>KU5^OK3|=GM56j~}!6_RHR`SJ&=-2n9bshlfYy6l?}Op$JcbgO3s3VMGFS zw7quqMxzRD6w3q(op5$~pZY#K+Y0Ibiv!#u+_T?x9~cdOt|Crk^ut}*m*StXmP%1xwvAbLnT z3x!#yBjrBS4;_YrnxlrH-`w6FEj%fnwyti%1Lht7=T<$x#Cog0jEMElJD7zHSJYhb zVt$wr319d=i6mLamj%^ANcHFGX{FZ9bzB1%Wz)2GSym^k@i7bHkWGLG7Z%if%leB!AhYpboP_Mj}ludWj=`;bA9x(?`?@>b}g5%}9oTHkSIpc&g48~3bRr~#>uc3okgaJ?;wcz?(G}q0!_vz>@>HMNU;WWX zBGWLvVevWiq73LQOIdk%R$8E;@R|YP-qw?@BNWFs!B>~aC9;`Bw%}8`+^BZPOXPln%Q|nGnuOQk@)W$ z=DSQ?ROi!it$5wGbYNiMVOib)9jQ{kUDj5m)VHj-pa~qQ!Y&SIp(yVRZsXIt@Ie87AuGfm%X-Mi^A%uBEVGc z4z~T-ZkEYmG!3BIk1t)(j%7<>lUjci`gLa%Ud&4WpW7NwU#smk10UI#i3w3^8s(R3uuiua)Qyac(iORPm8k6c>-ebHD7U|w-?O?Dv{Vxau+#OW z;(#4#S}%Os(43X>Y@|0#BDv5z=W376?BY6y z;yRmMeIMuzQ*3zGNZrg^q#J^c3`m`n7G_eko#6zD2uq>C>TAL>VTmC9U!oCS%&2#XLRp47v7v*!srYvN#i*uMxD-(IOF2pix3D{WA^Kt|AZEA!(_Bd11=PSLQ{fv2eo_ zj#)b4^}sr=s3X-ti#9IYHpPV4*%n7B-$=FkbJd0uiN)o+MWrdPU*&064KOp;+uGVxtEnFm&d_g+ zX!aISd2n_x?L4_$sdR>VWVJ6OWWl%F7vSIijkqeygqHF2c#K|!EX?;K=3U6mIg%dC zt2$oVymp`{W}n*I*da5BIg4|lVQR&QjkNe_KSVCK#L z!OSO6k%34mTIG|%R-~{plgj^1NB}n{7-o*$Jc@s?Na6n{@K$HafXe2wRwn}5!_LDt z44&?SuW^)%WszKLPNU;d;8~?~Z&s~N9PDy!1592}0IXjAB}rgG6@7nc?e8~#Lh@Gb zeQcUtO-BzY-|}LwI@T4qOJ*%dVtj?q)la0u=W{6kX4Uzam->c`O+yZZ$Lf& zB%HwH`4nGBg|~lM625s+zFX-cc_P|m$HGlJ(uhsUIbnouJGl_AhtT@|%$1D~dkpxP z2FJf8kSN}hOxYBqP_pII%jkuo6+|)RCmtTCZ z6-ogG0%+YPALfuDi+C40=C1B%Dn|Un@(Q*Ue@4u=fLHvD8BT!gL$(6Gb$v?6_$~{N z_*_=3iH$@HsKEh*ApIp5BK*_}$^h!p|A(vh4y5{j-^cM%NV1Bo9D9>8LK$()%(63z zGO{v~Jt{M#jF5FuM##>th>&q4GbEd&?Cp0y5B2{1zWww1r(Wlr=kxKn$8}%Vbz5hB zgEUpu-n=RK1jj69I}4)JV!*l=-jHkE>vRL8b;J&fc>)kDioy~Sv0Rh1h?U@R;PPd4nnnZrgQ1YaCj2%a4|*_z%r0tBgDU|Yke3{);%rmm`Q`oHt&t( zUg;|XK7)}Gq|AAYxXEul^>4NDZ;LN}gLlS3pOD`bRmWak+$^KQ&g+h^y8^#1G)^stg4-YQ9G&SrYTTu8n{rQtpohq63|R ztP(+zxZ_9(Y#;Lxn|=DL9!}+z(`EKjLsi)7W}1jhx6dKCvmnhTo0;7yNc;=V#jG4W zkBeU$G4i96uy0yz?{hTF4u^y`lP&>`a+3=6>ol0+3kibYpPBdEcY%YBnnIZn89{MA zg&7d~@tp4|dQsaRJT&VrA3qOeWHcA<;XEW!-uWEM?J2t$rS!sDTk5+VwLmNLF*q96 z2o%DOuC|Ur$o{TIVEfv5qFdZ@aXsO|&}65mXM)e?`92Ud=EnHCJ2*HDtjvDV2XLkw z`}b;~QE}Y1lo-7fjQmh_yKyFT5w?KzL106NE(LoZ;F)XzK|w)(ng6;Ev(-J_A6jE0 zKPy97yrbzK8n@#Y@tXo}CoyjPp%3Ga#q;sZ(K3Ci8{fuO)u2j!bvMl+zo206E6`|s zUygrfoqN;>i2^hdMTFX~&W4|G`%J085k!Luk$i{~vnZbl0NmpT?06Kr!@0#)B_3>r zspuXao?1v*7|~2|k3m-Oq`4zVR&xZdg|y~E3A?_z7uR~bf@{mdBK6zG!$z%T0b7rW zXeHH^kNY&6(sx^9c+65SdMq($bG-o~j4bLsp(M3}fT{>4cGJ#BL1+lpgFGuIAF3U=-Zdzl9b5qvrG>cR>DVcan+Ws7zYxl!tvToK z$Kjo@6HuL8IP%*zLH*^mx$~o`aWY~F-HL@~&_G^Ac0I;p^7o`6|5uY9J2tX*m^T!t zVEUn9h`_G&0}FxKZt41#Itaa|?JI@VMQ)2Jq}Uof|gJ~Zgz}YJ4vgh+s>JTT9uEN zH;m}`>F*U$n%ZvWIM|Jof}5ZJ^FWb>l3HfLKy*voUL;gd9X*(z4zuyCBoqpLO5LQA-=A8&1BjnROx^!gRIPa(w3xEzknF}J z*VCvu6gNPq#xhjSt-aaf4ikc}w%3#@il2?~A1EAUi3p&cceI1C*-WylN=Z*J*Y#rN zw;4+IsSYcO0T9rCGeA<=y@y8VTfYV188x?5{?0@jZQJ;>Z%Z<#{4xD7eOp|X`mX5F z(Mi>6nEl;|LOjT$PSVoWPf7;^qYaOsg%v@|ufyRb#c&3}{UyQ7Vd&^3oGr8H2Ysui zIZ0_Jkrv}OM*s$csiRNYlVw*GVWgv{lxvXFr=hc5zvte_jm6Z}#9TNM@R&>?;Nj?d$DP}0JJ-IhVBYMzf(3?uO^g({(pp0{<6h~G#nzO zlcFplR4f1pCk_Ljr5g;jVmXF1TM-pGUO)!*ec%wg+epZk&R`|(o`i2Gj?Zbdw7&XY z3hu;5=r!x)1z*Pu3_7;0Pjp=-!Fbh1=2Y)^#jLde+U~6p2EaE}(!= zJ2ZW)C6?7>I)DCFLC}^gh5Ep$44f!7nK~P)ppqiAJ?q8kJ$o#sqggO1bflb(GBeq# z5htAHVfW`wyu1NMdr<#CmmN-Ai@sO#*>Sy9anthV3^{<{h-AqVwBDUF{eQTUUAy&f zC1ErUPTnzuLeqQ%+A13@*WtNd5Ko27b@4 zv87_4ZVqb2Vbh@!{~}nU*AJDSj`}-CvfXRTY2L`&HKbB_b*$mPa}4r5j%`K~u4M|H z_NL9CXTO(7h?P=RQ`^ril7|l)8gc1I5Z&)Y1kph*{ilG&0|P|KZi7#^Y@MdJ-s>ad zLU`)^gs>b`%hn=%uFf7~yuJ<_H=~=D7W7X7_J*^Kdewzv1i=GNb5~6>|rWeyChz zUd(Yk#FilH8*nnH)U0qZ4S%1it0M0wa5HJ@K_%gJO2D(9QnpO&Rl~X`2EFUG`y0C3 zPpvoCJob(uc{#+N@MB5YR?g?9AIIw(Z5HAu*PShc2(_1mY(2gQ5H&$3@fDb7QwU=e znItVz$kDIn@f}Ws#o5^!m+V^DVWX3l;da~pz9|wc$i%|4T&}^(Xe6@ zmfcY!vxH@Dwg_{f_e6v8etvoqvqczOA!UhLyC?{-QPz zVBPJsIZfsytbCzMZ;Zz?`!U}3>>HdWJPKrD;xHmq{Vn*{p#G}lfD*JtD_i?af%qs;0o1@rDTandB!>$S$(tTU270lcj*|D^sPMpOc>#5=0DM)hk1zOWG%JF) z%)%bE#)TVd!Di3kjmf?v!og2ZyQN%{Dy*@}6`Rg()t3Gehj|R2O-oNNP9LWEV2M=s zpelLDZe?r)FSm)3!K{Zy%|$7Ea5>N#dzO9=4y}#?TnzMg9DJ@1~U1*P%JJH zlPiU2tV}k0d7AN%@^}U5hbLhtfrFD$cp~xKMWWXXwf5DIu;#rd3jvaKWq|-CsQ=Ux z9$7Ng6O?Dd313}3?5s+Tl=*nT2uzXuY6Ov+xd?9VJ8ySnydbOcX}~63vcJKB3mNvm zVzC3V3yTON&xG9_y9pq>3_8nv#WzFFI8w}rh`BP8WFU*y`$r8+v&F42=voCNxI9&X zCy-FeLkdrT7e6#qUNBxW-~o}93c*CdzJvuHmgz8zIyY2R=T3&Vb$vK7P1>8_{_cvj-XJx6fOeJ&E0*2qk$@(OL%(gdMO%;-aF%&*J0bf%tDVnv?MSA4bhga!^1paO4tWpG4luN&lvA!mqY# zK8W~u_w{1QJ8>801Z6S(VT(;(+c2X7P5qdorIDH_+-$6-GvrRkriF? zdZ>nVY+L2DeX4)UCfPv~Ml6jVL7RLD`ar7c(V^h8)%(WzFYLXf@8201C~5RMgKK7g zr~n3ezndL_^z48f0HMZai_6A&O2<|~CFy}8Rf-&RVbwbI!4Q7A0PuVg6Z-4 zfZ9XtV`Ln@QDby-X54gNBta*D^XiskR;urhP%gn#ptkb;y^HRM>RqFu&xVlCh&!`I zd~3Vb6vxTLBlv^x=P&ylztbBm4CS?ejLhh)s-FTSX6*7$I=ND7@B7c-U3R%Z*R}S7 zt{%zS%7D_;{dA}_H^J`mhDh^{YJ_lv*#7Ja1vJ!;l$10NY51fl6s~SGD`4SweIvOL zEptXrz$9=A98ye>k9>Q2TJ zdO7R+D2JJ_I|ML*+1yAsCFbcbwgYy5_IZR?j7|4b0CbRsQ2tiYZKDDN^gh$Wi@xh- zhma_Wn@}>GN_0P2u`oaRKz<=scU@~P_<%b|!At<{xCgx$ho&4p(bufKkmbi(zZAlo zh=eQQn>EYgX|J6A{s(4+C<#J#cAA{bYD@8!9m&0}XG;smNHC7pOl82IAoH1w)&Hga z@Y)cvNi?|b`C^1*01RA!vdh|)fU>2OiEeUuE7no|E1V^QuTMx;w^0{&?n2lCph_uj zYHE^424&6Xfxp^G!l(F*?@`6@@XWZuMMJpw6f-fh8n2Wt9Htl;itvg1@+R>tXP`Wl zeFrQxNx%NCP{wB8f;M9D>Xr{ETkGp!X>e~$OiceKj%!MAz&3-}J6J6XgQTEG+Tj$j z62nv5HjI@uvU;aq9pF>XNt9PUV@rNGxwtGFr)$lG@V9-YVKDAVVG|R6_U!hoYFn`g zj)4-&4uw1G>{DpLyY9eLplx*=q&jPo&l>lCOPmr$;2B5lJiYw6!T~YIzP4}gY`(l4 z7Ke$<(Z5$x5}&KJd5$vlxEluD5D2ylHqp{YPaUmI**K^VniXa739|kMXDzD_9L7m! zZK;LJl%AY1R@p(g2eRuVzh|?yUtfUTsmfH)(75RK7!4Sz@D{)NSUO9z-X_g0=bE(M zj2K9%VXuuMhMGsw!3Edi({KO%8uW*_NOe1(j)>(fh^arNNkf33ON)~CeY`|Y@4JIc z>M5)V!U)J_J)A5%Q!eEX9#;yNyqV2QB>nN$4nV3q?;YVJL= zSd+PNqrIzjCW68%6{gJ0UO$UIKnLopGkcXwJ@FbcHyW%wcte_i9!j2aM!G5});!Ry z!8lH)1rLb4-{9bZPfi4FmW^ULFzJ)X`z-ON}lv^D#4m+nlq#x{U3uwJ2r zSHC^w()K(60N!5?>(#(32z+b8f364q1F%%MQH6&(zrM|Q=+VlNf8WF$n+}XH7PkzU zlRPX#-IihlI-dcX>TF^_98eI3OU;`@=MNL$_efsn`r6hpzckU4{6-V)clqW_w}D`G z^$rm`p0_pZ(US4*1WmTjDV;&$3gD;2MJk7>hX4`G0;`v*?5v;bcj;Zk`9CD>9^Vw)@`eJYRP#Oh#AQ9{hI!-8##KQA(8)}xrG z)Q;~a^~EEKhim}FZ`a1uxFltMYq7hatwGI>_9FRvnAlcB( z{PbPz@>doLZvxNCqF;Z++Z>`-SMNrQJaHst50ai-Eh;D|D4e^SQFpzQ0mkGNos#pf z>;HmLRg}ntiyNzKX?_2jxRvpG=M!m~RW!7Z9y<_$YM7{XX9W z^ap?`QY1R=IoDtSKL*APL@OTsM9<486-cTn7))=gVD#qZnPrnrabvQrcz`~D!>qIQ z6s99#10_~|7NFe!2Yt{Zn4umzyjvJ%U8k7nX%q!6!%>YZ7?|2ddh&q-Q6OXoO%m>7 zB9_=R#JLpcqg8}mzn6od*VCBkle&dADrePc5lw-yr1ap)U*qJ#6F!Q>dBm^>o?k?6x9TEphEyOHH z%h1s98_3#!;$rm}vCg`$BS6;3W2zw>G`m+zghNn(2Sr8Q*;PsYNzr{>oJX>g)u1pA z1%#Tt0|@(7lUS~n{$?!r65FjD!lteqK(BBk)DAxy5t42Q((7KaCSzu|q{6Ru%Qb2* z=b4YJBBlKkh5uQs%=tJO)Rsj)$IEp~0$t*YrxN+AN)w$#uXr4)cZri??vKz0xSD}^ z6+{e~UI84B+M4i-S9+M~PoMN$mrOB!2E6D`l| ze{kSx5jypELo=m5%{^tp)d1BQsQD_&W0sHyjiS&e5Oc`(M8y;!l5R3A=CeEvPwsRl zrG2m$2kfT1PRel}j^sF!K>zp=-~luM(INjyepjI{?{W!ht9++g{+=g4j+D9B(>EFX z^-X8>O1IkLWr|Zg@ad>=z-R3k2_Q)J#@;{fYfy6pX*n6(`ow>m3UTa!GWz1wlGgCj8%8mgbA~1AXtC=WgW>9 zz~H_1+CU;|PzHaX`FvY@>(67MDfKJ2b0sZ>%<6W|MKF7=f^&@TS-`qRJq~elPDJPk zwiuBeNL&CS=@yLUQ6aaxnMvGmR7+L@Sj)+O$IkBJ{Zeb~ZR_b%idQEDk=2vx@yO3mCT~T!76g^JIFHJJ^%O7 zp(tA{1_pf+pdHH7i@C)7<@_x9qbm5HQz)|_s#%Lp#Lwwt7>#HJ|IHr0Fe-t>52T7% zF!91Sb@@l+|22wsqTfAl@=7l$T3mGm+Rcqp@r8V=M5iM%m<6sDY`iiAZUz zB!lVrECN`8)cWZ@LGP^*)CI5s3b44XEeU&gh0ql38#0u5NWlQWiTa#=F+vycJTY(| zGd4mx)_GyBr37Ymt^N;e=(4pPXTR8LYYYbiM(6NBp)D{r9SeM;;SwuGEXIM=4kqs=l*Dds1V|`Yf!US_ zd$o$_ZuRHIz-;xj72$!$27%TlCc`5C|2_QXGTFY)2N61>}V}ZGgc^`l&7ImrOg*^@s^HhZbGKFf~n>dpW z0$_8FD*30EN7HQm;-Z$nYMCvry8TbdAblQZc7-SzY7VG3sH=!nJ@^3$rhI`I@e=zm zJcUrd93r%*uO9$zcmbAFUFW&IAdzsu8m(3bduGsg4mL_ zK2{LEtqC+5x^?V_?1N7*wF-iB_qB>m%#2ylfjkHS6TN6`inDHCO0v6|RSp$Xc9FsY z-P9T59%;hv2%aT>}Drv(Z=JH18Z7?7)^ zJUmIuy{oEDxKux#>gOBmQd5uPMasUU#EtzCdS)X+&pdVP5kk)dK=jJCe0m)cn!QzJ z?I12G*Bwwg`6Xx-2s-YM$>PrXJ>04w%B4v3wTOVOc7u$(mkcV(FYX*$7 z@2x@VxN_QGR+Z$?Q$u-i&z=e$_57?YHobh|%G-%Z8c{0)u%gC5pT%yHym(xVh4L;@EQ$HdTx zz%eoGSxJZW!zum}F=XEf5dv>c@1+FcJq1paV}9RVs=AY+BG1mz`u#zann!_xVSb&f z=AmpMKt2LJQHxJ}3~1)u6kE2(8hCBf39-o|tY3BOuFR&!MkD|oDjwR((t*P=9$CbJ z$PH0*5mXVx8HQpx-3SeH?C>bSJg}YViLth}_8Y_)!_$=MuJl}sCc_<(p9NVUGFy;P zF3lb-VBbT=Nr9**8{wx%WKpsRD^tLIUvNA7^Wy&K`lseRj{9{&aY%V^RX3G6CNAzw z9qibk0Spk4Y~TfGAg^M&6qlq-Ey`Cb5`2?g3=x(MJf0l|a}euh(eTiN!fW06?EV#y zRV9@yaHal1Mwa5p$kNB>_X&bpR@9$2*JNt+%e8189{qK7$t9q%OB@-K6$ ze?a7pi_SNCh9X9!si*|zUgd=dQT(P2VDzhe09D(&BEY~UjXnAeUQB<&(7$g^bSLoj zQ}!5a)a+BCC_~_vf#O@uIapJD1B26vU@Z0ntnEY<4jLJ-AVHav$*%t(#`GFICQdg@ z%lKU2<`c4%cZzuo|W8YE-SHLX&4NI5nmica*dZ#2F-h?d^?Q z$TU8}f56k_ho-v;vFjp0z&O83pZcFm{%`liHzmx3M1=0|nt)YGWD{wX4puEbf?jma zZv?#5WabaaN)$87AcV74I4v3=(sny3$~9^6IUNt~i6JmAbP>pchmSbtLxpffaMaLj zz-Lhi-};FeJMn+Sr%3s#AkL4Q{zhtC^;`pP;kS=y^*>Y_vr6*# zkz(1B;{MC03j1oxNShaQ=0I6n)F<9YIh_Om>W=G1Qt|qkNf8;QL2fHSV8poczv?mZ zO{sG6y*_-Q4@tlJMI9^$LXex(GrX!jzPBP2kjVhn&Q0#~)rMmBdk&dM%0`Z*iYz5& z021yk=z{FJ*KT-~C%iIZ#`4}S&6c?ns1JEF7vZID9n+E~^i%;7%&o0i{adGMKeGGd5h6U1~-dh`{Y0AbP$3dd=X~K)6(AeXAwJmqeY_1Q##}!VqnYQ8sKz< z03Y?P%?VGCO7QYKq`MB@MT8`Q-NV?2TGR^arz4Dh)$i{G!U!q~_@sScG*fYNYh{+< zaGVW65{>k>+eM*i4kbYrDk>`J=zdo|7Y*Em0w!582w|;`zYu!!H0hOr4a}HT%D1u^ z?3=zg#nNm|A(Vq04BsfwK2DTQ_)tT@RW+LCk53->S}85zU@{>iDBQzpB*m{5$DhD0 z>>90r?E?{?kClhV=KB*|(a2MV(u3--yB+Tmczk>>h;2J%*(}auy&hpdb1E(Xjw+6?pe;^T&hq^{oJ*I9Zoiga zF{d^@*LHmKFe0)$$B}f6#}?8y&d7-0d1X{F>ddZ5yWoEOA#n{az=0Zi+zxUJ5=`QC zp8q2(2zv1^ZU$aKlxK?&&yV#qUFd?zS%vS~PK?2v`fcEVf0Bg+PIn)h<9rrTsG~IX zKWUHzH5=wHEuR<|rn)p#Bi#qMH56W*m&AHI|6gGPOno%pg@)aAe&f^3ANUe-tn%>j z2TK9%IY$r1HvaFlNoF?n%Av5N!JwnULLa~pIu4&Hoc4q;;2I!bwy6R#V6nz89$UAP z_LJ82*DWgf)bQ0L$dh&Yt6NUGx?iKFJCe7r9b#X20l)qaSFo*ECHADs)sbB)1lxrt zkD@qEFoz$_cBAzE_S(XB4HlCt=OymxZhvSN`Hwoi&Vo-8%+)3ke&P}~_}540*$}FF z!R?2HSosm^9+NsVU<*#KI-k1_s~ycQf@xL7VFLj_SrKVt>mxZrB!{P(qnJlE*MB%Q zbV;NhG_eRTf2P6AMqa)F|3D#JgwA*Pr4sk^Ka7`*$(+U|NOdFB=2vn?O2*?ULKvWm z+$^q+9b>kXqf{7uQaG)Ae76wlS0A6<1S*C4QMiY-@vyYThZu8r+l7SASf`SiK{`yvJEwwmJ!G1BOkd))T^lP_ZBvo>$QkZ0h zUNlAI3rwEEvt3zr4N=O-tA_JWIa7eLC6m5$+^F<(2qoKA-jH|2(lq;F)%Jv>f7t=j zQ`X!w{9MeG;xSeU69W_9LcH#)qlEbZ-Bx;xQiXx(c*(0kbLKj_@E5 zXP;CM&|dHB?Y)Pf;q^Wp64N{R6_0)c9|%GsOzc24@Mro^H83>cgTv|J+dW3%_-N{H zdtRRbtIP7q>FMCqs9!T$UV2sQp)~CwGGx3YfMighEpD<<0(=cm;fjQx_C58Rs>;d* zL@{}8!TXA@zrn~-`sZZ4S)INRWBxR_A}2$K`i)`!B2L02o3>6^6-HI|B0t&+riBP$ z(-|>>R9RG;h{wGP#O6@TEAt9IL&REuR;S{01`8JRzUIY!vVe#13e*wk^<6!3|MO}& ziUamlS9jyocU%()v1COTVSVc?(Ms_jmfHIl56pRbB@R--yCS5Ob`#zB5Fs-hFAu=e zPj|blrNfIadzK_7Hg*zhT&EFdu(T>H!eU4{ncEI(mLR@cHVWZKm$!b168=EO_bDPR zqy)kUq;hRZ|5kj{g`a(y6_fqL#Y4beS(DsMUi5xdTv@q!qE`8uda~r|2;#)EemK4- zW{>oLsAKh_bd6a1&UeFWpK-)M;t3|9yBjUY;tJ>@fZHAZf1Db;^b+UA%Cq%PuX@Bf z0bN!Z58w1THC`+~%XbjTdxip0Y7>u30B?SE35$_WjhMUx-Q)l)C*1uBk<=Hewimjd z>DJ+HXKZkf7&>B@AHq8jo)&{j;nQ=11oeq#1l@)c^2vZe?B%_`+Fy4Xfw@N(o!4(; z))9}NS#|jNwS_`uYLpNN{u+s;@r!kI=nOQohm_w>_MJ%&4inKE1|PsdfV1K?pn%Uf z6jjKgeE+dDs~%xr13mbviHUl}=7tG@^TFI64@WYy0Tq>YX*T*%P-+4^`i;OJl7v(+ zw-mwGYB^T|E_}5*gy2g-6w-Km(=)5F%dBy!vaW8A2@uP5Ywwg*Xx#RaVXPEbH!U}TEeKWU12R2rCgC=5Aqe)n}U%b0~T(+qp9gg0Ir7?OlU9aU^^%e zf2e`tca9iC!$D7p7{wd2KW_3kp|kjKgMbY_0aq|_5%xS_HGU=-i*sv8i4SJNzjkN) z2o{s<#0FBH%P6j^ysDR2o)9CW58hGc7XHL@;*_`8xjW5xN9m{(QvXajvMvIAFZ6ZG z!A*Q~5;4FG2Ge2V+UcT$5$GQ-glkFYlhz870zj8oUJdO4hlTg+%shji<0n}6hRclJ z1jm*>4TIMTewpK-$X32b9!Ku+)WeUa-(Di6o;u z|E@xV%`e+?Lvnw|5i`BchKMu)cgKKeO9Nb@Y@_5SNC(`v^}nE95WXh?Zw zQE^RAPg)eNXsjp6|E?&kDF9|e@7GRB1$*O&x7UYDC>5w(Bt9W24HyI=vXI5nIU|Pq zz*{4L#hyx`q4S!3(rNmFoJ$t!D7Reu&RY+)gQ2bgUmykSN=-ozFFuseM(Z0%w<_THs*xDNQjFAauOr1NS0-K{sLTDVeoJaJxY5EM{62m$PBcDF?& z8yLbNVtHnhZAP8HH%5soZRFG>%p+_{Nsc9xM{ouvp0=$owZ>*lzte_)J`5-K<seA_;x9o^ApHp>6?|)ap7#7bYkn}2M@ceqAi6ZYXz~^0PxJiZ3M7Fr8$85QRejfBnrH8)nNU06ls{RY#z-cNN z*|N}i-CcZ3Bu5gN>D{C-$7G$>QV#S-hGao{ocxhRyLbXa6Z2oG52rJUNh?}3{1#D15>e6j^Z9-9|64w(#3KoF{iY4vKH>CFBA28xL z4j}fm8!XMSf#r|eqI|Vr^Lpj2<-F6n2Y9NULem+G{I_>D`=%n*_eYX!LQ=8P^zbBT zd|aY_DjIf4GhXCRrB$UE&H-;b&s%xbJKmzXg-oDuAZHJerv8gLd?zIU1ChuJFeiNd z-0)f(_@47pDEQn>a6(8vpzTvlgOa*5Jv|-WsXKp}d2hp7x5!=zfRBQbL)V5bGFYhQ zU8T*T5g@xrqI}^+x>;Xa(3*67%#L%R>TU?ga@R{6ScOZC+^W^c*SbLyE(7}v`r7ETF*isz@>98Y3-8W;jCbATz?u0XZ!;KDUhz3n>jB$8>tRS4?)%c^ zxvnq`H?C}9$MIjOD{o@5?Sn6;GpZL@cJkuJG{`THjP?(r;EOw3HOe3`2Zf{68?XJ- z;fQ^UKRLA1TfZ^ib)1o;rOY81_m#b3!a{K2iSx#bpVA~4riUF$XFM{I>0*WLxh!gg zYFLUW;zquB9vFA3ZmEv68a`TN*Wt||e;qteQ}PWFe#4Px2ILowiv`qg0}E`r zz^(g@$ol1GGNh{oTjLsYqV26QA96%1`Z|?Aw*A+b=C0G0qQu=w!p>I~5?6tbt7kGv z3uVOuGBd3Z)#wN?n2ts~UjT+@fvna}N-Z-Sn7uFrzLfTRAPz*d^T)Xb1v}Itnq$By z21&BYegwem>K_4Hq`72Q9vPW^#Ki*Ay~2!Q>Yg8M&)M_HESat^!3c5YyHo0^aPKl+ z!0V@-E*v3sKUPgvkJ&6mfU}N0=#FKuma0*6;nT(=%ecWSUO*33S8yIT(G|Qh!Yr#K zLrZJ+%OaMSbEF+&Tf;EEjR*k&_dV`%q?KP~Mu(RxU=$jn(6Z&)Put#f2+o3Wx?ZUJY`Tdn*b5dgg3hVn-xcNI zI+)|S$G}JTRCQR*)}@NWCAO`a$=c~2J9sIUc>m^Sur-IysVIk)@H*jh>y{%A+E-Z3 zDPwZ6!ItZv0x!sYv{>4v7kylDXZS`m%2poF8WjGHL-q1$Q|*UK|6>aV1lc z==SK2gti{SlHQjAmXz>35s!4>QLxox_Oj!da`z1PYPAE#Fu3t4V85H3zqm&6M9Z2o zy`oi`gY*YzMK>?OIN8O>-2mWn3Ddxt+Qd_L=YcTo*mtE-fJuY(0N^5!lZ|-gl+nr- z5>(wzPIoTzdhOJM4MtKzuNMywj-xAD);|AcyTT~KYhXn$tgi`wsU6i#VFbqZjvA`D zzF>@wu!<9gMk2|pZ-3rQP=9?g^JA5{x5=6>2_~sFGS7ja6pkT_VIMYk?{JK?<)nQHE~?Py-|4UzH4_?v+~xa2Wfkrf8^P*X)0M8<+MR0`)hr;* z1}dTUWZZs#YZ|}Kg?itm_iPkZZAc>`+~Y91c&ktCxX(8YoeF58HM{#-B4~t5EnA)z zs-3*_JTchi;81b}xFQxOMy{d2VU@cUS7)yzN`Wr@A)lIEeDI?uZpqQSGIQGChpoi@zMTszT(W}-2|f@_hR=? zf!sf3SnKrxmDSspHU@Bv9$u0NcD=K(Zfi~n3}d6#TNDUzH*({tY%a=H!^jml9`{}_ zB73R!My6q9eZHcQk=%90uEfTJ08c^8gjA2vRl6>No8#BT^RTk&tqr&hlXV zoq&P=S>V)bI-ne6&HaJ-!-V24j^GDyh~|{7ORy=s)MlVWv1zj2!qoOLl9c-2RkqL} zhOan(%g*lFM@V`lCd;i%YpsVp@eiG_CAAsNKEhNU~Fl<^bMoOfyFf7rLdx&prP!# zO(~|EEDcXjv}#UzVCzf$Agw;*Gul*mH2(480N(Ys{Slxy^1y=JyF$pQbmmB*_W^1H zcGQ`G84p>?iLgAL8hWz{iANcr#?$Rg5vV!yB1EkP&u}9|7D3nbGK3r)9T#Kz2gXyz zoujR_nTNTq2fWjQ{^P`>Gkv#X{0X&Rbh>;6rQ^v&I#X}USo0D-`iEH!Jrom9Y0u~W16QuTVZ{U zGLq%H8GMPoT5*Zlgol?IIQLH(y2;{SKE0J0zYiSN=gz?2tX_3$e|Fll83sD! z9+QXYL7*H;m%`2T)iDfb46MUzm=ZNnjWB)fiGEr&-;eu(@Gia!5o|r7(=DA52BzsX z>x)J`7fUTFx}IK|9xke{X=VU(!)t&bYNCTjixp*W&YaZkWjBs4Qw^?Q-InY}ZNDYN zY7}A^=;;f(KhTTcA#NfUs^3{^u3dU^a0%aYnhT)|j{N%A(*48Y*qty;2V&le=CezG5dsCy>aO?|!s@ z&c23`bBE4Q9ozO*LoM2*jW}<=U_vYn#0n~f_?h>Wl`mgTWdZ*2>sriAv~}C#D-G`WEe2Qi3slN09l#9BExTP7517+{DaLJA3FRwHUdwxr8nT%BqmmU-s z&W~l`G8x{z`$s!sZ$?|enqT-~oxW@KrS)epiD%;t7o6;uIhn}7P2gQl+_P}3u7rwY zI``CQ{4k1vsf%Wpd9(I<;0(3tp17D;$NbNqcD&$NWeRsA4!lrnO*ao4WOFKIT8`Y1 zCvS-pLyljPuruv^@FSF(>!=(4d-D-?#J?Mf5|;k5z{gj>Vw$PZ)5exFIT*A6GZde1 zDNm9F++dY${BSlP^Z8Xo&P*`#>Xx4%=^O#|+V5>#pC)z%)3>%U9u?)ew>d47-Ixa+ z|Er&%8sVEU9Ms=vZJV zd4}f2Mf=PUbW{@wr9i99Nmv;p>-}8c>D$LIC>Y9b>221^-@8Y#tGTfgvo^o#ye(BI zcJcSS|GtRuFFBA!Y&6`8H(4WVXY%alV?Ka&!7Mx{FuSbL)Enrm76REPX%+2naHv&$ zj4d79IZalCh(~{o7f-jeW(Lu*=Sm_Q>&Y~@?*&vsE1L_N9Gx(qdGV`d&RpGAj3DOq@-BV+GIv z24Ts7A9(+x>*(w2v)x#+WY4J%`WK|$bER4BaQp1= zi;rEUp+yfDm33?p=j31MOI2=fmVi#>5|T8d+-B}PJ?$AvU#Tm0>0N}6NnJe@yB4PQ z)(#GWHja+_uk}t}zu>pG6Lf@>=I7GiB>phozjlSaLhujONoHwBN;VMk_R$}o6nk`> z;ct*+;W!IcVb-whQ~1)h0I!JPW237J{p~!qK7{U!I>$vw2?7xEV47p9%!~NbMm*<* zSDK4w_kP=InR+Yfx2ti5*#7F;1T*>la#L5nJ}CY1piW`_vCY9SmBNfrnNWH4imRyX2CS zF1PTCb6K{W7|%O_lGq=Pai^=k-Mm84Dv`dNm2e(Do%hh0*= z4D!DE|BR@wLvnmy>&`Y;+1OR&{BG)m&tiz=xs_JGTvovKw^B{f_P~}4I^)CuL`+Fo zb6R-=tbdhimJT6+F)ni<(U$xxA?aMf?RT(`vh^|ru5>gA|NYTp9OlfIS0fE7@AMVi zV@h@MIkMo@Gk3rKJ&nmRA$+5w0p`>&VqDv0pj_k#G0hKKjE`WTBno=fEqH1fJrK_x z(o_>>XKU*T4E>~+8p&IiNH8+Xt?~!+jfc;W+Rdv)1uW`rAdQ|7A0GqI_S@fVI_EbFGSXM&_`kSj&kQh#^5?$GOY*SSx&DUux0}9gQX;3gMpPtfvU-K$|<4WIW~w z`sX^$GY(I6H;2Al^|Yc)?+xlyqgYsL&6(*^tE#S+DU2obySF(Rzu2Qi)XA+=ct-{I z5dpuc-oQ{TIW&z#cxB>^hZkk{8;`APW3{`bpoB+au#+kQl$&v<-0s~w)2GyZKQnuk z)>S(y(Edl?pad54s_|14#V1L8$=`-bXI>xU2-0}gTwc7B^?s=)s-imPrb{q90!O%h zj>z@%mC-l;kFRZgObKZv0$!k=2!gyM^?qgO;_w@f(DaXx`mitj<=GCaL<(g!b1*lH zg&`HvU`fl@)SI(r&&%|G!{mIh9{jKY-Rh@f(CNN5KVixN)k$8jdT~VY()Y5o_-69C zpBYpaFVU)WJ8im7EAMV>r$>f=h?fJM0A zz*)~Eec=FA7Z7!2`f2J|5#A z)TIw-0Mk`i)x_fItg&Rt(zA84W%@sXByZs6{iZ_cxZd|TS|Aeo;F0r|3kd_$+oLP@ z`UyMkaD?nBEl%u94}p+lLz&(ARow?&0i#muY4DC*|5vg*2P3_$Kn3k7T9!G}+YlAe z;rHC!(BMPeJjh#8DIXg5w_tUWBm}ac`veT`rLP+qc|tt+!lGnKY#9$=;K1ZU-XMF3 z;1hWoCeOG+MkybwkuHvkmS1rw`sJ#coE)3V!R<;Ia_?Jy&D9;^cT zhHzH&b|eq%m?!eRJ}xJcK+*j78Dvsr7ZgOo*x-!rD9e=e8>5to8LfFU_SB(Zqaf_7 zrxT0>2^^r|7UH~C>6%6Ogh(8$in#G+k#xgUb#=8DSyG=j##^hS z)=#h$Y^8A#YLHOG)prFi{M9;!l#w-kSw4j+7EaY3Ir=Ou^)@+EN8R-kNPMO?My;P5>1ajNG zuF-!d1ofTxEpg<;vcf~_I`}fdW!5Sxq3sRrhmZ$+p`!}2r04bOV1dl`YoT;swD*WJ z22J!Z@(L2Fq~$D+EPv8tm2<7UxFI!=Rh&kOAO?(#NcqjseTKnN!JmLPVDSU{nm3z@OMUI!hbI zTJyccP1JKrD+XpCR=N0Z0$PoKgPof2oFXETOlR5*?+rbL!vddG#kLg9mZZe`M~ zG8XG{bma)ds|tPNd%wOJ=Ee6`uTbz9*WCYu@bhX%{}$|c_(Iy?%^UF;bK%A5#KQ5A zDZG-eQ+Z91Obm}0{|0M{)BFMYWI!gO@^rBPcRHW4*2S$cM43QXW@i{6I$k-)ynX+a0Nu?yUsaNVT)k%2&8U zG-+|9-t~<#@>8FTgM3RnxDkD)e+1}xVOgi;dMI!HdkN+wGi-NCVOD##cK#Zi38?N|71QHC5rzOudp zH&svht}Kf9cxr44NUp@2_Q7g(3pApWXuet0f6GXBk0DW}$K{CU-wFnw_yR$T5aYcU zc4AT1BJ=`G=Wk!hY3ux3!9voAm4&So3j(6Uxml!pFPeFW4nrcwsjDE+kmJc9v2t)3t6VblsMi##c=De zMtkuTDI;-4YAiubz$t8wR?ajB(dh9c84g|FL%3Yl{4618(potp?{OQ6ysT5IA-_4v zE>vvk^K`;xzU}N|-?OEaM+tVJo?S?dE_8aPAb!H zm@L$HommC(*B#S3@5*-3*2B;<6A!s-PVhICg8ifiC@vsp<*gRq>@*TPKsn&h0)hgL zf8wxRF$^XjMZ*9&9ih7Xr9(jS^$9K5jM^10Te!*Rx%(j$mT#e6u)VtXsbf9a<$=qL zqw7EfY(1%ARKPo?U2}y$FdY0C79Q?pDI9(RcR`&?vnAw9trZZ4b%XGC*UZY6E-Pcv`;vZxgR^b+g~pJVfs@cFehU$}2ZjKSXs4hu)Jg117N zjNG-(=cWx)r}BkWG1jqBiT-?lljy@3e;U`%9Bek)zR%Eo`wKtuMkHRt zw2!-*rxaj00;)wbT`r#cRQ)A>G1CZ8|26Lj`K1-Dk6@>|f7zw#tB}E)?{%BY)Adt- zYZ&mo$6bnPR)uFrw8iawJ6=dwus>d+`tc8Xl|@+)f(A0YR6|kQ%WM1Ys*LBA~;;b29*8? z!d@unO!bw=rn@6Ti-Q1gJVEvc$GD}$ua6CDH0i>(T4R=;K7IP(8QldWVIGvUbey0e ze3-k3L0{cIOLs5y2g?%|XeL+31maIuX*q!Ze3H-1i1~F-BU%$S;T3mN+Qn~`B?f*! z9kDl6X_KKNkpf(PBk*r6iAS(YsSI*dA! zxqC7HUsG2e59IW!zhw_9BXoOkC0LvgQ>lUJj) zwM(^_@mg0P&xbNZxy$V+GGnXx=}2R?fHhegO*=gTfIJmZ1@2A zlM{`5J8WR86SBSszj_52>((UvVHbUt9Fy16H5#H@K5S2OwEs}cp%ZD}VcU2{KU$GA zK>$!FO3WaxT?JTj%iAe`WNH|BBI5$UtFOg_TAzAiLwYZME|a;8=6Abk1((ZL5S*av z*XBfe;BJNP=wz9n=Y?%NdDBhOaGMpivtq*6 zDu6s<{RSPzx;&~7mHp{hCYn<*0v4(4Y*gAf#Kx!4}H3Qvv-M}^b;;YB~3W^ zsjnW{zn*myv1av+KV7w)fEDjHkg;cTN6y?7*A2Gt7oTm{*nE+=aAz=sf$96+b*Gr} zeWt}ia`Ca&(MDA+P4}~gpKdN9jj1)_fyx|;()(TnYdZb}AUzJ(c3jvZ|ECl(pn?oB zgqX~24svYO7bJ6+y#{fRZ?1q}+lrtzuQC{;s!uHCh+FuUrWH2JZgA!dm7 z%(kFk9uHRY(Bg%VPnIsg77IQ$lw^MXagBr7_%XZ-w8~2pSq_l%#lW33l|B-Vtm6+o zksiT@{uvse}$q8)zvp(?_mt@?YQH|kJ}fOL|h7e zs6-`}X+GHO%_YQ}*W3`oUHe%k?Hiw{$( zuW)8O#J)g_wD57QU;ceKt)RdyhMO=z54M`WxAO(CVj~?VbRMTmIK{n#f5#F5S@1@; zQW~t-9mTy9ZwXsRK;JT~tExrDnRg$)00|TTl4&0kD%H04zx$C^U{*=}3-28~y`TBS z_duyS?D1ksZ(mI_qklRt#iVQO=}OBA0pcf;7Wo2eal5>jLZL(xanvvTznMhTjw*;5;M@bK#$NM3fDczL}vt&-I-}uaEw;-%~)h-#uN4oua z;?Q^jvYIO`cZklKn7YsQ=i;X@7_Zv`<*=E(l5O;x8Q9x`SiJ9~P~+GnyRy z)24h524vdO`yNDUSY&B_Ol=t1p5#4TavSc!d`|!U_w(8Hw&@VC5Dm=f5DNC=p*G{P zQfuEH&BHkN)G{}=Uu^|l?TGdfxc9D866K=>$@q>k2<=Kr-GUt!G2y?u&-1$sbaSXB zHmEe$*UQ7fqAwP&r_*Dl%r5~VFsvURzw+1*W-xs=xF*%6W1{8}$D?HZ*k*ic^zKTf zfP93CxF)PKJ~%M2`^r$OyUBYAs}5c7L}M5aUwy&xO(CyaW0@4R9PZUQ`NmamDo2j!Ml2`FNs1ysU4Au{g(SQ-Qg|D>iUyvsFwc-p)?R;S@W0 z7H*wmElLy<)|pGf@z9lYeD3xum>p}lV(6qrqex+`v!Oy06tZ>>TMVC!{en0*p{7-a zOuoh`$yB^_(jC66Fn&g)C3dgniCrvhJM9BQ%SPhAm2_kuvM{u3{YvrPIdNCT2GArn zWG{YtmF9xnp?rN2g`+T4ZlDbh4~P6m#%@t?@Jr%mVEN$cRUBoC+)G+6k?VxPl<|1l z^k_G8{CG~dh}sUBEJ;(fktX3~4ab}WIz#XMqNQ3DADCRZ{UGE=R(UNI?l^Z}qvU5t z&wE7vp?a!qv+i6jm+)Q^qod3D>ib zp2^ad=Nsp%c^{?@WrHbfY7}OmeE;OwQfIKBKpTzr?2!M7_n_*Zot7N9V4TPD2XThw zwdG2MA3Vj>{xzu99FLE!`l&6xHaRk}UWd(Dd=W5Rg>0_|<}2q9i3eC{R`K31=g7e#LYy)f# z(u7kDD?xW3PP!oOF@fj=>07N&pE1^oSVS{hORj8q!SlE!x=u#mWM)%;cw1YW8cb@{ zYKOkqKqeY+)`c&g`+Z}JXk_Y*q=~0V)FT1?LV1UMx_5R+HllUH1qkv$@W>#6*z>nX zI4F*AOu4e0I*?oR?(NU&J6=xK5rK4>wOd-6rIAZHw`FZ$J@^$)HSV4UaPPMnG~>$p z0*BdPhWbVajxBlyw2s-0c~xH%WB7t9*4tMGi(OeXDt$-XlkTdZTTP%5CsbrI+-$+A z*u1pt;Y!<^f8>?wOs)p#RlN7`C||O=pJJUZ%l1zuP-2{$QL_i~sM&U*R3nAPd_ z6~6eC|0NS{P_Crgq$153&9jkFMJ`OAC0R1U@|-!#dSlIP&W0a-;3!0MgGwQ+Z7Ba> z>s6oYqJvF{n!tpoXiM5|QAG`c>XMi2$4`pN;f|r$;5UOukm9QJu)sa zP_Om0F)`%K%6hHBX;6xK4V zALxO}y^({TEdy`dcb@|HGE+Rb5!952rw*?xUv0i%l~yU)1QJzsXGL%%yA1Cw@1Xca z;nUh5v%d zH6E_0ZKA}1(=!v{>k=kHO!|xj)n2@MVie@9*}APx1OIf~!f6_&or8H)KLw7^?xZL*>c`Qy~^w82c%S+K;gtxRUb-r)PsH-U#K1AR5+ZUFG3%y>K z9rOQ94(FC>Re^1qg_^pRg!YSnWgHUL9tR_dvqR&Pw*=FhdL=T~3l{ag92sWax{3?H zy_Y=7R4Yl{dx~!tc>CMEP8YCrs}97e6@B_FKNo1?mGAsS$Dd=vCKW>rmv;R`eu2*P z<-{i%fzxAlg?5z6dVk~QBCtD)4a=OJfK>v&v5y|*jogGWuA_|vW8@MTG#D65l<5YX zxt%~hKLZ0g`H0RTvpkSbN()VVKLAEGFt+F9THM48=&cI$;2}|%^|pi*A#4}5n%gRD zI$b)LUu_RvL+NGrS98~m*W1O=M4Z_fB1r!aw;1Ku>rliORZ{8~1zN22(35b<$%u(*K z5!^`{cXI^X!l^MnO-)Kl%HQ|xHuLt!%yHfRLk&F=t0}qxWeR6|F!n$-?U^_SCf!|4 zujT3wkntiz%9DR{);cO@J>v%&+@11xcsP7{beEdtv!Rc8Y+Hizav9>p#PXa?^v^lN ziXEh}7g=95qcH;|XMEr?S|_LRfzdq+Buf>zJF!X8zklR#m2nng1_e)s<=!%CIsvHZ zXCHv6AC{N<-6HcZE@d$c3$G1I@HCh{(+4@l4Kv$U7_Z2>*0u?+6dIYb`5TH+Mep19 zJB646LO_4)m}~eGC8oucj7Z0trDgcUBe{2LvdqS5$=z-vHL+5HpW@Tb{usNv(i{Hb zyl#f0yVH{;?X@z~?F6GR39z4jjAU~<*3W+Z-*{z!A7N(5$^WJ9LiQy~wEn+p?k+sNn1pTG2C%9D*Zc+~x zwp!=C6)*Q~IUm1}_)ppvg=DpRkAjB7SKy+L>r$Q;6>%S;M=Eosu9mG|itFq)ZbRN9 zzr@5ZbH|G~D0Aju2Qru2*{;X_%lBbs;H&A)AI;C7J-pd;o?G9XA}jY}WgMU)gHo+#IFma&xf&?&aEJ#Zwtc7SC|cCQ4gRYie(fNd z34D5*TUtCpEh-i^wQSRK#jt>g9>!=~2*2hef)zu3V%ECh;9hk4TuF+*sV|ta_^J>n zys}hP?r>lIaKqmffL8cD@tJZDUYUu|CxCEO?SpsF?gBSW9?;UwD4cG{-}VH(-b3UYm-#@ux7w~B9_{3Adq z7i&OIMd~4FgzbW+rzzSDUMGG^}qgx+% z%sLtu5cjf1xL$u1LiN!@C5hClo#PhT@own6VomSXLKPi##%ZeN25PBRgie6b(^dj_%Qs^KY% z8;ll9-IU?HfAe)4j6AHlRhneaN9S9f$5zyHYjTget4wOba{H*uN8xjY_ZnDXP+hpS zV_$+CWun2_>u+z4=K3Q(F=8T*W)yepiJHm-J(G}Dz^1wO;U-K(uA}91CwmZWuMIXl z_q=Tk=yfQUpg9>j!$=Xy@KJTvGV7a12#efG$ zw!1C+5}R4`rio3DWC+Q;vi?|G+rIY_N0VkAfcwMmv!y<(0~5IL1{(KK`6UvW$rff$ zS^gzg0ZUCqAPlg~Mj(u)VKO#{d-8)J%j7L?em^-$cE&}~JBl`NmQhRSv#eTUs$|el ze6apZabr42Q9Ts{&mciuYe}0N(4kLg#_Hvm=gm2*MKr{bM`;JDX{1la1{yEQ`Dx@sWo06gL zv<=R~t8M=%9O_J zzO}K0GPCviA`{C?$=%>qmsNmMDxub_pL<#RdKBMcD;nYzmIT_D4MRgig6Qz+k8r*) z3fUO=ajj_Ei}nuhKf#*I(j@#60DKsi5T;-c&FUc+{2;cAODdGXUwvJLXV&5>9K|R zalRwr`2(r7k>QXyg505K-zArUGS)=%KqBI-NRr9r`mWTiwu+OXnN-)wF!1AIh=#AN zzNr3;>bWmgG(!|vNJ)y5NUq2@=;8^Y0tHkM7X-drfSyAfVH>Zo?@pJ4NBm(;xn#t6 zDVf|krU=2GxTt5Svh;g=X$(%r_^AK$w@ApN4=L=@S1^uZV#kVMLN+eE>(*TT3rHBm zT$uz&1wxfR{f>=$A{Xx?5Ej(P#Pkr&Q$UwHG+_}tnfbFlW^aYt+_e3F;LyL6kc+c0 z{DA;#wQ%o5E{E{)N*};H5f48YthVSZC}|6fXQO91z|RR}?e2=691+JTa-0UxNj1z1PMK;pp9?qn%BE5*A^(&?C*5%jhZ}8xc2rq%BB?}M{Ycaww$Mfx!RLr3 zoLYq7R{p`0ytIHDMQD*Vgb*$YF@5GE4Lrh^&2)tiscP6PD7zZZ3k-F==QucYkCl-m zCXd0H1@ud^e-?i!Um!ZMRNi{!(a)`v$`S|jItW+?ds#yE$@WpmBccw!DcbtNQ=}vL|P|xd(8g5s4ls^KeFOxYz^*wK}d|=l2_8Z-C%mNCXSRK z({#eAUrGa!l{=BM+R6$Z{Wf*CL|5i?EjcY;VdrkwA$l+SWP8EA22~2Q(SYdFnzGH8==(TBSN`93IAD*ZY2RJ} z{OPVt{)>KDj5$iy{HA;$KL7h(1R+~pG%%$NZ*6Ofym-ynn5=0lNCiv9T0(}<52gtS zr=W=Ay>(UP7%4*!8>R-!rl6goL9Ls|Qxdt4WzhtK)Fy&SQ!r)BTfQYE$y;H`+)C0Z~G+hG_=4(DU(3cF7$z{67eN1=j%7CJx0}6gRGx-#b zJXfpw?g6Otq+FTUjaEiY$QdL|+T+OGaD77+5MCVV((Ck@GYPU<^tpiH{am***j0?v z!23iPHxu(I>1+AxKO}B0 zW@C{8#x0ZpJjauu+Thu4`+H6*j;o4tOfcexPG)OY2VdBMPc{cE6pk?5W_tjah=Z4| d2NwKT+K}cPuO6$__M8F!JAyr`ldE+);D5%cB?15d literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/illustration_training_lead_01.png b/selfdrive/assets/offroad/illustration_training_lead_01.png new file mode 100644 index 0000000000000000000000000000000000000000..12f3f6bae8ccc2b565d99da98df17dedc6c9a889 GIT binary patch literal 1515 zcmVPx)rAb6VRCodHn|){-br{Egzst3qFY{&d1)VSJnoHJoV_ll06sJ@fqB2Cr6h&ny zDu^JWsNi44KNbB$+&?NRqD*v5=Z44-94ZWxYc^zE*Zk7eS=Z@s;-)Qaa(9oezN*a0h{W z+eB#g?DQUr*Co#HZA)aoE*%TfaiAfKLu)!9uN}Y!v9vri{ts`Kdz8*21LbXMI}+HQ zEHWFeM!AreE>tfb0hnGW&b@ zT>!Yn4kObZ{p|SoWg9riA{}`Jfj#O30Qr%>6JIZV0(IjXPAOXq&UOMY$GSLYAOYLj zmK3|Z1ZO9<<6`V2v0^LK_80^02Lybv75hpy2zr8X`Bo)9n5ksv*H|DR|C)(jKdC_q zZ*(i%E1aKLBJ<=;v7s^dVmgad^PW69+H=vA2D{w_OfX;t#ijVp(75MSQ^{-X9P`Dl**7fuqYr~_d_12( zx5jx$dPM0O`oyhxcH-0ovdFCNVY>buUS%zI#8zXAPaIP$6uMoB9mTm2e?PuMK9*^} zS=Y1_&Z=GGZ>fwPzE6c@Ik_q}c-+t2zV_r(109#@y1u6tfC(z)rTnC0K|%)Tlg^Ci zcil;oT@yF5B*Pjpw;t`q?`1+ zoygT2U#>rT7f$-@MX~2CL~&cVSMd;tj+057!(Bt)xRt{-$Rg9RhH3c&2>3F$#MLSe zLOILi<{l+BaKsG_uC$9WHF6bb1-gRk9xy?rI;bA1D-e)jpriR;V6+gW)eS+xi2?W&sdxZ5{lO!is#s^Q@sl`@LriCJT(0Ah_&Y}ZMP^oUJ z-|m7L%aF1E^2w8@Kg1T1u=6c0I9sfrI1mr3wONLYKbiY*Ma~0O121Gd;y^sC)@bS5 z$fY9>;-6!7SPi;Z?C?)P4}}xiPv@(5UdSV=(ybY6KlY;~^95UM;|On3mRN6VT;SWE z@}G*3bE&mA0-H)B;A_i=SllBB@DI*f65-_G(Q+ip_GDTBVz4|dL}>snM-R^vAL3ML z!OR6An+s7U^0+t;)>nw%7@8pf>(3xB;x==tXy=0MBAbrB#=v;7$gZ(#g#edck0gd( zDm6V1ayAuxj4|W=Qp3ivRRYrEk>t<^#ny8mAIm7WX*&NFe{ckEAxg38An)UX894-- zR>j2k=VZ=67V6qIF!HnzW%;?m#?~nTews_o-AerMFhwvM^|0D?IY53-1F%!5rGBuS zcoJ6=GQj;I1I~ViEuy{Dv~gSo0pv+si7&?`t#9LG$1_!gYq(Y*fRp{({{xVPKz6cJ RzqSAX002ovPDHLkV1j+wJJkP)00001b5ch_0Itp) z=>Px+z)3_wRCodHU0ZAvRTw^Jrj?6#@UBSQ-L@zKcCS>BivbhBpd^BziD-j~8Xxsl zc~f6CDi5M!G)g1ksyskUKnd=pi-j0vdod9a444*_cFXR}@&C773t>CV&dfP;W_Ng* z-I;U#|Np*kX3m*2Us*!x=-<&<^KVWD!h3LAN3e-fFJLo~NaN7p;5I_o3f$uNdcj^d zBI^U}eZtt{lCZEXeXkRh>q6vIF!CB>?8Qqp#qYTP(tWl1nbs<>GOkP@vO*{NE=H~# zngG165M^bwuk)L7`&!)Aw8$XvERC{5aGSnB^OV1PaqHPLG#!jSr!#GfDAE7FbaqH zFfZnpQAnejJSB2>C~?DZv9KEmztsp7uVa`O^J5*na`1@j8IjrQ)oMR0Yz3lc@*u)& zOw3=Z1L`r`$L)5WDRlYp#CPGI`Hb6yjph%XJl#L#qyAHSC8@`-3{OnFV9D|&K=Gj= z5_b;13`?Jz+(~UdtMnqLn`29KP1_4saf5kSf?85qR8)0YESKIdD5Iq`Qj45!iMFtU z_9MJiy2%nc0iA%r0otg}jUCS%7m&_U3TY=^KhJENq8If&G7F51V|`dB)@w-t0iC22 z8IA83^7(CWiw+6kz2)#i@!@g7#uVhpBajLPMFwRML@|iuAfKZ*O^oc}wc8}RUyxU15a%W3;cCm;? zcyb+Y(A?uw@^3=}ofkQtJ<2_oi3CzyF~=TE+^!V}7~yL`U?d%IARfeJLIdtiTo?Jb zMT;g54i$EQ9rj-CXay!fJctYN2~1ltmFps(`Tg8xcvPBOu{y8s1Y9M2F5_@jsV{+H*$F3b_1^BD~`V$yMMcjxVd8kQ|!M{xN7tW#)zEvbZ*>WNNQ67Zd zMTK3-sZiu?cvN~)Hqu?G2Y4v)AtG#v>*-!@lEJGCUf*0*^|s@?fFnV*+m_{u~DC=)^1C6kV$8`nMpmd`5VO ziQ^Uy4f~3+Jl37r=Tr{IM9wrvW`O_rFuYZg)(GzuX}sfrC<97^(iY8i{^~?7M{d{2 z8S$yQ#-umGJ3*L;71NIF%>s#wpFT~-*eByzSnKBu4+en5Y*m85tKXLvY7}nb>b@2B|%fO72 zM{|?m|NFecY;eVxoC<_rfLp-F(n9eIGh_h9==OMD7S=Py{#_<=s;PAW(aApF2tP)U z*FK?PA6^+Pjdve8Sg!qlkw=a2DR|I!#Eno+;BUn<0EYd)!LT1M8}>^g!|x2=2){FY z7#2M47hjT}kqZNq{sO-X-3Gr4eNI6`H~fAu7~y?^xsdHvP|y=~MSay3`HAnrYSucp kYVq@OWgz(Hss5?|0k-D_JWVmbJOBUy07*qoM6N<$f|;$^RR910 literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/indicator_wifi_0.png b/selfdrive/assets/offroad/indicator_wifi_0.png new file mode 100644 index 0000000000000000000000000000000000000000..9cf9762ad3d8f3e20fcc8fb9256c958bee6933ba GIT binary patch literal 3038 zcmV<43nBE0P)Px=m`OxIRCodHor#j$HVlTlY0~>nkN1DNcG`4vAI-J>KZW$jvSd>fKvA?X!?CTE zDG>ODlk(nt))3v@-Q8$8_rv%+yx!9*$K&hpJ)iG-k5Wwb0 z%0{7IXgtt}O6L{Dm!cz3=%Vj5-U=K5W>d5Y5J>4L_e%{F&nwEWl{zqpx&Igf1z@R~ zssur})4!JFqT;#Bw@QGZ1B71R)Ch`dK+sb>%KvJs8c*OGK)lj;U5o2j6$DqL_$h2u z0f<#VAmwwXf2Yy%9Y3Y`spD_-hnE_-jG~!GF%U@cT=&m1To04$zQ zbL^BR0RZq!H*&ffCnxr5Lz(6-MHo0nYiDVI2g(O)d zfk2DK_hbH(&ewTfgt8f(;E4503-{0C7Y|N*05BrruBC zrxfAeserK+Ytm$uVy4t}f~+GLN^Y0Cm7ED24|D*5m;#mD{iSk$d=(usqWY^Q$-ead z3M?)KrtYTeKp-YCQNL=G@c%GC-MgB|Ui?%+(gPL&D_kNFC+@;3e56tW5PsM2Hc3SI zpby`_(-{d!C#0B^5e(P(HqYrx_BEZipGYdozDx{=F()n0u6e z6okx>f!V1NW-R?;^%%p_a4aJeLC5#J^0`PAQr9^lWGCLSpq^dY`+&g1JkKgyo~%CO zfP{r|acK2R^22Fsh;^1i`57`~@scQhn=K%}^?$$2ieJ31U;5SWaky8M-}W=pF;cJ?HK0CP!jxWqMJwg3P? za3Ki+{)n6z7NE7}le@MnaqHD>>$v2AwWFNB#3~S@Q9SBQsNQ#_O(w=7%&lUvaFp-j z`?X;BLFoiZH7Z_gjgl)Mf>p>Z>`|NfC*H6}=2H_RWPp%L_(W>b<^`X?3#P9`&YZg5 z-17iLERLDR5t0+x9X*~SU7leS7xuSwcBs>wd{L7kbSAw-hhoE}6I1`LYr_xMNBK)k zUFs#*I1hJ$FE&e=B{zcLlwu!X1OP`j?Fk5wiY7$~>>ipTYW-||X41tJl+QI8OX8Bn zycC=OMNm04aifx9O4%P5a00$j5FiLmN|6Ge(T;_%eV-K)TbXtOEHSnd%(DNVddw00B1< zEzU^`InI3+1o0%xS1|}dBLS+<7LQc7baRV!0tAyd!3+cv2*U8(rq)+1il^LKT=9J-`tP-VEMF|HmFRnL1Dx~$ z`aGq+w*&#*N6!?HMZ0w3QiYXzo&W&|sEK$7#oeZmRKBLpv-D|}bM^Vf^wF^57deWW z`#uwM-iuF4w6_AoQ@zHgT4>y%BHO(*zk&Hn-@TU={zeu#RRRKr&h+ zK9C);x#V6Q%Vo^+dqGY#(Q?yhtR#B_COd<3_%#Iq7uEu4VS@I#RHRNmmnpCFB_~`b z>2!`&AU&jTWJ2a3fGaJK#ijZ`%o?@vA{{gMtBEA5xxE#BaDo`ajJ!a=yzEoFgmMBK zwmq-n`=x+x{klHpbu|(nq?E|(QeaJxOvYhKE+BwIEewB0?O>{ZK=4P;+(iLF!3dY@ zlLf^AUyT0R;emlw0+5ts8GzKh{H!@oNc;i-fG|~P!u(?~&E?e>#0g_d4}^tLMH~Ww z$e-Nblyp6cRahTh5vJAp07UFbxczog04@RJ(3RpUi37|5pn1)N#9X5k7RI6g0(TjY zLz^`}G(Yo_m2izq=2WLFCKM6N)&Rm>FwqZTw*Zg@0$aGl+RsH^=;^4Qr7Er4%UDamyI8r1H)!O5KJVg z=TzY2rQkX90tTXYEQ7h5n8V1NbE^k|l#gE=3zp`rv-G*dJg)l!Ef-WZ2m}E9eMqLFubUT=}K&k^lF#j~6i2hq4vIr`pCfmWRg;Es= z1OW1Uic2*Ie@k?LMR3jebC|0J1i=EZAHi~?OO8yuzf&C$h`ei|_!Mm|{CM#}np+js z1cFvwz)<1$Wc8}Db~Q0W@Z?F%Pgjr}o~j;c8^>^o3~q?nY4ol}R#jE32?W&Ot+!~C zp3#Ek`Gn-HSRpgF{Nq(Lsli>vn_3DZGgLs2RG^PExzN#6Eeb8 z5wk2!Td_h%zZ|B|t5a1VKpGM{6~Y{gfN4khZgqR{1{iX83&Wqu6GNKElxhS4Jh3Aw zwMC3?kIF~T?j$h48~uzq!7KpSi$$s0k&yAhDK!Jk{pkPoNxfF?dEybUlI{(60gX*r zU2UMxWObGxGAAJuv;u^wpe$~=DsuNnzJ{;jlgG@?<^D8~uvFDjwID!Z5-{c#*DwS^ zRo%J3C*|(p_BM70Khg23scH})ISClS5}C(6iUfYi=^k^GAn^%M$!q{F)``88)%6L) z*G{_xb_whf7?D8r?qG!H>_alyxD*OL1f94U1}P?42BWJm%8aiXY>JPf)I12Jc-BZ7 z7oUAd5ipqtL0y%3eaZsnoYOQ21OSRUq;I)B5(2yCekWlFkY+(309fr dUoHEgKR zoX<^yKmeemOA*JCsQS^7Y>tLSn9VORSO9APAeV=l`_iNKo0MNuAdr$`!NyA&IlsW- z#f#azO@TmC@!k>iKtOBGg|-F)vq#=1ZnF=H3kVdOqNYF~1yS(vtk+lF4a`MmQy>UJ zplfIHBaZ{2(h%bD^X8~I5J*v!d>?6G6|9KL;bW`GYMZAy5Fp^-765{U|Hi6NBe0kY z_Nt>ML4cH{G?WJrmJrs2YGKn2rDj2Z=A}H$_$}`lgp~)qp^X z#m5sLoHOw}C)i{`=p3@H1_TH}3XU~|F(A+;u6}#?Ic4Vlt+{4MiXcK0h;}nOkFXFt gyn0nGpf9KY0aCHP+U?NOy#N3J07*qoM6N<$f}WP27XSbN literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/indicator_wifi_100.png b/selfdrive/assets/offroad/indicator_wifi_100.png new file mode 100644 index 0000000000000000000000000000000000000000..dc9f28fab3917b000318a78c62c11d1969ea26a9 GIT binary patch literal 3270 zcmV;%3_0_OP)Px>fJsC_RCodHoei)SRT;;-a=}y#6#M`UBM?oCv>cNFQ5za&&~Q)!2^lR*%cLxg zGHt5KAwR~!QR>PJVT6N;3VtN$h^V0WF&dSVjv#skB^3ctuDDnruJ($X1s`a(bGUs!f$*|oraCF{j)`><^* zd{BeUY~Kj4!pZ`x8X6k5vz`fQs7EiTY*pqU7znEDB7Ioz1g_;{3Rn%rq|ov|u#Du` z#ImlWE|P#sKbWWvDKM1fanJ~%iIU@AuoRYPNm8t38MFkM1XTI~MC}Y12CDo4P_MEI z!<7(^!F?pfy3ia6CJCr`UAsrYw_!Nw`kpn}fkThL9WalCSRaCesU`sx-;E%YR(zKb zg5t>rCBz~qCd39$sD+6{1lGy;$3|f@)Bm>2(w6r4}G}cJPD}$-Z-LP{e{rOhf^6TL+yoIU>eErhD)EE zB>|PM+qla>4ZSQj@?6$Sscu~==E8L(!}8KEY^_^Q0xJIqjJq1fgLVD39Irz?YA4(V zza|-8w`sq%N}}?0i+2S~g1v1Tnd>TxfV#NVW|%@UyjS*3%nyl^fXY|vUf299;lP-7 zG z!2un&9b2-{S8*qP{E%db+$|kB2}po*DNNU-10Y0E&)doh-sW@ZP_c%G^?5Tv`xu`z z^4PToO8DX^rI!6*KL}Ce=SBE5FN$%-NkE_uMX~N%zZInbhx@9vtd128&OA|AUr7L* z_s0{9UX-VV_#$Xja|nDELXp`RGKp9ibwwK`0Zxxc=}nMk!%vN$=RuXeRN&;hEQ1hY zq+4SpLoq4TD{2&9M-IG+-V2D)f<*dptQ*_~X~|X!z85CIXA(K%`C#nr1((1Q&?P4= zX`de_6D!Yf(1-t`FyOno!DYH$T zQF_`)pS=s^>g;(B1#6U6BZjiwrl>JKKz9R!Sy2z1O__-@C4iOjZWF`sqZ9ib5640O z0!OmcB`9fM|6AxNjz_%0`pfVX{x!4oBKX&rf)v+b77JAJ_t~Y70v-k%@+L|~S~Rkz zD$3ah)T-7k?L+WB_?FcaI0t?N1EIXdUDNt_U!Y$<+DWh(Y{>O{EJ52rko4Mf8#W_K%H&QhNsbeB&e;GL>}be&U=zTD{PSBcVcMW$T6eKlv(_M z?gQa_pkMn(P%ommC?QS<>j{C*yx_e#ukpM)|7k;dI!NB z5aKT$vm(iQ_P!Q&Uw@N_XO9MS4hQKsm1cHSL%FuF!w34){YW3e_qd7d=;7KLTB9?Vby-Lr0Y-aooz80X>T6@1Sx3P{Z?j2q?O6 zpe_wM?W-X%6Lha?MbLFBJO{b#j)2At)UT0P(4)59eE2uq4qt6csd|jO3I?f%@>5>WY?i8}*^ zJNGC%1+?JGpFt0nXo|cuah?Puzr*OhmG}P z=vskh=V~-kE%xH5WKY)9l)qEB+6q?RU}8N9NB~v55((Dm!8f&S zhQg4-@>rJEV~EbSWI11+Ng_12wNq-}5u^#Ao+)4Q0R`zkcr9Vt{AIz!nQ0s$DSyeBWKf@;k~w_@o$V zK+cA|fs*jfju@rJTIDci6o*%^vz1}hD3#-TUwk|p;!Nc$#!`1hZH^53_NlBqjMLo;mpSF&1HS4K5$6)BOUg(GCfQYqkvD;<=(P3?yB5@sHhfnDBymW0}tTK zHroZ_lg^%_Krichj52hF$fYs@1Zo640%^)y6n-V7`D(w)&}9EJ0UryRMH`Z+bw3q! zUC+f;1PJg~U@3$w8!=Af9BOdpVk-g!R8Q7S2X!aci>M(P-gv*QO7W?OKn{Xc^-}W{ zb}DH#g4pOYW|=9Az%{^c!1kycD!q$3#57qnSaE)f7}awEroYb9EakJK9vkrf?_k>~ zZuORhXk$=GKmw?BeJ`98Vz3h0q@K}Slfpj<)V)I11I}dlreH z+1SB|=G%uNKf{nLCxGItAKlGb2}wdqg25pL#-S~}IqMzfP=93AA>F>H@#Iqehw>Le zql0TfBZeA1)Jvr_s;D=wY3xCxjXEQ_ip@@RuY+7FBfziYYfw3Q#-`Y!`*ghpLa$BZjl#U9c&CX{+oG{~eK5-#}7%6$L+lo;CuCo=z|n=0egW)f~zmHtfo@ z4uW(m#F4ceq!(`K^zKB^t?`Qm5Jxnzw7(O>vZjK5CNj9Yp`bTl*&#%Xml=^J`QX-0a}|ae7%92`7Z56 zfZ(cgon7lB|#5#yO3?I=#s zM{&ex&>KDuFQAt|tts#{%lVA*ZDN^ARw6*fH^PrW?`JjA)ET75!g8sH2vAv9Sgia~ zRhs#HT0O)ds*RbtJD`%f697#f**j_=4EKMYI|n^jn<)vV>(x?JH6zGX0?0(YOd?Z1 z966P>BxsgX4yBnhL4Ca>!XOx#N&+fKa|dS{_#JnbDRB?XkMkG-PS+a9aq$ORGd#MH z7nL*uB*CH3+R!eWV~IvEUClmD>TZ5~tq4$QUx4+os=WLlbvHYEPf;!V^X--*K;@kb z8ViUkdTDoRuh_E`hFlGmI1b`;AFI1qufNMB3lX3)FNY|yjh#=)g73KxB@v)frx|8} z&Kl!O4$W7y5&Px=$w@>(RCodHoym?IMG%G=+ib?{U@XL$MMzw@vWXW!;)HkxI3gj$9q|B2To4Bi zz8Z1i6?`xto&ZZowphIH9z6VCJ9AWBUDchH6`7UQlOctwySh3nGUBg@$cXHjod>pv z_V)I6G@T=k54+1)+f1k&KN&9}+((_D1K3 z;d9XvD0I`i;yVHdfSDD|0t7NT#(h|f;W=XbQfUDO33nS7C;&^*R3r%8lm4hQ=MB$O zK34(+3qa_2t3*%~1A>O(G5#ZSwRnKs0OE%DW+|a#QV<*g$;HJKQRbaR?ZkX1A&Z>tA9d_>#vkn16MUXp24I#IT{2qK4V~b05EzyjZrB~0|4NP_`1L_ zYBe#+Xac}d34!a+S+m#eDm64fXt*pOkT*n86bNK|jQ+H^uJfbRp5#k_;F7>FxK}Y4 z1Ofm{y{E*3znf(0tApYi_glX1HHzUpj2rc@_i&{m=Hj{Cat83eL&*^?b?(gV;!v*; zJefkDevD1&m8BEiyIm>3Bw5l}z2tNO80cpDCRa%zkyQjvdf! z!r1V_@S5ac*Oy8#=?GBxRyV-l{gf2!71kP66T>xP{3+M`)YOT0#dO^y%SLkE0=@A7 z0gkDNegs~D5ZFn*AkZXmbG4pbbtU1fMNV@?>eJJ47K?yZqAlofz{b14+7jJ$>EsLfZGB903iuU3CKt03|oNK zT27wYMTuL-WLw9j2fQ8S{4rjE9F5}9!iDPfqO{4tc!Z%>C`MrSP#;n2XX`VAjwWY(?g@{{OGe9*aR3ZK<IDHGYEWD=dkQfS$Tj=ngT^M70W=cQO7~Y4=y%Cg$0$a+CAR|zgbD9)R$9n@?6n~9 z7g-)9Ac7HU070cy4Uj-mX-&4&Zr?I12m}CPK2Lwv`?e=NgZE_agk6&F4gvw7^xr82*kaO4@Cqb#D_OmjRLMXf<1;o-KiPk!@fsj$mQK((KAnC0B2y7%l%mec}6a{ zId^1$@k#)ak}M2J&CAakbA==?000Pmg(loT9@AW3O+~B-Hui*@7*)hJ5Xk&l`uGbJ%rC%K6+DS*IJ#?PV6njadU zaaomck4^4Wmy9M1;mg(l!rU;L69A?JjmP3IxR~rn)>xfn^`vwTp7Nv=g_2l_q%2i$ zngZd2B#rXzBzesy0Yg5Y9SCH6o_eZp?GO_(-&EJ&4Orr`@nd#im<rZf2TMgka?Fv{#Uf6$dgJAmbpbyNg&wP z5YRUGA$h%`yj@AckUXU%#-}UD8lI{i%Qnst5@8+)-)T%;jV!9FSP}@R!CP<9W_d;n zmft4?Z^d%?39A!2lCY)69Q}U`C66f;lNd59DW7d=V`~FEW&CiH4&Ue}PBNh*LKQj7 z*kvnTXz4G9>HXwX6bR6Ulum^(#v|a`F@CbTy<`InvAczl&*T?F8po7M1OYO!BPp~+ zOlGyKAkCKz0nXOy<(?G&g6-&i}0F6n(xLZO)8wf>p z=bW6ByW88_*d2UH=ZmJIL4f9@U=&Mc?)NB?_ysTb7$XNsPJqhF2H@hI*h^VlpFna| zsv4*os2b?dK=I+AL+0pHa@nuw%O8qg7Qf^em;I;X(>k6iJ&}`)m4;|QhCd?yMEt8b zgl_4gQ{uOW+^1e!s0L)nx5U4TW9bKd@kF81t72`^fQs)ps;CHar!hMV|`&^^^P%ib?*JX`_B3NR;>Px=>q$gGRCodHoJ-6lMHR>WWDrFVd?7*OLIod062+*fsBxn^648h*NZhzl7n%^z z7*`r&bm2mcG4T;KnFR~*?M6wA(LjP4V}gO8PBa;CV3;Q}z|4I9ewXf#zI|W)sH$6i zZ=d9!?%TJ!>eM;^K2>$9?%jFT2FdR3?heh_SKz$j_-u||FOT(eKkrs>ZqB*a&Vn-~ zc6N4rW+Oxc3{G&i4t)+dACyk_sN++~6e+0mDexrZkT8RiL688a>)Z=~j`yhZbCn4h zQ0@rH~o27u5`R_`A|g?ObEg8bdIFRh6EMI>-^^q)#DBHmJpAFQ@L~< zYbC)JIerm0vLM7-NPzQw(=P&>{KhYG{G#ip`Qjw7%Sbx&NJau2Z(Yv^I)BK0JnBak zr=cgn4J5;f*n`PvB*6Jj=Pm{g^hW7tfm1ww95OuF zubBBy2PXl}H`HGOM(5ABd7rD!Dvm)0yNqBGj08B}Q2zp8=pQAn1&&j^ks(NSvNs8E zzGdim3DCPd${3}Y1th>Ra1t`~noaa_8U(lyB@F#3bM{m>O2q1%%0d#*2t(bA!8#Z{NXO5$Fc%9# zNCru<4ni0`A6*nV=aK-WRrW<-?)O}eA@=V{7fxa{VpW;g)|W~`m|ID?mSXqt2t<$& zQ!?db6!f$CeiJ{b#Qxn3m|L+HhOAV|q^hT|bxDSl+vN^pX9tdZvPS}xl9j&wspkIn zRj!aZs^4nC_Nn(*7;#N7OC+XghQ_g2r5> z-6siRgy&Xi%bC`9xPY;Au3eh2T~+v9XQAu~87M$omGIX_F>E)bCv`~1;{_QUxQFf{ z&PORnyoel9bx7)NH>ZNo232i0%piJmjoJuLQPWG=Tt?f2kZX} z=iAqtD%}?6SMBL}uw+_cPiSjjup|pxd0-SHzzWt8=N9k_?2aW#rFt|h^0R(V1Ve(?#Bma4;e_j(#cSSh> zt1mD6xw;bRx!2YyQPyXIlK=vk>5~BKFqqRJ!=`YlcP}-{=iWlwB!ca8Y$N=fT5O}K z`e5njpd`RZ_WyPPsl+$A{EdREcI8{0r2Zn}In_S z-gIkn$5)l8p3{CKUzuD>vF_muFtZL&)v4)uND{dE7;_3}qob_EH8ob#`yhlQFeegw zP(0Zb(p0ZS_l4}!LY7t4*U;yJmH)_*G~8E}XmgI9rf3gChNB$Ig|T2STt$~4>n$N2 z=YS=MQbi+u^G|?a|IJgBo9qA?9GD)347S6C9mh-|MVt4QVCIj1f#?k-&1@r?`sc4s6`^yq3Nn2RN0B`db0YUnzwi+H2Lo z+Cj22j-V2S1Zqgb?C;DSELuNs@aLMj{abLMe(Sv!Tn(-)@M?~ZS;}df_w3~#ICm=g zAMikd`#Ii&jt_H;D(EW#B*LOZli}Zp8QfmcNT9`vhM7gI6Ty+c1`jIK_f`sgKX?zg z4une9{DZQ75AFiLjG;T_YA^lafU(|{+EqFZ2u=XXjlaXEXqb(X2!?%s4jpXqgYw@% znIA3Sn;u(yBYy$*gJ02>Ao=^M(zMBFU<%r3>OZ&`HAksi07HEM{0^*B9;WgyfIidW zdeg?wt1N)QKLY*+a*`7$^9|q_Xp~qMz`$hSnPof5#h@31?}D>n zC~_Z)UcVh4irh*Jc^&xYP&{ALQ__A3gj}SHZ1IeW$8i3a(ig!QFm$<_2D~aG^UkOe zHBT^8TZ0Q2%&F0jz=s;#K9pMyq38`v_5PHj!da030yw(<8F+h+#_Fk)37?xG!tFiF z3I2FCB!B>B_wEI+3*O3n3N+()BSg3(ACAvYnPGVXz7kOtc zibU4q3ZmZ2BiGTY_?)IM4xVDlLlk}=aE0(7Z~@DWEalE%_dvMza3wGz#j=g-Cy#(p z>K5SbcpEqeLW%SAKZ4JJH`eQ0_L=)H1vi18fJZ?{`TnxHxBfdUZEm2i{EGrU0bIiF zEtGQ}xE|aN`jYek%5cxXD9bE>k$woe$Uz?ZBv`a5V_CJ0zN2i{FMbWW$RQqjO{0po z{U!``KKN}5E1%@vTS2G|Br9D&T}Fm`KvOxzjqg}l@OZ;B7QkSafWJ4e@PpiQ%`;D? zJELC7`t1ff+J$^Lon{+U6NY;wFvKqs!?Gj#wF)|X9QdX$l3UiQ;Lt0_s`kO|-l@u2 zKDauUO^yRy-U9v&>hkrW`ydPbv8u_HuYunH_Z7S;3&m2e`3z%lL7$ zz-WQd0vTH%n^nXVHX=m7mU=!2t^%(p;CAl+7Py<^oviX5<2cHuSOCZG1D^ta0ZrsI zH{A)wJ%XD+0v!1+&}V!4k9q#`O|ZpQwgKn)qmaJ2eu~(A4EVFQQHEpzoc2|{7f?(F z-7q8@Y_+a9>+=DfUoFa=&+pqr<8IXK04Mp2UN?_i5Xo78X6A5hq_WpmY&NOaKo)RE zP%Hwd;x!O$qh1^vwP_?cV51_+0U|+^{|Jbv^U9((iUc^wy@Nkk+3M~$e5L!Nzz6EgF>w*6-+*eFD``?VC z4ABBO@7=()fUa_Y2d@}n+ee)%7Ql%&fiCG|)5TX;iW*OcYyq5k3uq%xaPxbI+~!gD zITpaF-)hJLqsGVP6fs^Jx&?5oza;u;10viu^tO)rFR=gwxDfdFF^l9oOCBG;+7t`m z{mZ~#=dfTu*ZhCst&@#g3~Ay)ob4jhr-56@{CWD%NjdN5xRvsM=leLm4THEK00000 LNkvXXu0mjfBZlYd literal 0 HcmV?d00001 diff --git a/selfdrive/assets/offroad/indicator_wifi_75.png b/selfdrive/assets/offroad/indicator_wifi_75.png new file mode 100644 index 0000000000000000000000000000000000000000..bcbebce85d754c65c43f2f9e5c6f4f6ff6f6b6aa GIT binary patch literal 3186 zcmV-&42|=NP)Px>EJ;K`RCodHoqMbuRTYOVEd{a2qlkctMv4!NC}=>GqF_u+Gyy3H5<YO-onP|HoI7V`?X}lhv-b1Mo$;(1VRUqK2GyCBab|WrgrnzM$Ij3GJ=(?tT|Rqm zKit>ij2Sb$rxwrvLkFC#LubQ7Vaw?rb$nGA7ZeowU$~dxFkprXLlFcxUFRMKb-YKN zpDM%e5TuQ$DOP2*v_}jk{h=BwF&i6^51MB?6_i}u%^Sk+CC$!0^bmUQ45a4*rdJfe2 z!`#NBepEON-2tDes=0_B1UTQGy^c2k9NIO=X92T;!LTECXEIt4;CzR3M?yP#4a!+y z7q@RG81|ME)BWz?L4fm3^+&?y86n+0qdwh{>T z8~Q?DL4fmh`Z2H>=l5myC^s1dTL^~2YZZlqfB;R=GlEuYOts+gH86!i?(#)7V2d76d3^iaHKf(f+G|^WMqy?9nF) z;0H5;S-6Uhxcx4(!U1PW420uh?382=-{`aLZ!n1k@QFiAr{iOHBHg&M$sjNlnFV6O zj)=~;?Qc-P0{F&0L+rJgwWj}AGhL>8ojGZBV0`#JXbli9lD!AW3JN9G6-U%=R(t#A*_qB4CXW7YvH_%r*b?6>gc|K>~-Ay zc*Z9(OcKfgQ^PoEQUwZ4wNGys$sv zoOJLBA9OLjUkfjSsXg(iR0x~7`nzxuw)$tGJEyo9J2|>@jc1%MC%MfI`_t&*aSRh~ zM5t}8LZ`yP$%d&e%=NHUP#wv=f3r z#Sm)e!`(x@u$?d5`mE5>$O7*}2>KX2xwOFH5U>h0Z^niOMQLEeJk$O*0rmyPp=%I$ z1wx&qu+3>l(Dt7)EdNS)6MRv7LDT5-pQ-D0IHz=G$n5E~bEn@l=Y)kLPl}#F;Fk!s zX>g3~sKFEx?1vA?J|B6vz%yZk|2Gpi5)6-(H3qh|Z)YIbJm|Mcf4wwm5O8yFpx{dp z`Zf5@;KGMrpblFMKSMCs`$Oy&1mq56;3N42J!M5^sm$h{VJn-5RN09`ae=M&)<;Wiipw{RP?%J>yC1t=%aE5&LWshZ$Gwy zsjE#yKTW7j$~$7~S6V(wejVn8Y3;403msAc)ZKXopX|JFB{qFfn?vB8Icjx3*9@%f zr|j9V>KVTY4n&93;gfJGe0jpn0Zv3S0JSl-uYkSQ50>)X`a?gUFgTI3gF+<@I1brJ`4x{zRk$ot%Z`9ejc7`;>FT}cVT66+}Zv(P4{K~)yO;FrO_!<1m}ejzOK>#eFxR-bY(@R@KWOc`5H z&UFquoDD)*0D~S0zXP349v0YtB1w&9eNtHt{~2;(q^?O3&Z&? zrO(6At8R#_98QS2Su|NhA0ig5IR^8mZ|+jQr0Bf~U%wvRE@Y_Z?+%kgQb9lf*t_<{ z4sS@#QsotLX7nloVR?B`VI?FJ1O$N7%n!gLKp?mqI~lm&J{5c%Md};? z+S!M0ksne*NfvnYs^T%w zwFg%l%}B9qvmeVhU)@>WWPfx0(a;scrEnt*iSJET z_O$;FOFK7E7XLuN2jFob42qnYa6ViP%Lb`?DCdUItJX3w()VFMSj$ZxhNkx@K(^}_ zcf)?*#?pCF6swz14CTg(dkR?D%_BF!$~LJ|mYHD{%!^%ISo>YnL1Phv9R(lGVc{pZ z=JcS2=M+Y{2J1I-=x7siX-=`tW$hNga3@1kd@q=m?a>bu=x`16N$-X02ddz(7mihJ zgWbK;j{W@M>Rd8&9O&|T*loA)EyM1EB=pC)POf|f{u;Wk;EW^`>reu{=D?fa3U~)x z&~ZugXJdiJ0*wU{wm>qgh*j8#6#a6_xfuF}j~8b2B~WWJ-p}z)R{6GZY)}^q;P_ea zBk*r95BzbAKcQ>(2-YD8aOAnL%=Yvjalfy!YcPx!z445}7v;|93x>f4MRlyz=m01AFMHfPa#&GANSv6-4PTk094VJN!04Wu~Kylf)Ohf5hG-R;d)6#4rA0R2yl>l2XD<$?|v`& zQolDg_f=>C(zOdY55Uk^QeickqRLtT@1Fp>E$#Lj7_MN(+I?KMy3PH)EP&Hq2{-lY z^|t$*ZjSbzqF(wp=L1;)=bZ;#3+NZVw0mH$*b8KaMhs589QHGP>~yiOziUtj3*gM_ zVG-=%;q") - cell_data_connected = (cell_data_state == 2) - - return { - 'sim_id': sim_id, - 'mcc_mnc': mcc_mnc, - 'network_type': network_type, - 'sim_state': sim_state, - 'data_connected': cell_data_connected - } + return HARDWARE.get_sim_info() @dispatcher.add_method diff --git a/selfdrive/boardd/SConscript b/selfdrive/boardd/SConscript index 0ccbe6bd24eeed..94e630a641ca67 100644 --- a/selfdrive/boardd/SConscript +++ b/selfdrive/boardd/SConscript @@ -1,6 +1,6 @@ Import('env', 'common', 'cereal', 'messaging', 'cython_dependencies') -env.Program('boardd', ['boardd.cc', 'panda.cc'], LIBS=['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj']) +env.Program('boardd', ['boardd.cc', 'panda.cc', 'pigeon.cc'], LIBS=['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj']) env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc']) env.Command(['boardd_api_impl.so', 'boardd_api_impl.cpp'], diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index a3bb2b0b4cf389..9823ad98509443 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -28,6 +28,7 @@ #include "messaging.hpp" #include "panda.h" +#include "pigeon.h" #define MAX_IR_POWER 0.5f @@ -35,15 +36,6 @@ #define CUTOFF_IL 200 #define SATURATE_IL 1600 #define NIBBLE_TO_HEX(n) ((n) < 10 ? (n) + '0' : ((n) - 10) + 'a') -#define VOLTAGE_K 0.091 // LPF gain for 5s tau (dt/tau / (dt/tau + 1)) - -#ifdef QCOM -const uint32_t NO_IGNITION_CNT_MAX = 2 * 60 * 60 * 30; // turn off charge after 30 hrs -const float VBATT_START_CHARGING = 11.5; -const float VBATT_PAUSE_CHARGING = 11.0; -#endif - -namespace { Panda * panda = NULL; std::atomic safety_setter_thread_running(false); @@ -195,13 +187,9 @@ void usb_retry_connect() { } void can_recv(PubMaster &pm) { - uint64_t start_time = nanos_since_boot(); - // create message - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(start_time); - + MessageBuilder msg; + auto event = msg.initEvent(); int recv = panda->can_receive(event); if (recv){ pm.send("can", msg); @@ -266,7 +254,7 @@ void can_recv_thread() { useconds_t sleep = remaining / 1000; usleep(sleep); } else { - LOGW("missed cycle"); + LOGW("missed cycles (%d) %lld", (int)-1*remaining/dt, remaining); next_frame_time = cur_time; } @@ -280,14 +268,11 @@ void can_health_thread() { uint32_t no_ignition_cnt = 0; bool ignition_last = false; - float voltage_f = 12.5; // filtered voltage // Broadcast empty health message when panda is not yet connected while (!panda){ - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto healthData = event.initHealth(); + MessageBuilder msg; + auto healthData = msg.initEvent().initHealth(); healthData.setHwType(cereal::HealthData::HwType::UNKNOWN); pm.send("health", msg); @@ -296,10 +281,8 @@ void can_health_thread() { // run at 2hz while (!do_exit && panda->connected) { - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto healthData = event.initHealth(); + MessageBuilder msg; + auto healthData = msg.initEvent().initHealth(); health_t health = panda->get_health(); @@ -307,8 +290,6 @@ void can_health_thread() { health.ignition_line = 1; } - voltage_f = VOLTAGE_K * (health.voltage / 1000.0) + (1.0 - VOLTAGE_K) * voltage_f; // LPF - // Make sure CAN buses are live: safety_setter_thread does not work if Panda CAN are silent and there is only one other CAN node if (health.safety_model == (uint8_t)(cereal::CarParams::SafetyModel::SILENT)) { panda->set_safety_model(cereal::CarParams::SafetyModel::NO_OUTPUT); @@ -322,24 +303,6 @@ void can_health_thread() { no_ignition_cnt += 1; } -#ifdef QCOM - bool cdp_mode = health.usb_power_mode == (uint8_t)(cereal::HealthData::UsbPowerMode::CDP); - bool no_ignition_exp = no_ignition_cnt > NO_IGNITION_CNT_MAX; - if ((no_ignition_exp || (voltage_f < VBATT_PAUSE_CHARGING)) && cdp_mode && !ignition) { - std::vector disable_power_down = read_db_bytes("DisablePowerDown"); - if (disable_power_down.size() != 1 || disable_power_down[0] != '1') { - LOGW("TURN OFF CHARGING!\n"); - panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CLIENT); - LOGW("POWER DOWN DEVICE\n"); - system("service call power 17 i32 0 i32 1"); - } - } - if (!no_ignition_exp && (voltage_f > VBATT_START_CHARGING) && !cdp_mode) { - LOGW("TURN ON CHARGING!\n"); - panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CDP); - } -#endif - #ifndef __x86_64__ bool power_save_desired = !ignition; if (health.power_save_enabled != power_save_desired){ @@ -405,7 +368,7 @@ void can_health_thread() { size_t i = 0; for (size_t f = size_t(cereal::HealthData::FaultType::RELAY_MALFUNCTION); - f <= size_t(cereal::HealthData::FaultType::INTERRUPT_RATE_KLINE_INIT); f++){ + f <= size_t(cereal::HealthData::FaultType::INTERRUPT_RATE_TIM9); f++){ if (fault_bits.test(f)) { faults.set(i, cereal::HealthData::FaultType(f)); i++; @@ -421,13 +384,16 @@ void hardware_control_thread() { LOGD("start hardware control thread"); SubMaster sm({"thermal", "frontFrame"}); - // Only control fan speed on UNO - if (panda->hw_type != cereal::HealthData::HwType::UNO) return; + // Other pandas don't have hardware to control + if (panda->hw_type != cereal::HealthData::HwType::UNO && panda->hw_type != cereal::HealthData::HwType::DOS) return; uint64_t last_front_frame_t = 0; uint16_t prev_fan_speed = 999; uint16_t ir_pwr = 0; uint16_t prev_ir_pwr = 999; +#ifdef QCOM + bool prev_charging_disabled = false; +#endif unsigned int cnt = 0; while (!do_exit && panda->connected) { @@ -435,11 +401,27 @@ void hardware_control_thread() { sm.update(1000); // TODO: what happens if EINTR is sent while in sm.update? if (sm.updated("thermal")){ + // Fan speed uint16_t fan_speed = sm["thermal"].getThermal().getFanSpeed(); if (fan_speed != prev_fan_speed || cnt % 100 == 0){ panda->set_fan_speed(fan_speed); prev_fan_speed = fan_speed; } + +#ifdef QCOM + // Charging mode + bool charging_disabled = sm["thermal"].getThermal().getChargingDisabled(); + if (charging_disabled != prev_charging_disabled){ + if (charging_disabled){ + panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CLIENT); + LOGW("TURN OFF CHARGING!\n"); + } else { + panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CDP); + LOGW("TURN ON CHARGING!\n"); + } + prev_charging_disabled = charging_disabled; + } +#endif } if (sm.updated("frontFrame")){ auto event = sm["frontFrame"]; @@ -468,82 +450,11 @@ void hardware_control_thread() { } } -#define pigeon_send(x) _pigeon_send(x, sizeof(x)-1) -void _pigeon_send(const char *dat, int len) { - unsigned char a[0x20+1]; - a[0] = 1; - for (int i=0; iusb_bulk_write(2, a, ll+1); - } -} - -void pigeon_set_power(int power) { - panda->usb_write(0xd9, power, 0); -} - -void pigeon_set_baud(int baud) { - panda->usb_write(0xe2, 1, 0); - panda->usb_write(0xe4, 1, baud/300); -} - -void pigeon_init() { - usleep(1000*1000); - LOGW("panda GPS start"); - - // power off pigeon - pigeon_set_power(0); - usleep(100*1000); - - // 9600 baud at init - pigeon_set_baud(9600); - - // power on pigeon - pigeon_set_power(1); - usleep(500*1000); - - // baud rate upping - pigeon_send("\x24\x50\x55\x42\x58\x2C\x34\x31\x2C\x31\x2C\x30\x30\x30\x37\x2C\x30\x30\x30\x33\x2C\x34\x36\x30\x38\x30\x30\x2C\x30\x2A\x31\x35\x0D\x0A"); - usleep(100*1000); - - // set baud rate to 460800 - pigeon_set_baud(460800); - usleep(100*1000); - - // init from ubloxd - // To generate this data, run test/ubloxd.py with the print statements enabled in the write function in panda/python/serial.py - pigeon_send("\xB5\x62\x06\x00\x14\x00\x03\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x01\x00\x00\x00\x00\x00\x1E\x7F"); - pigeon_send("\xB5\x62\x06\x3E\x00\x00\x44\xD2"); - pigeon_send("\xB5\x62\x06\x00\x14\x00\x00\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x19\x35"); - pigeon_send("\xB5\x62\x06\x00\x14\x00\x01\x00\x00\x00\xC0\x08\x00\x00\x00\x08\x07\x00\x01\x00\x01\x00\x00\x00\x00\x00\xF4\x80"); - pigeon_send("\xB5\x62\x06\x00\x14\x00\x04\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x1D\x85"); - pigeon_send("\xB5\x62\x06\x00\x00\x00\x06\x18"); - pigeon_send("\xB5\x62\x06\x00\x01\x00\x01\x08\x22"); - pigeon_send("\xB5\x62\x06\x00\x01\x00\x02\x09\x23"); - pigeon_send("\xB5\x62\x06\x00\x01\x00\x03\x0A\x24"); - pigeon_send("\xB5\x62\x06\x08\x06\x00\x64\x00\x01\x00\x00\x00\x79\x10"); - pigeon_send("\xB5\x62\x06\x24\x24\x00\x05\x00\x04\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x5A\x63"); - pigeon_send("\xB5\x62\x06\x1E\x14\x00\x00\x00\x00\x00\x01\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x3C\x37"); - pigeon_send("\xB5\x62\x06\x24\x00\x00\x2A\x84"); - pigeon_send("\xB5\x62\x06\x23\x00\x00\x29\x81"); - pigeon_send("\xB5\x62\x06\x1E\x00\x00\x24\x72"); - pigeon_send("\xB5\x62\x06\x01\x03\x00\x01\x07\x01\x13\x51"); - pigeon_send("\xB5\x62\x06\x01\x03\x00\x02\x15\x01\x22\x70"); - pigeon_send("\xB5\x62\x06\x01\x03\x00\x02\x13\x01\x20\x6C"); - pigeon_send("\xB5\x62\x06\x01\x03\x00\x0A\x09\x01\x1E\x70"); - - LOGW("panda GPS on"); -} - -static void pigeon_publish_raw(PubMaster &pm, unsigned char *dat, int alen) { +static void pigeon_publish_raw(PubMaster &pm, std::string dat) { // create message - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto ublox_raw = event.initUbloxRaw(alen); - memcpy(ublox_raw.begin(), dat, alen); + MessageBuilder msg; + auto ublox_raw = msg.initEvent().initUbloxRaw(dat.length()); + memcpy(ublox_raw.begin(), dat.data(), dat.length()); pm.send("ubloxRaw", msg); } @@ -555,38 +466,33 @@ void pigeon_thread() { // ubloxRaw = 8042 PubMaster pm({"ubloxRaw"}); - // run at ~100hz - unsigned char dat[0x1000]; - uint64_t cnt = 0; +#ifdef QCOM2 + Pigeon * pigeon = Pigeon::connect("/dev/ttyHS0"); +#else + Pigeon * pigeon = Pigeon::connect(panda); +#endif - pigeon_init(); + pigeon->init(); while (!do_exit && panda->connected) { - int alen = 0; - while (alen < 0xfc0) { - int len = panda->usb_read(0xe0, 1, 0, dat+alen, 0x40); - if (len <= 0) break; - - //printf("got %d\n", len); - alen += len; - } - if (alen > 0) { - if (dat[0] == (char)0x00){ + std::string recv = pigeon->receive(); + if (recv.length() > 0) { + if (recv[0] == (char)0x00){ LOGW("received invalid ublox message, resetting panda GPS"); - pigeon_init(); + pigeon->init(); } else { - pigeon_publish_raw(pm, dat, alen); + pigeon_publish_raw(pm, recv); } } - // 10ms + // 10ms - 100 Hz usleep(10*1000); - cnt++; } -} + delete pigeon; } + int main() { int err; LOGW("starting boardd"); @@ -606,6 +512,8 @@ int main() { fake_send = true; } + panda_set_power(true); + while (!do_exit){ std::vector threads; threads.push_back(std::thread(can_health_thread)); diff --git a/selfdrive/boardd/can_list_to_can_capnp.cc b/selfdrive/boardd/can_list_to_can_capnp.cc index 8ba9d3d5609d9c..2fa3f5b9bcbdfd 100644 --- a/selfdrive/boardd/can_list_to_can_capnp.cc +++ b/selfdrive/boardd/can_list_to_can_capnp.cc @@ -1,10 +1,4 @@ -#include -#include -#include -#include "common/timing.h" -#include -#include "cereal/gen/cpp/log.capnp.h" -#include "cereal/gen/cpp/car.capnp.h" +#include "messaging.hpp" typedef struct { long address; @@ -16,21 +10,19 @@ typedef struct { extern "C" { void can_list_to_can_capnp_cpp(const std::vector &can_list, std::string &out, bool sendCan, bool valid) { - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - event.setValid(valid); + MessageBuilder msg; + auto event = msg.initEvent(valid); auto canData = sendCan ? event.initSendcan(can_list.size()) : event.initCan(can_list.size()); int j = 0; for (auto it = can_list.begin(); it != can_list.end(); it++, j++) { - canData[j].setAddress(it->address); - canData[j].setBusTime(it->busTime); - canData[j].setDat(kj::arrayPtr((uint8_t*)it->dat.data(), it->dat.size())); - canData[j].setSrc(it->src); + auto c = canData[j]; + c.setAddress(it->address); + c.setBusTime(it->busTime); + c.setDat(kj::arrayPtr((uint8_t*)it->dat.data(), it->dat.size())); + c.setSrc(it->src); } - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); + auto bytes = msg.toBytes(); out.append((const char *)bytes.begin(), bytes.size()); } diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 5820fa40049a96..21ce0c301a03ed 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -2,10 +2,29 @@ #include #include +#include + #include "common/swaglog.h" +#include "common/gpio.h" #include "panda.h" +void panda_set_power(bool power){ +#ifdef QCOM2 + int err = 0; + err += gpio_init(GPIO_STM_RST_N, true); + err += gpio_init(GPIO_STM_BOOT0, true); + + err += gpio_set(GPIO_STM_RST_N, false); + err += gpio_set(GPIO_STM_BOOT0, false); + + usleep(100*1000); // 100 ms + + err += gpio_set(GPIO_STM_RST_N, power); + assert(err == 0); +#endif +} + Panda::Panda(){ int err; @@ -39,8 +58,10 @@ Panda::Panda(){ is_pigeon = (hw_type == cereal::HealthData::HwType::GREY_PANDA) || (hw_type == cereal::HealthData::HwType::BLACK_PANDA) || - (hw_type == cereal::HealthData::HwType::UNO); - has_rtc = (hw_type == cereal::HealthData::HwType::UNO); + (hw_type == cereal::HealthData::HwType::UNO) || + (hw_type == cereal::HealthData::HwType::DOS); + has_rtc = (hw_type == cereal::HealthData::HwType::UNO) || + (hw_type == cereal::HealthData::HwType::DOS); return; @@ -80,6 +101,10 @@ int Panda::usb_write(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigne int err; const uint8_t bmRequestType = LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; + if (!connected){ + return LIBUSB_ERROR_NO_DEVICE; + } + pthread_mutex_lock(&usb_lock); do { err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, NULL, 0, timeout); @@ -109,6 +134,10 @@ int Panda::usb_bulk_write(unsigned char endpoint, unsigned char* data, int lengt int err; int transferred = 0; + if (!connected){ + return 0; + } + pthread_mutex_lock(&usb_lock); do { // Try sending can messages. If the receive buffer on the panda is full it will NAK @@ -131,6 +160,10 @@ int Panda::usb_bulk_read(unsigned char endpoint, unsigned char* data, int length int err; int transferred = 0; + if (!connected){ + return 0; + } + pthread_mutex_lock(&usb_lock); do { diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h index 3586cda74fed91..c3e2dc981e556d 100644 --- a/selfdrive/boardd/panda.h +++ b/selfdrive/boardd/panda.h @@ -34,6 +34,9 @@ struct __attribute__((packed)) health_t { uint8_t power_save_enabled; }; + +void panda_set_power(bool power); + class Panda { private: libusb_context *ctx = NULL; diff --git a/selfdrive/boardd/pigeon.cc b/selfdrive/boardd/pigeon.cc new file mode 100644 index 00000000000000..4ec7ebf8ce3d70 --- /dev/null +++ b/selfdrive/boardd/pigeon.cc @@ -0,0 +1,226 @@ +#include +#include +#include +#include +#include + +#include "common/swaglog.h" +#include "common/gpio.h" + +#include "pigeon.h" + +// Termios on macos doesn't define all baud rate constants +#ifndef B460800 +#define B460800 0010004 +#endif + +using namespace std::string_literals; + + +Pigeon * Pigeon::connect(Panda * p){ + PandaPigeon * pigeon = new PandaPigeon(); + pigeon->connect(p); + + return pigeon; +} + +Pigeon * Pigeon::connect(const char * tty){ + TTYPigeon * pigeon = new TTYPigeon(); + pigeon->connect(tty); + + return pigeon; +} + +void Pigeon::init() { + usleep(1000*1000); + LOGW("panda GPS start"); + + // power off pigeon + set_power(0); + usleep(100*1000); + + // 9600 baud at init + set_baud(9600); + + // power on pigeon + set_power(1); + usleep(500*1000); + + // baud rate upping + send("\x24\x50\x55\x42\x58\x2C\x34\x31\x2C\x31\x2C\x30\x30\x30\x37\x2C\x30\x30\x30\x33\x2C\x34\x36\x30\x38\x30\x30\x2C\x30\x2A\x31\x35\x0D\x0A"s); + usleep(100*1000); + + // set baud rate to 460800 + set_baud(460800); + usleep(100*1000); + + // init from ubloxd + // To generate this data, run test/ubloxd.py with the print statements enabled in the write function in panda/python/serial.py + send("\xB5\x62\x06\x00\x14\x00\x03\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x01\x00\x00\x00\x00\x00\x1E\x7F"s); + send("\xB5\x62\x06\x3E\x00\x00\x44\xD2"s); + send("\xB5\x62\x06\x00\x14\x00\x00\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x19\x35"s); + send("\xB5\x62\x06\x00\x14\x00\x01\x00\x00\x00\xC0\x08\x00\x00\x00\x08\x07\x00\x01\x00\x01\x00\x00\x00\x00\x00\xF4\x80"s); + send("\xB5\x62\x06\x00\x14\x00\x04\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x1D\x85"s); + send("\xB5\x62\x06\x00\x00\x00\x06\x18"s); + send("\xB5\x62\x06\x00\x01\x00\x01\x08\x22"s); + send("\xB5\x62\x06\x00\x01\x00\x02\x09\x23"s); + send("\xB5\x62\x06\x00\x01\x00\x03\x0A\x24"s); + send("\xB5\x62\x06\x08\x06\x00\x64\x00\x01\x00\x00\x00\x79\x10"s); + send("\xB5\x62\x06\x24\x24\x00\x05\x00\x04\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x5A\x63"s); + send("\xB5\x62\x06\x1E\x14\x00\x00\x00\x00\x00\x01\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x3C\x37"s); + send("\xB5\x62\x06\x24\x00\x00\x2A\x84"s); + send("\xB5\x62\x06\x23\x00\x00\x29\x81"s); + send("\xB5\x62\x06\x1E\x00\x00\x24\x72"s); + send("\xB5\x62\x06\x01\x03\x00\x01\x07\x01\x13\x51"s); + send("\xB5\x62\x06\x01\x03\x00\x02\x15\x01\x22\x70"s); + send("\xB5\x62\x06\x01\x03\x00\x02\x13\x01\x20\x6C"s); + send("\xB5\x62\x06\x01\x03\x00\x0A\x09\x01\x1E\x70"s); + + LOGW("panda GPS on"); +} + +void PandaPigeon::connect(Panda * p) { + panda = p; +} + +void PandaPigeon::set_baud(int baud) { + panda->usb_write(0xe2, 1, 0); + panda->usb_write(0xe4, 1, baud/300); +} + +void PandaPigeon::send(std::string s) { + int len = s.length(); + const char * dat = s.data(); + + unsigned char a[0x20+1]; + a[0] = 1; + for (int i=0; iusb_bulk_write(2, a, ll+1); + } +} + +std::string PandaPigeon::receive() { + std::string r; + + while (true){ + unsigned char dat[0x40]; + int len = panda->usb_read(0xe0, 1, 0, dat, sizeof(dat)); + if (len <= 0 || r.length() > 0x1000) break; + r.append((char*)dat, len); + } + + return r; +} + +void PandaPigeon::set_power(bool power) { + panda->usb_write(0xd9, power, 0); +} + +PandaPigeon::~PandaPigeon(){ +} + +void handle_tty_issue(int err, const char func[]) { + LOGE_100("tty error %d \"%s\" in %s", err, strerror(err), func); +} + +void TTYPigeon::connect(const char * tty) { + pigeon_tty_fd = open(tty, O_RDWR); + if (pigeon_tty_fd < 0){ + handle_tty_issue(errno, __func__); + assert(pigeon_tty_fd >= 0); + } + assert(tcgetattr(pigeon_tty_fd, &pigeon_tty) == 0); + + // configure tty + pigeon_tty.c_cflag &= ~PARENB; // disable parity + pigeon_tty.c_cflag &= ~CSTOPB; // single stop bit + pigeon_tty.c_cflag |= CS8; // 8 bits per byte + pigeon_tty.c_cflag &= ~CRTSCTS; // no RTS/CTS flow control + pigeon_tty.c_cflag |= CREAD | CLOCAL; // turn on READ & ignore ctrl lines + pigeon_tty.c_lflag &= ~ICANON; // disable canonical mode + pigeon_tty.c_lflag &= ~ISIG; // disable interpretation of INTR, QUIT and SUSP + pigeon_tty.c_iflag &= ~(IXON | IXOFF | IXANY); // turn off software flow ctrl + pigeon_tty.c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL); // disable any special handling of received bytes + pigeon_tty.c_oflag &= ~OPOST; // prevent special interpretation of output bytes + pigeon_tty.c_oflag &= ~ONLCR; // prevent conversion of newline to carriage return/line feed + + // configure blocking behavior + pigeon_tty.c_cc[VMIN] = 0; // min amount of characters returned + pigeon_tty.c_cc[VTIME] = 0; // max blocking time in s/10 (0=inf) + + assert(tcsetattr(pigeon_tty_fd, TCSANOW, &pigeon_tty) == 0); +} + +void TTYPigeon::set_baud(int baud){ + speed_t baud_const = 0; + switch(baud){ + case 9600: + baud_const = B9600; + break; + case 460800: + baud_const = B460800; + break; + default: + assert(false); + } + + // make sure everything is tx'ed before changing baud + assert(tcdrain(pigeon_tty_fd) == 0); + + // change baud + assert(tcgetattr(pigeon_tty_fd, &pigeon_tty) == 0); + assert(cfsetspeed(&pigeon_tty, baud_const) == 0); + assert(tcsetattr(pigeon_tty_fd, TCSANOW, &pigeon_tty) == 0); + + // flush + assert(tcflush(pigeon_tty_fd, TCIOFLUSH) == 0); +} + +void TTYPigeon::send(std::string s) { + int len = s.length(); + const char * dat = s.data(); + + int err = write(pigeon_tty_fd, dat, len); + if(err < 0) { handle_tty_issue(err, __func__); } + err = tcdrain(pigeon_tty_fd); + if(err < 0) { handle_tty_issue(err, __func__); } +} + +std::string TTYPigeon::receive() { + std::string r; + + while (true){ + char dat[0x40]; + int len = read(pigeon_tty_fd, dat, sizeof(dat)); + if(len < 0) { + handle_tty_issue(len, __func__); + } else if (len == 0 || r.length() > 0x1000){ + break; + } else { + r.append(dat, len); + } + + } + return r; +} + +void TTYPigeon::set_power(bool power){ +#ifdef QCOM2 + int err = 0; + err += gpio_init(GPIO_UBLOX_RST_N, true); + err += gpio_init(GPIO_UBLOX_SAFEBOOT_N, true); + err += gpio_init(GPIO_UBLOX_PWR_EN, true); + + err += gpio_set(GPIO_UBLOX_RST_N, power); + err += gpio_set(GPIO_UBLOX_SAFEBOOT_N, power); + err += gpio_set(GPIO_UBLOX_PWR_EN, power); + assert(err == 0); +#endif +} + +TTYPigeon::~TTYPigeon(){ + close(pigeon_tty_fd); +} diff --git a/selfdrive/boardd/pigeon.h b/selfdrive/boardd/pigeon.h new file mode 100644 index 00000000000000..667ac70610c840 --- /dev/null +++ b/selfdrive/boardd/pigeon.h @@ -0,0 +1,43 @@ +#pragma once +#include +#include + + +#include "panda.h" + +class Pigeon { + public: + static Pigeon* connect(Panda * p); + static Pigeon* connect(const char * tty); + virtual ~Pigeon(){}; + + void init(); + virtual void set_baud(int baud) = 0; + virtual void send(std::string s) = 0; + virtual std::string receive() = 0; + virtual void set_power(bool power) = 0; +}; + +class PandaPigeon : public Pigeon { + Panda * panda = NULL; +public: + ~PandaPigeon(); + void connect(Panda * p); + void set_baud(int baud); + void send(std::string s); + std::string receive(); + void set_power(bool power); +}; + + +class TTYPigeon : public Pigeon { + int pigeon_tty_fd = -1; + struct termios pigeon_tty; +public: + ~TTYPigeon(); + void connect(const char* tty); + void set_baud(int baud); + void send(std::string s); + std::string receive(); + void set_power(bool power); +}; diff --git a/selfdrive/camerad/SConscript b/selfdrive/camerad/SConscript index 1b205198c68f10..7a81b76c8da6f3 100644 --- a/selfdrive/camerad/SConscript +++ b/selfdrive/camerad/SConscript @@ -11,6 +11,10 @@ if arch == "aarch64": elif arch == "larch64": libs += [] cameras = ['cameras/camera_qcom2.c'] + # no screen + # env = env.Clone() + # env.Append(CXXFLAGS = '-DNOSCREEN') + # env.Append(CFLAGS = '-DNOSCREEN') else: if webcam: libs += ['opencv_core', 'opencv_highgui', 'opencv_imgproc', 'opencv_videoio'] @@ -20,8 +24,8 @@ else: env.Append(CFLAGS = '-DWEBCAM') env.Append(CPPPATH = '/usr/local/include/opencv4') else: - libs += [] cameras = ['cameras/camera_frame_stream.cc'] + if arch == "Darwin": del libs[libs.index('OpenCL')] env = env.Clone() diff --git a/selfdrive/camerad/cameras/camera_frame_stream.cc b/selfdrive/camerad/cameras/camera_frame_stream.cc index aecca564a265ab..9a4263103df9eb 100644 --- a/selfdrive/camerad/cameras/camera_frame_stream.cc +++ b/selfdrive/camerad/cameras/camera_frame_stream.cc @@ -45,7 +45,7 @@ void camera_init(CameraState *s, int camera_id, unsigned int fps) { tbuffer_init2(&s->camera_tb, FRAME_BUF_COUNT, "frame", camera_release_buffer, s); } -void run_frame_stream(DualCameraState *s) { +void run_frame_stream(MultiCameraState *s) { SubMaster sm({"frame"}); CameraState *const rear_camera = &s->rear; @@ -93,7 +93,7 @@ CameraInfo cameras_supported[CAMERA_ID_MAX] = { }, }; -void cameras_init(DualCameraState *s) { +void cameras_init(MultiCameraState *s) { camera_init(&s->rear, CAMERA_ID_IMX298, 20); s->rear.transform = (mat3){{ 1.0, 0.0, 0.0, @@ -111,7 +111,7 @@ void cameras_init(DualCameraState *s) { void camera_autoexposure(CameraState *s, float grey_frac) {} -void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, +void cameras_open(MultiCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *camera_bufs_focus, VisionBuf *camera_bufs_stats, VisionBuf *camera_bufs_front) { assert(camera_bufs_rear); @@ -124,11 +124,11 @@ void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, camera_open(&s->rear, camera_bufs_rear, true); } -void cameras_close(DualCameraState *s) { +void cameras_close(MultiCameraState *s) { camera_close(&s->rear); } -void cameras_run(DualCameraState *s) { +void cameras_run(MultiCameraState *s) { set_thread_name("frame_streaming"); run_frame_stream(s); cameras_close(s); diff --git a/selfdrive/camerad/cameras/camera_frame_stream.h b/selfdrive/camerad/cameras/camera_frame_stream.h index 80ff54b5e3e562..a29e403040da6b 100644 --- a/selfdrive/camerad/cameras/camera_frame_stream.h +++ b/selfdrive/camerad/cameras/camera_frame_stream.h @@ -40,17 +40,17 @@ typedef struct CameraState { } CameraState; -typedef struct DualCameraState { +typedef struct MultiCameraState { int ispif_fd; CameraState rear; CameraState front; -} DualCameraState; +} MultiCameraState; -void cameras_init(DualCameraState *s); -void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *camera_bufs_focus, VisionBuf *camera_bufs_stats, VisionBuf *camera_bufs_front); -void cameras_run(DualCameraState *s); -void cameras_close(DualCameraState *s); +void cameras_init(MultiCameraState *s); +void cameras_open(MultiCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *camera_bufs_focus, VisionBuf *camera_bufs_stats, VisionBuf *camera_bufs_front); +void cameras_run(MultiCameraState *s); +void cameras_close(MultiCameraState *s); void camera_autoexposure(CameraState *s, float grey_frac); #ifdef __cplusplus } // extern "C" diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc index dfed65238c2a6a..27709ef22779ec 100644 --- a/selfdrive/camerad/cameras/camera_qcom.cc +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -258,7 +258,7 @@ static int imx179_s5k3p8sp_apply_exposure(CameraState *s, int gain, int integ_li return err; } -void cameras_init(DualCameraState *s) { +void cameras_init(MultiCameraState *s) { char project_name[1024] = {0}; property_get("ro.boot.project_name", project_name, ""); @@ -545,10 +545,10 @@ static void imx298_ois_calibration(int ois_fd, uint8_t* eeprom) { -static void sensors_init(DualCameraState *s) { +static void sensors_init(MultiCameraState *s) { int err; - int sensorinit_fd = -1; + unique_fd sensorinit_fd; if (s->device == DEVICE_LP3) { sensorinit_fd = open("/dev/v4l-subdev11", O_RDWR | O_NONBLOCK); } else { @@ -1829,7 +1829,7 @@ static void front_start(CameraState *s) { -void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *camera_bufs_focus, VisionBuf *camera_bufs_stats, VisionBuf *camera_bufs_front) { +void cameras_open(MultiCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *camera_bufs_focus, VisionBuf *camera_bufs_stats, VisionBuf *camera_bufs_front) { int err; struct ispif_cfg_data ispif_cfg_data; @@ -1866,13 +1866,13 @@ void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *ca assert(camera_bufs_rear); assert(camera_bufs_front); - int msmcfg_fd = open("/dev/media0", O_RDWR | O_NONBLOCK); - assert(msmcfg_fd >= 0); + s->msmcfg_fd = open("/dev/media0", O_RDWR | O_NONBLOCK); + assert(s->msmcfg_fd >= 0); sensors_init(s); - int v4l_fd = open("/dev/video0", O_RDWR | O_NONBLOCK); - assert(v4l_fd >= 0); + s->v4l_fd = open("/dev/video0", O_RDWR | O_NONBLOCK); + assert(s->v4l_fd >= 0); if (s->device == DEVICE_LP3) { s->ispif_fd = open("/dev/v4l-subdev15", O_RDWR | O_NONBLOCK); @@ -2018,7 +2018,7 @@ static void ops_term() { static void* ops_thread(void* arg) { int err; - DualCameraState *s = (DualCameraState*)arg; + MultiCameraState *s = (MultiCameraState*)arg; set_thread_name("camera_settings"); @@ -2109,7 +2109,7 @@ static void* ops_thread(void* arg) { return NULL; } -void cameras_run(DualCameraState *s) { +void cameras_run(MultiCameraState *s) { int err; pthread_t ops_thread_handle; @@ -2221,7 +2221,7 @@ void cameras_run(DualCameraState *s) { cameras_close(s); } -void cameras_close(DualCameraState *s) { +void cameras_close(MultiCameraState *s) { camera_close(&s->rear); camera_close(&s->front); } diff --git a/selfdrive/camerad/cameras/camera_qcom.h b/selfdrive/camerad/cameras/camera_qcom.h index 812f1a5968896f..02e139d7c7df33 100644 --- a/selfdrive/camerad/cameras/camera_qcom.h +++ b/selfdrive/camerad/cameras/camera_qcom.h @@ -15,6 +15,7 @@ #include "common/mat.h" #include "common/visionbuf.h" #include "common/buffering.h" +#include "common/utilpp.h" #include "camera_common.h" @@ -69,13 +70,13 @@ typedef struct CameraState { uint32_t line_length_pclk; unsigned int max_gain; - int csid_fd; - int csiphy_fd; - int sensor_fd; - int isp_fd; - int eeprom_fd; + unique_fd csid_fd; + unique_fd csiphy_fd; + unique_fd sensor_fd; + unique_fd isp_fd; + unique_fd eeprom_fd; // rear only - int ois_fd, actuator_fd; + unique_fd ois_fd, actuator_fd; uint16_t infinity_dac; struct msm_vfe_axi_stream_cfg_cmd stream_cfg; @@ -123,19 +124,21 @@ typedef struct CameraState { } CameraState; -typedef struct DualCameraState { +typedef struct MultiCameraState { int device; - int ispif_fd; + unique_fd ispif_fd; + unique_fd msmcfg_fd; + unique_fd v4l_fd; CameraState rear; CameraState front; -} DualCameraState; +} MultiCameraState; -void cameras_init(DualCameraState *s); -void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *camera_bufs_focus, VisionBuf *camera_bufs_stats, VisionBuf *camera_bufs_front); -void cameras_run(DualCameraState *s); -void cameras_close(DualCameraState *s); +void cameras_init(MultiCameraState *s); +void cameras_open(MultiCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *camera_bufs_focus, VisionBuf *camera_bufs_stats, VisionBuf *camera_bufs_front); +void cameras_run(MultiCameraState *s); +void cameras_close(MultiCameraState *s); void camera_autoexposure(CameraState *s, float grey_frac); void actuator_move(CameraState *s, uint16_t target); diff --git a/selfdrive/camerad/cameras/debayer.cl b/selfdrive/camerad/cameras/debayer.cl index c9e3716dfd1aa6..5188dc88c1926e 100644 --- a/selfdrive/camerad/cameras/debayer.cl +++ b/selfdrive/camerad/cameras/debayer.cl @@ -81,28 +81,18 @@ __kernel void debayer10(__global uchar const * const in, float4 p = convert_float4(pint); -#if NEW == 1 - // now it's 0x2a - const float black_level = 42.0f; - // max on black level - p = max(0.0, p - black_level); -#else // 64 is the black level of the sensor, remove // (changed to 56 for HDR) const float black_level = 56.0f; // TODO: switch to max here? p = (p - black_level); -#endif - -#if NEW == 0 // correct vignetting (no pow function?) // see https://www.eecis.udel.edu/~jye/lab_research/09/JiUp.pdf the A (4th order) const float r = ((oy - RGB_HEIGHT/2)*(oy - RGB_HEIGHT/2) + (ox - RGB_WIDTH/2)*(ox - RGB_WIDTH/2)); const float fake_f = 700.0f; // should be 910, but this fits... const float lil_a = (1.0f + r/(fake_f*fake_f)); p = p * lil_a * lil_a; -#endif // rescale to 1.0 #if HDR @@ -125,12 +115,8 @@ __kernel void debayer10(__global uchar const * const in, float3 c1 = (float3)(p.s0, (p.s1+p.s2)/2.0f, p.s3); #endif -#if NEW - // TODO: new color correction -#else // color correction c1 = color_correct(c1); -#endif #if HDR // srgb gamma isn't right for YUV, so it's disabled for now diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index 658ab55bae22ea..c28d6edf559cec 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -1,6 +1,7 @@ #include #include #include +#include #if defined(QCOM) && !defined(QCOM_REPLAY) #include "cameras/camera_qcom.h" @@ -13,6 +14,7 @@ #endif #include "common/util.h" +#include "common/params.h" #include "common/swaglog.h" #include "common/ipc.h" @@ -33,8 +35,9 @@ #include #define UI_BUF_COUNT 4 +#define DEBAYER_LOCAL_WORKSIZE 16 #define YUV_COUNT 40 -#define MAX_CLIENTS 5 +#define MAX_CLIENTS 6 extern "C" { volatile sig_atomic_t do_exit = 0; @@ -44,6 +47,10 @@ void set_do_exit(int sig) { do_exit = 1; } +/* +TODO: refactor out camera specific things from here +*/ + struct VisionState; struct VisionClientState { @@ -74,8 +81,13 @@ struct VisionState { cl_program prg_debayer_rear; cl_program prg_debayer_front; + cl_program prg_debayer_wide; cl_kernel krnl_debayer_rear; cl_kernel krnl_debayer_front; + cl_kernel krnl_debayer_wide; + int debayer_cl_localMemSize; + size_t debayer_cl_globalWorkSize[2]; + size_t debayer_cl_localWorkSize[2]; cl_program prg_rgb_laplacian; cl_kernel krnl_rgb_laplacian; @@ -88,10 +100,12 @@ struct VisionState { // processing TBuffer ui_tb; TBuffer ui_front_tb; + TBuffer ui_wide_tb; mat3 yuv_transform; TBuffer *yuv_tb; TBuffer *yuv_front_tb; + TBuffer *yuv_wide_tb; // TODO: refactor for both cameras? Pool yuv_pool; @@ -113,6 +127,15 @@ struct VisionState { int yuv_front_width, yuv_front_height; RGBToYUVState front_rgb_to_yuv_state; + Pool yuv_wide_pool; + VisionBuf yuv_wide_ion[YUV_COUNT]; + cl_mem yuv_wide_cl[YUV_COUNT]; + YUVBuf yuv_wide_bufs[YUV_COUNT]; + FrameMetadata yuv_wide_metas[YUV_COUNT]; + size_t yuv_wide_buf_size; + int yuv_wide_width, yuv_wide_height; + RGBToYUVState wide_rgb_to_yuv_state; + size_t rgb_buf_size; int rgb_width, rgb_height, rgb_stride; VisionBuf rgb_bufs[UI_BUF_COUNT]; @@ -124,11 +147,15 @@ struct VisionState { int rgb_front_width, rgb_front_height, rgb_front_stride; VisionBuf rgb_front_bufs[UI_BUF_COUNT]; cl_mem rgb_front_bufs_cl[UI_BUF_COUNT]; + bool rhd_front; - bool rhd_front_checked; int front_meteringbox_xmin, front_meteringbox_xmax; int front_meteringbox_ymin, front_meteringbox_ymax; + size_t rgb_wide_buf_size; + int rgb_wide_width, rgb_wide_height, rgb_wide_stride; + VisionBuf rgb_wide_bufs[UI_BUF_COUNT]; + cl_mem rgb_wide_bufs_cl[UI_BUF_COUNT]; cl_mem camera_bufs_cl[FRAME_BUF_COUNT]; VisionBuf camera_bufs[FRAME_BUF_COUNT]; @@ -138,7 +165,11 @@ struct VisionState { cl_mem front_camera_bufs_cl[FRAME_BUF_COUNT]; VisionBuf front_camera_bufs[FRAME_BUF_COUNT]; - DualCameraState cameras; + cl_mem wide_camera_bufs_cl[FRAME_BUF_COUNT]; + VisionBuf wide_camera_bufs[FRAME_BUF_COUNT]; + + + MultiCameraState cameras; zsock_t *terminate_pub; @@ -152,11 +183,13 @@ struct VisionState { void* frontview_thread(void *arg) { int err; VisionState *s = (VisionState*)arg; + s->rhd_front = read_db_bool("IsRHD"); set_thread_name("frontview"); + err = set_realtime_priority(51); // we subscribe to this for placement of the AE metering box // TODO: the loop is bad, ideally models shouldn't affect sensors - SubMaster sm({"driverState", "dMonitoringState"}); + SubMaster sm({"driverState"}); cl_command_queue q = clCreateCommandQueue(s->context, s->device_id, 0, &err); assert(err == 0); @@ -179,14 +212,20 @@ void* frontview_thread(void *arg) { assert(err == 0); err = clSetKernelArg(s->krnl_debayer_front, 1, sizeof(cl_mem), &s->rgb_front_bufs_cl[rgb_idx]); assert(err == 0); +#ifdef QCOM2 + err = clSetKernelArg(s->krnl_debayer_front, 2, s->debayer_cl_localMemSize, 0); + assert(err == 0); + err = clEnqueueNDRangeKernel(q, s->krnl_debayer_front, 2, NULL, + s->debayer_cl_globalWorkSize, s->debayer_cl_localWorkSize, 0, 0, &debayer_event); +#else float digital_gain = 1.0; err = clSetKernelArg(s->krnl_debayer_front, 2, sizeof(float), &digital_gain); assert(err == 0); - const size_t debayer_work_size = s->rgb_front_height; // doesn't divide evenly, is this okay? const size_t debayer_local_work_size = 128; err = clEnqueueNDRangeKernel(q, s->krnl_debayer_front, 1, NULL, &debayer_work_size, &debayer_local_work_size, 0, 0, &debayer_event); +#endif assert(err == 0); } else { assert(s->rgb_front_buf_size >= s->cameras.front.frame_size); @@ -197,16 +236,17 @@ void* frontview_thread(void *arg) { } clWaitForEvents(1, &debayer_event); clReleaseEvent(debayer_event); + tbuffer_release(&s->cameras.front.camera_tb, buf_idx); visionbuf_sync(&s->rgb_front_bufs[ui_idx], VISIONBUF_SYNC_FROM_DEVICE); sm.update(0); - // no more check after gps check - if (!s->rhd_front_checked && sm.updated("dMonitoringState")) { - auto state = sm["dMonitoringState"].getDMonitoringState(); - s->rhd_front = state.getIsRHD(); - s->rhd_front_checked = state.getRhdChecked(); + +#ifdef NOSCREEN + if (frame_data.frame_id % 4 == 2) { + sendrgb(&s->cameras, (uint8_t*) s->rgb_front_bufs[rgb_idx].addr, s->rgb_front_bufs[rgb_idx].len, 2); } +#endif if (sm.updated("driverState")) { auto state = sm["driverState"].getDriverState(); @@ -241,6 +281,7 @@ void* frontview_thread(void *arg) { int x_end; int y_start; int y_end; + int skip = 1; if (s->front_meteringbox_xmax > 0) { @@ -256,9 +297,15 @@ void* frontview_thread(void *arg) { x_start = s->rhd_front ? 0:s->rgb_front_width * 3 / 5; x_end = s->rhd_front ? s->rgb_front_width * 2 / 5:s->rgb_front_width; } - +#ifdef QCOM2 + x_start = 0.15*s->rgb_front_width; + x_end = 0.85*s->rgb_front_width; + y_start = 0.5*s->rgb_front_height; + y_end = 0.75*s->rgb_front_height; + skip = 2; +#endif uint32_t lum_binning[256] = {0,}; - for (int y = y_start; y < y_end; ++y) { + for (int y = y_start; y < y_end; y += skip) { for (int x = x_start; x < x_end; x += 2) { // every 2nd col const uint8_t *pix = &bgr_front_ptr[y * s->rgb_front_stride + x * 3]; unsigned int lum = (unsigned int)pix[0] + pix[1] + pix[2]; @@ -272,7 +319,7 @@ void* frontview_thread(void *arg) { lum_binning[std::min(lum / 3, 255u)]++; } } - const unsigned int lum_total = (y_end - y_start) * (x_end - x_start)/2; + const unsigned int lum_total = (y_end - y_start) * (x_end - x_start) / 2 / skip; unsigned int lum_cur = 0; int lum_med = 0; for (lum_med=0; lum_med<256; lum_med++) { @@ -300,11 +347,8 @@ void* frontview_thread(void *arg) { // send frame event { if (s->pm != NULL) { - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - - auto framed = event.initFrontFrame(); + MessageBuilder msg; + auto framed = msg.initEvent().initFrontFrame(); framed.setFrameId(frame_data.frame_id); framed.setEncodeId(cnt); framed.setTimestampEof(frame_data.timestamp_eof); @@ -336,6 +380,159 @@ void* frontview_thread(void *arg) { return NULL; } + +#ifdef QCOM2 +// wide +void* wideview_thread(void *arg) { + int err; + VisionState *s = (VisionState*)arg; + + set_thread_name("wideview"); + + err = set_realtime_priority(51); + LOG("setpriority returns %d", err); + + // init cl stuff + const cl_queue_properties props[] = {0}; //CL_QUEUE_PRIORITY_KHR, CL_QUEUE_PRIORITY_HIGH_KHR, 0}; + cl_command_queue q = clCreateCommandQueueWithProperties(s->context, s->device_id, props, &err); + assert(err == 0); + + // init the net + LOG("wideview start!"); + + for (int cnt = 0; !do_exit; cnt++) { + int buf_idx = tbuffer_acquire(&s->cameras.wide.camera_tb); + // int buf_idx = camera_acquire_buffer(s); + if (buf_idx < 0) { + break; + } + + double t1 = millis_since_boot(); + + FrameMetadata frame_data = s->cameras.wide.camera_bufs_metadata[buf_idx]; + uint32_t frame_id = frame_data.frame_id; + + if (frame_id == -1) { + LOGE("no frame data? wtf"); + tbuffer_release(&s->cameras.wide.camera_tb, buf_idx); + continue; + } + + int ui_idx = tbuffer_select(&s->ui_wide_tb); + int rgb_idx = ui_idx; + + cl_event debayer_event; + if (s->cameras.wide.ci.bayer) { + err = clSetKernelArg(s->krnl_debayer_wide, 0, sizeof(cl_mem), &s->wide_camera_bufs_cl[buf_idx]); + assert(err == 0); + err = clSetKernelArg(s->krnl_debayer_wide, 1, sizeof(cl_mem), &s->rgb_wide_bufs_cl[rgb_idx]); + assert(err == 0); + err = clSetKernelArg(s->krnl_debayer_wide, 2, s->debayer_cl_localMemSize, 0); + assert(err == 0); + err = clEnqueueNDRangeKernel(q, s->krnl_debayer_wide, 2, NULL, + s->debayer_cl_globalWorkSize, s->debayer_cl_localWorkSize, 0, 0, &debayer_event); + assert(err == 0); + } else { + assert(s->rgb_wide_buf_size >= s->frame_size); + assert(s->rgb_stride == s->frame_stride); + err = clEnqueueCopyBuffer(q, s->wide_camera_bufs_cl[buf_idx], s->rgb_wide_bufs_cl[rgb_idx], + 0, 0, s->rgb_wide_buf_size, 0, 0, &debayer_event); + assert(err == 0); + } + + clWaitForEvents(1, &debayer_event); + clReleaseEvent(debayer_event); + + tbuffer_release(&s->cameras.wide.camera_tb, buf_idx); + + visionbuf_sync(&s->rgb_wide_bufs[rgb_idx], VISIONBUF_SYNC_FROM_DEVICE); + +#ifdef NOSCREEN + if (frame_data.frame_id % 4 == 0) { + sendrgb(&s->cameras, (uint8_t*) s->rgb_wide_bufs[rgb_idx].addr, s->rgb_wide_bufs[rgb_idx].len, 1); + } +#endif + + double t2 = millis_since_boot(); + + double yt1 = millis_since_boot(); + + int yuv_idx = pool_select(&s->yuv_wide_pool); + + s->yuv_wide_metas[yuv_idx] = frame_data; + + uint8_t* yuv_ptr_y = s->yuv_wide_bufs[yuv_idx].y; + cl_mem yuv_wide_cl = s->yuv_wide_cl[yuv_idx]; + rgb_to_yuv_queue(&s->wide_rgb_to_yuv_state, q, s->rgb_wide_bufs_cl[rgb_idx], yuv_wide_cl); + visionbuf_sync(&s->yuv_wide_ion[yuv_idx], VISIONBUF_SYNC_FROM_DEVICE); + + double yt2 = millis_since_boot(); + + // keep another reference around till were done processing + pool_acquire(&s->yuv_wide_pool, yuv_idx); + pool_push(&s->yuv_wide_pool, yuv_idx); + + // send frame event + { + if (s->pm != NULL) { + MessageBuilder msg; + auto framed = msg.initEvent().initWideFrame(); + framed.setFrameId(frame_data.frame_id); + framed.setEncodeId(cnt); + framed.setTimestampEof(frame_data.timestamp_eof); + framed.setFrameLength(frame_data.frame_length); + framed.setIntegLines(frame_data.integ_lines); + framed.setGlobalGain(frame_data.global_gain); + framed.setLensPos(frame_data.lens_pos); + framed.setLensSag(frame_data.lens_sag); + framed.setLensErr(frame_data.lens_err); + framed.setLensTruePos(frame_data.lens_true_pos); + framed.setGainFrac(frame_data.gain_frac); + + s->pm->send("wideFrame", msg); + } + } + + tbuffer_dispatch(&s->ui_wide_tb, ui_idx); + + // auto exposure over big box + // TODO: fix this? should not use med imo + const int exposure_x = 384; + const int exposure_y = 300; + const int exposure_height = 400; + const int exposure_width = 1152; + if (cnt % 3 == 0) { + // find median box luminance for AE + uint32_t lum_binning[256] = {0,}; + for (int y=0; yyuv_wide_width) + exposure_x + x]; + lum_binning[lum]++; + } + } + const unsigned int lum_total = exposure_height * exposure_width / 4; + unsigned int lum_cur = 0; + int lum_med = 0; + for (lum_med=0; lum_med<256; lum_med++) { + // shouldn't be any values less than 16 - yuv footroom + lum_cur += lum_binning[lum_med]; + if (lum_cur >= lum_total / 2) { + break; + } + } + + camera_autoexposure(&s->cameras.wide, lum_med / 256.0); + } + + pool_release(&s->yuv_wide_pool, yuv_idx); + double t5 = millis_since_boot(); + LOGD("queued: %.2fms, yuv: %.2f, | processing: %.3fms", (t2-t1), (yt2-yt1), (t5-t1)); + } + + return NULL; +} +#endif + // processing void* processing_thread(void *arg) { int err; @@ -390,13 +587,19 @@ void* processing_thread(void *arg) { assert(err == 0); err = clSetKernelArg(s->krnl_debayer_rear, 1, sizeof(cl_mem), &s->rgb_bufs_cl[rgb_idx]); assert(err == 0); +#ifdef QCOM2 + err = clSetKernelArg(s->krnl_debayer_rear, 2, s->debayer_cl_localMemSize, 0); + assert(err == 0); + err = clEnqueueNDRangeKernel(q, s->krnl_debayer_rear, 2, NULL, + s->debayer_cl_globalWorkSize, s->debayer_cl_localWorkSize, 0, 0, &debayer_event); +#else err = clSetKernelArg(s->krnl_debayer_rear, 2, sizeof(float), &s->cameras.rear.digital_gain); assert(err == 0); - const size_t debayer_work_size = s->rgb_height; // doesn't divide evenly, is this okay? const size_t debayer_local_work_size = 128; err = clEnqueueNDRangeKernel(q, s->krnl_debayer_rear, 1, NULL, &debayer_work_size, &debayer_local_work_size, 0, 0, &debayer_event); +#endif assert(err == 0); } else { assert(s->rgb_buf_size >= s->frame_size); @@ -405,7 +608,6 @@ void* processing_thread(void *arg) { 0, 0, s->rgb_buf_size, 0, 0, &debayer_event); assert(err == 0); } - clWaitForEvents(1, &debayer_event); clReleaseEvent(debayer_event); @@ -413,6 +615,12 @@ void* processing_thread(void *arg) { visionbuf_sync(&s->rgb_bufs[rgb_idx], VISIONBUF_SYNC_FROM_DEVICE); +#ifdef NOSCREEN + if (frame_data.frame_id % 4 == 1) { + sendrgb(&s->cameras, (uint8_t*) s->rgb_bufs[rgb_idx].addr, s->rgb_bufs[rgb_idx].len, 0); + } +#endif + #if defined(QCOM) && !defined(QCOM_REPLAY) /*FILE *dump_rgb_file = fopen("/tmp/process_dump.rgb", "wb"); fwrite(s->rgb_bufs[rgb_idx].addr, s->rgb_bufs[rgb_idx].len, sizeof(uint8_t), dump_rgb_file); @@ -485,7 +693,7 @@ void* processing_thread(void *arg) { // truly stuck, needs help s->cameras.rear.self_recover -= 1; if (s->cameras.rear.self_recover < -FOCUS_RECOVER_PATIENCE) { - LOGW("rear camera bad state detected. attempting recovery from %.1f, recover state is %d", + LOGD("rear camera bad state detected. attempting recovery from %.1f, recover state is %d", lens_true_pos, s->cameras.rear.self_recover.load()); s->cameras.rear.self_recover = FOCUS_RECOVER_STEPS + ((lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M:OP3T_AF_DAC_M))?1:0); // parity determined by which end is stuck at } @@ -495,7 +703,7 @@ void* processing_thread(void *arg) { // in suboptimal position with high prob, but may still recover by itself s->cameras.rear.self_recover -= 1; if (s->cameras.rear.self_recover < -(FOCUS_RECOVER_PATIENCE*3)) { - LOGW("rear camera bad state detected. attempting recovery from %.1f, recover state is %d", lens_true_pos, s->cameras.rear.self_recover.load()); + LOGD("rear camera bad state detected. attempting recovery from %.1f, recover state is %d", lens_true_pos, s->cameras.rear.self_recover.load()); s->cameras.rear.self_recover = FOCUS_RECOVER_STEPS/2 + ((lens_true_pos < (s->cameras.device == DEVICE_LP3? LP3_AF_DAC_M:OP3T_AF_DAC_M))?1:0); } } else if (s->cameras.rear.self_recover < 0) { @@ -530,11 +738,8 @@ void* processing_thread(void *arg) { // send frame event { if (s->pm != NULL) { - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - - auto framed = event.initFrame(); + MessageBuilder msg; + auto framed = msg.initEvent().initFrame(); framed.setFrameId(frame_data.frame_id); framed.setEncodeId(cnt); framed.setTimestampEof(frame_data.timestamp_eof); @@ -618,11 +823,8 @@ void* processing_thread(void *arg) { free(row); jpeg_finish_compress(&cinfo); - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - - auto thumbnaild = event.initThumbnail(); + MessageBuilder msg; + auto thumbnaild = msg.initEvent().initThumbnail(); thumbnaild.setFrameId(frame_data.frame_id); thumbnaild.setTimestampEof(frame_data.timestamp_eof); thumbnaild.setThumbnail(kj::arrayPtr((const uint8_t*)thumbnail_buffer, thumbnail_len)); @@ -638,20 +840,29 @@ void* processing_thread(void *arg) { tbuffer_dispatch(&s->ui_tb, ui_idx); // auto exposure over big box +#ifdef QCOM2 + const int exposure_x = 384; + const int exposure_y = 300; + const int exposure_height = 400; + const int exposure_width = 1152; + const int skip = 2; +#else const int exposure_x = 290; - const int exposure_y = 282 + 40; + const int exposure_y = 322; const int exposure_height = 314; const int exposure_width = 560; + const int skip = 1; +#endif if (cnt % 3 == 0) { // find median box luminance for AE uint32_t lum_binning[256] = {0,}; - for (int y=0; yyuv_width) + exposure_x + x]; lum_binning[lum]++; } } - const unsigned int lum_total = exposure_height * exposure_width; + const unsigned int lum_total = exposure_height * exposure_width / skip / skip; unsigned int lum_cur = 0; int lum_med = 0; for (lum_med=0; lum_med<256; lum_med++) { @@ -661,8 +872,6 @@ void* processing_thread(void *arg) { break; } } - // double avg = (double)acc / (big_box_width * big_box_height) - 16; - // printf("avg %d\n", lum_med); camera_autoexposure(&s->cameras.rear, lum_med / 256.0); } @@ -769,6 +978,20 @@ void* visionserver_client_thread(void* arg) { } else { assert(false); } + } else if (stream_type == VISION_STREAM_RGB_WIDE) { + stream_bufs->width = s->rgb_wide_width; + stream_bufs->height = s->rgb_wide_height; + stream_bufs->stride = s->rgb_wide_stride; + stream_bufs->buf_len = s->rgb_wide_bufs[0].len; + rep.num_fds = UI_BUF_COUNT; + for (int i=0; irgb_wide_bufs[i].fd; + } + if (stream->tb) { + stream->tbuffer = &s->ui_wide_tb; + } else { + assert(false); + } } else if (stream_type == VISION_STREAM_YUV) { stream_bufs->width = s->yuv_width; stream_bufs->height = s->yuv_height; @@ -797,6 +1020,21 @@ void* visionserver_client_thread(void* arg) { } else { stream->queue = pool_get_queue(&s->yuv_front_pool); } + } else if (stream_type == VISION_STREAM_YUV_WIDE) { + stream_bufs->width = s->yuv_wide_width; + stream_bufs->height = s->yuv_wide_height; + stream_bufs->stride = s->yuv_wide_width; + stream_bufs->buf_len = s->yuv_wide_buf_size; + rep.num_fds = YUV_COUNT; + for (int i=0; iyuv_wide_ion[i].fd; + } + if (stream->tb) { + stream->tbuffer = s->yuv_wide_tb; + } else { + stream->queue = pool_get_queue(&s->yuv_wide_pool); + } + } else { assert(false); } @@ -849,6 +1087,9 @@ void* visionserver_client_thread(void* arg) { } else if (stream_i == VISION_STREAM_YUV_FRONT) { rep.d.stream_acq.extra.frame_id = s->yuv_front_metas[idx].frame_id; rep.d.stream_acq.extra.timestamp_eof = s->yuv_front_metas[idx].timestamp_eof; + } else if (stream_i == VISION_STREAM_YUV_WIDE) { + rep.d.stream_acq.extra.frame_id = s->yuv_wide_metas[idx].frame_id; + rep.d.stream_acq.extra.timestamp_eof = s->yuv_wide_metas[idx].timestamp_eof; } vipc_send(fd, &rep); } @@ -959,25 +1200,28 @@ cl_program build_debayer_program(VisionState *s, int frame_width, int frame_height, int frame_stride, int rgb_width, int rgb_height, int rgb_stride, int bayer_flip, int hdr) { +#ifdef QCOM2 + assert(rgb_width == frame_width); + assert(rgb_height == frame_height); +#else assert(rgb_width == frame_width/2); assert(rgb_height == frame_height/2); - - #ifdef QCOM2 - int dnew = 1; - #else - int dnew = 0; - #endif +#endif char args[4096]; snprintf(args, sizeof(args), "-cl-fast-relaxed-math -cl-denorms-are-zero " "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d " "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DRGB_STRIDE=%d " - "-DBAYER_FLIP=%d -DHDR=%d -DNEW=%d", + "-DBAYER_FLIP=%d -DHDR=%d", frame_width, frame_height, frame_stride, rgb_width, rgb_height, rgb_stride, - bayer_flip, hdr, dnew); + bayer_flip, hdr); +#ifdef QCOM2 + return CLU_LOAD_FROM_FILE(s->context, s->device_id, "cameras/real_debayer.cl", args); +#else return CLU_LOAD_FROM_FILE(s->context, s->device_id, "cameras/debayer.cl", args); +#endif } cl_program build_conv_program(VisionState *s, @@ -1010,19 +1254,7 @@ cl_program build_pool_program(VisionState *s, void cl_init(VisionState *s) { int err; - cl_platform_id platform_id = NULL; - cl_uint num_devices; - cl_uint num_platforms; - - err = clGetPlatformIDs(1, &platform_id, &num_platforms); - assert(err == 0); - err = clGetDeviceIDs(platform_id, CL_DEVICE_TYPE_DEFAULT, 1, - &s->device_id, &num_devices); - assert(err == 0); - - cl_print_info(platform_id, s->device_id); - printf("\n"); - + s->device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); s->context = clCreateContext(NULL, 1, &s->device_id, NULL, NULL, &err); assert(err == 0); } @@ -1042,7 +1274,7 @@ void init_buffers(VisionState *s) { for (int i=0; icamera_bufs[i] = visionbuf_allocate_cl(s->frame_size, s->device_id, s->context, &s->camera_bufs_cl[i]); - #ifndef QCOM2 + #ifdef QCOM // TODO: make lengths correct s->focus_bufs[i] = visionbuf_allocate(0xb80); s->stats_bufs[i] = visionbuf_allocate(0xb80); @@ -1054,11 +1286,22 @@ void init_buffers(VisionState *s) { s->device_id, s->context, &s->front_camera_bufs_cl[i]); } - +#ifdef QCOM2 + for (int i=0; iwide_camera_bufs[i] = visionbuf_allocate_cl(s->cameras.wide.frame_size, + s->device_id, s->context, + &s->wide_camera_bufs_cl[i]); + } +#endif // processing buffers if (s->cameras.rear.ci.bayer) { - s->rgb_width = s->frame_width/2; - s->rgb_height = s->frame_height/2; +#ifdef QCOM2 + s->rgb_width = s->frame_width; + s->rgb_height = s->frame_height; +#else + s->rgb_width = s->frame_width / 2; + s->rgb_height = s->frame_height / 2; +#endif } else { s->rgb_width = s->frame_width; s->rgb_height = s->frame_height; @@ -1074,15 +1317,22 @@ void init_buffers(VisionState *s) { } tbuffer_init(&s->ui_tb, UI_BUF_COUNT, "rgb"); - //assert(s->cameras.front.ci.bayer); if (s->cameras.front.ci.bayer) { - s->rgb_front_width = s->cameras.front.ci.frame_width/2; - s->rgb_front_height = s->cameras.front.ci.frame_height/2; +#ifdef QCOM2 + s->rgb_front_width = s->cameras.front.ci.frame_width; + s->rgb_front_height = s->cameras.front.ci.frame_height; +#else + s->rgb_front_width = s->cameras.front.ci.frame_width / 2; + s->rgb_front_height = s->cameras.front.ci.frame_height / 2; +#endif } else { s->rgb_front_width = s->cameras.front.ci.frame_width; s->rgb_front_height = s->cameras.front.ci.frame_height; } - +#ifdef QCOM2 + s->rgb_wide_width = s->cameras.wide.ci.frame_width; + s->rgb_wide_height = s->cameras.wide.ci.frame_height; +#endif for (int i=0; irgb_front_width, s->rgb_front_height, &s->rgb_front_bufs[i]); @@ -1093,6 +1343,17 @@ void init_buffers(VisionState *s) { } } tbuffer_init(&s->ui_front_tb, UI_BUF_COUNT, "frontrgb"); +#ifdef QCOM2 + for (int i=0; irgb_wide_width, s->rgb_wide_height, &s->rgb_wide_bufs[i]); + s->rgb_wide_bufs_cl[i] = visionbuf_to_cl(&s->rgb_wide_bufs[i], s->device_id, s->context); + if (i == 0){ + s->rgb_wide_stride = img.stride; + s->rgb_wide_buf_size = img.size; + } + } + tbuffer_init(&s->ui_wide_tb, UI_BUF_COUNT, "widergb"); +#endif // yuv back for recording and orbd pool_init(&s->yuv_pool, YUV_COUNT); @@ -1124,6 +1385,23 @@ void init_buffers(VisionState *s) { s->yuv_front_bufs[i].v = s->yuv_front_bufs[i].u + (s->yuv_front_width/2 * s->yuv_front_height/2); } + // yuv wide for recording +#ifdef QCOM2 + pool_init(&s->yuv_wide_pool, YUV_COUNT); + s->yuv_wide_tb = pool_get_tbuffer(&s->yuv_wide_pool); + + s->yuv_wide_width = s->rgb_wide_width; + s->yuv_wide_height = s->rgb_wide_height; + s->yuv_wide_buf_size = s->rgb_wide_width * s->rgb_wide_height * 3 / 2; + + for (int i=0; iyuv_wide_ion[i] = visionbuf_allocate_cl(s->yuv_wide_buf_size, s->device_id, s->context, &s->yuv_wide_cl[i]); + s->yuv_wide_bufs[i].y = (uint8_t*)s->yuv_wide_ion[i].addr; + s->yuv_wide_bufs[i].u = s->yuv_wide_bufs[i].y + (s->yuv_wide_width * s->yuv_wide_height); + s->yuv_wide_bufs[i].v = s->yuv_wide_bufs[i].u + (s->yuv_wide_width/2 * s->yuv_wide_height/2); + } +#endif + if (s->cameras.rear.ci.bayer) { // debayering does a 2x downscale s->yuv_transform = transform_scale_buffer(s->cameras.rear.transform, 0.5); @@ -1149,7 +1427,24 @@ void init_buffers(VisionState *s) { s->krnl_debayer_front = clCreateKernel(s->prg_debayer_front, "debayer10", &err); assert(err == 0); } +#ifdef QCOM2 + if (s->cameras.wide.ci.bayer) { + s->prg_debayer_wide = build_debayer_program(s, s->cameras.wide.ci.frame_width, s->cameras.wide.ci.frame_height, + s->cameras.wide.ci.frame_stride, + s->rgb_wide_width, s->rgb_wide_height, s->rgb_wide_stride, + s->cameras.wide.ci.bayer_flip, s->cameras.wide.ci.hdr); + + s->krnl_debayer_wide = clCreateKernel(s->prg_debayer_wide, "debayer10", &err); + assert(err == 0); + } +#endif + s->debayer_cl_localMemSize = (DEBAYER_LOCAL_WORKSIZE + 2 * (3 / 2)) * (DEBAYER_LOCAL_WORKSIZE + 2 * (3 / 2)) * sizeof(float); + s->debayer_cl_globalWorkSize[0] = s->rgb_width; + s->debayer_cl_globalWorkSize[1] = s->rgb_height; + s->debayer_cl_localWorkSize[0] = DEBAYER_LOCAL_WORKSIZE; + s->debayer_cl_localWorkSize[1] = DEBAYER_LOCAL_WORKSIZE; +#ifdef QCOM s->prg_rgb_laplacian = build_conv_program(s, s->rgb_width/NUM_SEGMENTS_X, s->rgb_height/NUM_SEGMENTS_Y, 3); s->krnl_rgb_laplacian = clCreateKernel(s->prg_rgb_laplacian, "rgb2gray_conv2d", &err); @@ -1169,9 +1464,13 @@ void init_buffers(VisionState *s) { s->conv_cl_localWorkSize[1] = CONV_LOCAL_WORKSIZE; for (int i=0; i<(ROI_X_MAX-ROI_X_MIN+1)*(ROI_Y_MAX-ROI_Y_MIN+1); i++) {s->lapres[i] = 16160;} +#endif rgb_to_yuv_init(&s->rgb_to_yuv_state, s->context, s->device_id, s->yuv_width, s->yuv_height, s->rgb_stride); rgb_to_yuv_init(&s->front_rgb_to_yuv_state, s->context, s->device_id, s->yuv_front_width, s->yuv_front_height, s->rgb_front_stride); +#ifdef QCOM2 + rgb_to_yuv_init(&s->wide_rgb_to_yuv_state, s->context, s->device_id, s->yuv_wide_width, s->yuv_wide_height, s->rgb_wide_stride); +#endif } void free_buffers(VisionState *s) { @@ -1179,18 +1478,28 @@ void free_buffers(VisionState *s) { for (int i=0; icamera_bufs[i]); visionbuf_free(&s->front_camera_bufs[i]); +#ifdef QCOM visionbuf_free(&s->focus_bufs[i]); visionbuf_free(&s->stats_bufs[i]); +#elif defined(QCOM2) + visionbuf_free(&s->wide_camera_bufs[i]); +#endif } for (int i=0; irgb_bufs[i]); visionbuf_free(&s->rgb_front_bufs[i]); +#ifdef QCOM2 + visionbuf_free(&s->rgb_wide_bufs[i]); +#endif } for (int i=0; iyuv_ion[i]); visionbuf_free(&s->yuv_front_ion[i]); +#ifdef QCOM2 + visionbuf_free(&s->yuv_wide_ion[i]); +#endif } clReleaseMemObject(s->rgb_conv_roi_cl); @@ -1201,7 +1510,11 @@ void free_buffers(VisionState *s) { clReleaseProgram(s->prg_debayer_front); clReleaseKernel(s->krnl_debayer_rear); clReleaseKernel(s->krnl_debayer_front); - +#ifdef QCOM2 + clReleaseProgram(s->prg_debayer_wide); + clReleaseKernel(s->krnl_debayer_wide); +#endif + clReleaseProgram(s->prg_rgb_laplacian); clReleaseKernel(s->krnl_rgb_laplacian); @@ -1223,13 +1536,18 @@ void party(VisionState *s) { processing_thread, s); assert(err == 0); -#if !defined(QCOM2) && !defined(__APPLE__) - // TODO: fix front camera on qcom2 +#ifndef __APPLE__ pthread_t frontview_thread_handle; err = pthread_create(&frontview_thread_handle, NULL, frontview_thread, s); assert(err == 0); #endif +#ifdef QCOM2 + pthread_t wideview_thread_handle; + err = pthread_create(&wideview_thread_handle, NULL, + wideview_thread, s); + assert(err == 0); +#endif // priority for cameras err = set_realtime_priority(51); @@ -1241,15 +1559,23 @@ void party(VisionState *s) { tbuffer_stop(&s->ui_front_tb); pool_stop(&s->yuv_pool); pool_stop(&s->yuv_front_pool); +#ifdef QCOM2 + tbuffer_stop(&s->ui_wide_tb); + pool_stop(&s->yuv_wide_pool); +#endif zsock_signal(s->terminate_pub, 0); -#if !defined(QCOM2) && !defined(QCOM_REPLAY) && !defined(__APPLE__) +#if (defined(QCOM) && !defined(QCOM_REPLAY)) || defined(WEBCAM) || defined(QCOM2) LOG("joining frontview_thread"); err = pthread_join(frontview_thread_handle, NULL); assert(err == 0); #endif - +#ifdef QCOM2 + LOG("joining wideview_thread"); + err = pthread_join(wideview_thread_handle, NULL); + assert(err == 0); +#endif LOG("joining visionserver_thread"); err = pthread_join(visionserver_thread_handle, NULL); assert(err == 0); @@ -1263,6 +1589,9 @@ void party(VisionState *s) { int main(int argc, char *argv[]) { set_realtime_priority(51); +#ifdef QCOM + set_core_affinity(2); +#endif zsys_handler_set(NULL); signal(SIGINT, (sighandler_t)set_do_exit); @@ -1283,11 +1612,17 @@ int main(int argc, char *argv[]) { init_buffers(s); -#if (defined(QCOM) && !defined(QCOM_REPLAY)) || defined(QCOM2) +#if defined(QCOM) && !defined(QCOM_REPLAY) s->pm = new PubMaster({"frame", "frontFrame", "thumbnail"}); +#elif defined(QCOM2) + s->pm = new PubMaster({"frame", "frontFrame", "wideFrame", "thumbnail"}); #endif +#ifndef QCOM2 cameras_open(&s->cameras, &s->camera_bufs[0], &s->focus_bufs[0], &s->stats_bufs[0], &s->front_camera_bufs[0]); +#else + cameras_open(&s->cameras, &s->camera_bufs[0], &s->focus_bufs[0], &s->stats_bufs[0], &s->front_camera_bufs[0], &s->wide_camera_bufs[0]); +#endif party(s); diff --git a/selfdrive/camerad/transforms/rgb_to_yuv_test.cc b/selfdrive/camerad/transforms/rgb_to_yuv_test.cc index c8b87510586d5e..9d68e5b9ef8123 100644 --- a/selfdrive/camerad/transforms/rgb_to_yuv_test.cc +++ b/selfdrive/camerad/transforms/rgb_to_yuv_test.cc @@ -42,14 +42,7 @@ static inline double millis_since_boot() { void cl_init(cl_device_id &device_id, cl_context &context) { int err; - cl_platform_id platform_id = NULL; - cl_uint num_devices; - cl_uint num_platforms; - - err = clGetPlatformIDs(1, &platform_id, &num_platforms); - err = clGetDeviceIDs(platform_id, CL_DEVICE_TYPE_DEFAULT, 1, - &device_id, &num_devices); - cl_print_info(platform_id, device_id); + device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); context = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); } diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index 0438dd76a0e444..60f3a94e481948 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -5,7 +5,7 @@ from common.numpy_fast import clip, interp from selfdrive.car import create_gas_command from selfdrive.car.honda import hondacan -from selfdrive.car.honda.values import CruiseButtons, CAR, VISUAL_HUD +from selfdrive.car.honda.values import CruiseButtons, CAR, VISUAL_HUD, HONDA_BOSCH from opendbc.can.packer import CANPacker VisualAlert = car.CarControl.HUDControl.VisualAlert @@ -135,8 +135,6 @@ def update(self, enabled, CS, frame, actuators, # **** process the car messages **** # steer torque is converted back to CAN reference (positive when steering right) - apply_gas = clip(actuators.gas, 0., 1.) - apply_brake = int(clip(self.brake_last * P.BRAKE_MAX, 0, P.BRAKE_MAX - 1)) apply_steer = int(interp(-actuators.steer * P.STEER_MAX, P.STEER_LOOKUP_BP, P.STEER_LOOKUP_V)) lkas_active = enabled and not CS.steer_not_allowed @@ -147,14 +145,14 @@ def update(self, enabled, CS, frame, actuators, # Send steering command. idx = frame % 4 can_sends.append(hondacan.create_steering_control(self.packer, apply_steer, - lkas_active, CS.CP.carFingerprint, idx, CS.CP.isPandaBlack)) + lkas_active, CS.CP.carFingerprint, idx, CS.CP.isPandaBlack, CS.CP.openpilotLongitudinalControl)) # Send dashboard UI commands. if (frame % 10) == 0: idx = (frame//10) % 4 - can_sends.extend(hondacan.create_ui_commands(self.packer, pcm_speed, hud, CS.CP.carFingerprint, CS.is_metric, idx, CS.CP.isPandaBlack, CS.stock_hud)) + can_sends.extend(hondacan.create_ui_commands(self.packer, pcm_speed, hud, CS.CP.carFingerprint, CS.is_metric, idx, CS.CP.isPandaBlack, CS.CP.openpilotLongitudinalControl, CS.stock_hud)) - if CS.CP.radarOffCan: + if not CS.CP.openpilotLongitudinalControl: if (frame % 2) == 0: idx = frame // 2 can_sends.append(hondacan.create_bosch_supplemental_1(self.packer, CS.CP.carFingerprint, idx, CS.CP.isPandaBlack)) @@ -169,14 +167,19 @@ def update(self, enabled, CS, frame, actuators, if (frame % 2) == 0: idx = frame // 2 ts = frame * DT_CTRL - pump_on, self.last_pump_ts = brake_pump_hysteresis(apply_brake, self.apply_brake_last, self.last_pump_ts, ts) - can_sends.append(hondacan.create_brake_command(self.packer, apply_brake, pump_on, - pcm_override, pcm_cancel_cmd, hud.fcw, idx, CS.CP.carFingerprint, CS.CP.isPandaBlack, CS.stock_brake)) - self.apply_brake_last = apply_brake - - if CS.CP.enableGasInterceptor: - # send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas. - # This prevents unexpected pedal range rescaling - can_sends.append(create_gas_command(self.packer, apply_gas, idx)) + if CS.CP.carFingerprint in HONDA_BOSCH: + pass # TODO: implement + else: + apply_gas = clip(actuators.gas, 0., 1.) + apply_brake = int(clip(self.brake_last * P.BRAKE_MAX, 0, P.BRAKE_MAX - 1)) + pump_on, self.last_pump_ts = brake_pump_hysteresis(apply_brake, self.apply_brake_last, self.last_pump_ts, ts) + can_sends.append(hondacan.create_brake_command(self.packer, apply_brake, pump_on, + pcm_override, pcm_cancel_cmd, hud.fcw, idx, CS.CP.carFingerprint, CS.CP.isPandaBlack, CS.stock_brake)) + self.apply_brake_last = apply_brake + + if CS.CP.enableGasInterceptor: + # send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas. + # This prevents unexpected pedal range rescaling + can_sends.append(create_gas_command(self.packer, apply_gas, idx)) return can_sends diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 4aaa98aa6680cb..77f74681b6f482 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -79,7 +79,7 @@ def get_can_signals(CP): ("GEARBOX", 100), ] - if CP.radarOffCan: + if CP.carFingerprint in HONDA_BOSCH: # Civic is only bosch to use the same brake message as other hondas. if CP.carFingerprint not in (CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT): signals += [("BRAKE_PRESSED", "BRAKE_MODULE", 0)] @@ -90,6 +90,10 @@ def get_can_signals(CP): ("EPB_STATE", "EPB_STATUS", 0), ("CRUISE_SPEED", "ACC_HUD", 0)] checks += [("GAS_PEDAL_2", 100)] + if CP.openpilotLongitudinalControl: + signals += [("BRAKE_ERROR_1", "STANDSTILL", 1), + ("BRAKE_ERROR_2", "STANDSTILL", 1)] + checks += [("STANDSTILL", 50)] else: # Nidec signals. signals += [("BRAKE_ERROR_1", "STANDSTILL", 1), @@ -206,7 +210,7 @@ def update(self, cp, cp_cam, cp_body): # LOW_SPEED_LOCKOUT is not worth a warning ret.steerWarning = steer_status not in ['NORMAL', 'LOW_SPEED_LOCKOUT', 'NO_TORQUE_ALERT_2'] - if self.CP.radarOffCan: + if not self.CP.openpilotLongitudinalControl: self.brake_error = 0 else: self.brake_error = cp.vl["STANDSTILL"]['BRAKE_ERROR_1'] or cp.vl["STANDSTILL"]['BRAKE_ERROR_2'] @@ -270,7 +274,7 @@ def update(self, cp, cp_cam, cp_body): self.brake_switch = cp.vl["POWERTRAIN_DATA"]['BRAKE_SWITCH'] != 0 - if self.CP.radarOffCan: + if self.CP.carFingerprint in HONDA_BOSCH: self.cruise_mode = cp.vl["ACC_HUD"]['CRUISE_CONTROL_LABEL'] ret.cruiseState.standstill = cp.vl["ACC_HUD"]['CRUISE_SPEED'] == 252. ret.cruiseState.speedOffset = calc_cruise_offset(0, ret.vEgo) diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index 178a452ec63343..45aea3fc1cf4d7 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -1,12 +1,26 @@ from selfdrive.config import Conversions as CV from selfdrive.car.honda.values import HONDA_BOSCH +# CAN bus layout with relay +# 0 = ACC-CAN - radar side +# 1 = F-CAN B - powertrain +# 2 = ACC-CAN - camera side +# 3 = F-CAN A - OBDII port + +# CAN bus layout with giraffe +# 0 = F-CAN B - powertrain +# 1 = ACC-CAN - camera side +# 2 = ACC-CAN - radar side def get_pt_bus(car_fingerprint, has_relay): return 1 if car_fingerprint in HONDA_BOSCH and has_relay else 0 -def get_lkas_cmd_bus(car_fingerprint, has_relay): +def get_lkas_cmd_bus(car_fingerprint, has_relay, radar_disabled=False): + if radar_disabled: + # when radar is disabled, steering commands are sent directly to powertrain bus + return get_pt_bus(car_fingerprint, has_relay) + # normally steering commands are sent to radar, which forwards them to powertrain bus return 2 if car_fingerprint in HONDA_BOSCH and not has_relay else 0 @@ -35,12 +49,47 @@ def create_brake_command(packer, apply_brake, pump_on, pcm_override, pcm_cancel_ return packer.make_can_msg("BRAKE_COMMAND", bus, values, idx) -def create_steering_control(packer, apply_steer, lkas_active, car_fingerprint, idx, has_relay): +def create_acc_commands(packer, enabled, accel, gas, idx, stopping, starting, car_fingerprint, has_relay): + commands = [] + bus = get_pt_bus(car_fingerprint, has_relay) + + control_on = 5 if enabled else 0 + # no gas = -30000 + gas_command = gas if enabled and gas > 0 else -30000 + accel_command = accel if enabled else 0 + braking = 1 if enabled and accel < 0 else 0 + standstill = 1 if enabled and stopping else 0 + standstill_release = 1 if enabled and starting else 0 + + acc_control_values = { + # setting CONTROL_ON causes car to set POWERTRAIN_DATA->ACC_STATUS = 1 + "CONTROL_ON": control_on, + "GAS_COMMAND": gas_command, # used for gas + "ACCEL_COMMAND": accel_command, # used for brakes + "BRAKE_LIGHTS": braking, + "BRAKE_REQUEST": braking, + "STANDSTILL": standstill, + "STANDSTILL_RELEASE": standstill_release, + } + commands.append(packer.make_can_msg("ACC_CONTROL", bus, acc_control_values, idx)) + + acc_control_on_values = { + "SET_TO_3": 0x03, + "CONTROL_ON": enabled, + "SET_TO_FF": 0xff, + "SET_TO_75": 0x75, + "SET_TO_30": 0x30, + } + commands.append(packer.make_can_msg("ACC_CONTROL_ON", bus, acc_control_on_values, idx)) + + return commands + +def create_steering_control(packer, apply_steer, lkas_active, car_fingerprint, idx, has_relay, radar_disabled): values = { "STEER_TORQUE": apply_steer if lkas_active else 0, "STEER_TORQUE_REQUEST": lkas_active, } - bus = get_lkas_cmd_bus(car_fingerprint, has_relay) + bus = get_lkas_cmd_bus(car_fingerprint, has_relay, radar_disabled) return packer.make_can_msg("STEERING_CONTROL", bus, values, idx) @@ -55,27 +104,40 @@ def create_bosch_supplemental_1(packer, car_fingerprint, idx, has_relay): return packer.make_can_msg("BOSCH_SUPPLEMENTAL_1", bus, values, idx) -def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, is_metric, idx, has_relay, stock_hud): +def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, is_metric, idx, has_relay, openpilot_longitudinal_control, stock_hud): commands = [] bus_pt = get_pt_bus(car_fingerprint, has_relay) - bus_lkas = get_lkas_cmd_bus(car_fingerprint, has_relay) - - if car_fingerprint not in HONDA_BOSCH: - acc_hud_values = { - 'PCM_SPEED': pcm_speed * CV.MS_TO_KPH, - 'PCM_GAS': hud.pcm_accel, - 'CRUISE_SPEED': hud.v_cruise, - 'ENABLE_MINI_CAR': 1, - 'HUD_LEAD': hud.car, - 'HUD_DISTANCE': 3, # max distance setting on display - 'IMPERIAL_UNIT': int(not is_metric), - 'SET_ME_X01_2': 1, - 'SET_ME_X01': 1, - "FCM_OFF": stock_hud["FCM_OFF"], - "FCM_OFF_2": stock_hud["FCM_OFF_2"], - "FCM_PROBLEM": stock_hud["FCM_PROBLEM"], - "ICONS": stock_hud["ICONS"], - } + radar_disabled = car_fingerprint in HONDA_BOSCH and openpilot_longitudinal_control + bus_lkas = get_lkas_cmd_bus(car_fingerprint, has_relay, radar_disabled) + + if openpilot_longitudinal_control: + if car_fingerprint in HONDA_BOSCH: + acc_hud_values = { + 'CRUISE_SPEED': hud.v_cruise, + 'ENABLE_MINI_CAR': 1, + 'SET_TO_1': 1, + 'HUD_LEAD': hud.car, + 'HUD_DISTANCE': 3, + 'ACC_ON': hud.car != 0, + 'SET_TO_X1': 1, + 'IMPERIAL_UNIT': int(not is_metric), + } + else: + acc_hud_values = { + 'PCM_SPEED': pcm_speed * CV.MS_TO_KPH, + 'PCM_GAS': hud.pcm_accel, + 'CRUISE_SPEED': hud.v_cruise, + 'ENABLE_MINI_CAR': 1, + 'HUD_LEAD': hud.car, + 'HUD_DISTANCE': 3, # max distance setting on display + 'IMPERIAL_UNIT': int(not is_metric), + 'SET_ME_X01_2': 1, + 'SET_ME_X01': 1, + "FCM_OFF": stock_hud["FCM_OFF"], + "FCM_OFF_2": stock_hud["FCM_OFF_2"], + "FCM_PROBLEM": stock_hud["FCM_PROBLEM"], + "ICONS": stock_hud["ICONS"], + } commands.append(packer.make_can_msg("ACC_HUD", bus_pt, acc_hud_values, idx)) lkas_hud_values = { @@ -87,6 +149,12 @@ def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, is_metric, idx, } commands.append(packer.make_can_msg('LKAS_HUD', bus_lkas, lkas_hud_values, idx)) + if radar_disabled and car_fingerprint in HONDA_BOSCH: + radar_hud_values = { + 'SET_TO_1' : 0x01, + } + commands.append(packer.make_can_msg('RADAR_HUD', bus_pt, radar_hud_values, idx)) + return commands diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index ac8bfe3b9f7ba6..d74db1b1fb56e5 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -478,7 +478,7 @@ def update(self, c, can_strings): events = self.create_common_events(ret, pcm_enable=False) if self.CS.brake_error: events.add(EventName.brakeUnavailable) - if self.CS.brake_hold and self.CS.CP.carFingerprint not in HONDA_BOSCH: + if self.CS.brake_hold and self.CS.CP.openpilotLongitudinalControl: events.add(EventName.brakeHold) if self.CS.park_brake: events.add(EventName.parkBrake) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 713c38ae1bec74..6a92ced813bbf1 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -645,10 +645,12 @@ class CAR: (Ecu.vsa, 0x18da28f1, None): [ b'57114-TPA-G020\x00\x00', b'57114-TPG-A020\x00\x00', + b'57114-TMB-H030\x00\x00', ], (Ecu.eps, 0x18da30f1, None): [ b'39990-TPA-G030\x00\x00', b'39990-TPG-A020\x00\x00', + b'39990-TMA-H020\x00\x00', ], (Ecu.gateway, 0x18daeff1, None): [ b'38897-TMA-H110\x00\x00', @@ -661,10 +663,12 @@ class CAR: (Ecu.fwdCamera, 0x18dab5f1, None): [ b'36161-TPA-E050\x00\x00', b'36161-TPG-A030\x00\x00', + b'36161-TMB-H040\x00\x00', ], (Ecu.combinationMeter, 0x18da60f1, None): [ b'78109-TPA-G520\x00\x00', b'78109-TPG-A110\x00\x00', + b'78109-TMB-H220\x00\x00', ], (Ecu.hud, 0x18da61f1, None): [ b'78209-TLA-X010\x00\x00', @@ -672,10 +676,12 @@ class CAR: (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36802-TPA-E040\x00\x00', b'36802-TPG-A020\x00\x00', + b'36802-TMB-H040\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ b'77959-TLA-G220\x00\x00', b'77959-TLA-C320\x00\x00', + b'77959-TLA-H240\x00\x00', ], }, CAR.FIT: { @@ -754,6 +760,7 @@ class CAR: b'78109-THR-AB20\x00\x00', b'78109-THR-AB30\x00\x00', b'78109-THR-AB40\x00\x00', + b'78109-THR-AC20\x00\x00', b'78109-THR-AC40\x00\x00', b'78109-THR-AE20\x00\x00', b'78109-THR-AE40\x00\x00', @@ -858,6 +865,7 @@ class CAR: b'36161-T6Z-A020\x00\x00', b'36161-T6Z-A310\x00\x00', b'36161-T6Z-A520\x00\x00', + b'36161-TJZ-A120\x00\x00', ], (Ecu.gateway, 0x18daeff1, None): [ b'38897-T6Z-A010\x00\x00', @@ -866,6 +874,7 @@ class CAR: (Ecu.combinationMeter, 0x18da60f1, None): [ b'78109-T6Z-A420\x00\x00', b'78109-T6Z-A510\x00\x00', + b'78109-TJZ-A510\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ b'77959-T6Z-A020\x00\x00', @@ -874,6 +883,7 @@ class CAR: b'57114-T6Z-A120\x00\x00', b'57114-T6Z-A130\x00\x00', b'57114-T6Z-A520\x00\x00', + b'57114-TJZ-A520\x00\x00', ], }, CAR.INSIGHT: { @@ -891,6 +901,7 @@ class CAR: b'77959-TXM-A230\x00\x00', ], (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TXM-A030\x00\x00', b'57114-TXM-A040\x00\x00', ], (Ecu.shiftByWire, 0x18da0bf1, None): [ @@ -900,7 +911,9 @@ class CAR: b'38897-TXM-A020\x00\x00', ], (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TXM-A010\x00\x00', b'78109-TXM-A020\x00\x00', + b'78109-TXM-A110\x00\x00', ], }, CAR.HRV: { diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 787cc91b005d67..c47545ef22e1f9 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -43,11 +43,13 @@ def __init__(self, dbc_name, CP, VM): self.steer_rate_limited = False self.last_resume_frame = 0 + self.p = SteerLimitParams(CP) + def update(self, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert, left_lane, right_lane, left_lane_depart, right_lane_depart): # Steering Torque - new_steer = actuators.steer * SteerLimitParams.STEER_MAX - apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, SteerLimitParams) + new_steer = actuators.steer * self.p.STEER_MAX + apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p) self.steer_rate_limited = new_steer != apply_steer # disable if steer angle reach 90 deg, otherwise mdps fault in some models @@ -75,9 +77,8 @@ def update(self, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert, if pcm_cancel_cmd: can_sends.append(create_clu11(self.packer, frame, CS.clu11, Buttons.CANCEL)) elif CS.out.cruiseState.standstill: - # SCC won't resume anyway when the lead distace is less than 3.7m # send resume at a max freq of 5Hz - if CS.lead_distance > 3.7 and (frame - self.last_resume_frame)*DT_CTRL > 0.2: + if (frame - self.last_resume_frame)*DT_CTRL > 0.2: can_sends.append(create_clu11(self.packer, frame, CS.clu11, Buttons.RES_ACCEL)) self.last_resume_frame = frame diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 61d9de05bb9e43..fd53ffc8a42a36 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -1,3 +1,4 @@ +import copy from cereal import car from selfdrive.car.hyundai.values import DBC, STEER_THRESHOLD, FEATURES, EV_HYBRID from selfdrive.car.interfaces import CarStateBase @@ -124,8 +125,8 @@ def update(self, cp, cp_cam): ret.rightBlindspot = cp.vl["LCA11"]["CF_Lca_IndRight"] != 0 # save the entire LKAS11 and CLU11 - self.lkas11 = cp_cam.vl["LKAS11"] - self.clu11 = cp.vl["CLU11"] + self.lkas11 = copy.copy(cp_cam.vl["LKAS11"]) + self.clu11 = copy.copy(cp.vl["CLU11"]) self.park_brake = cp.vl["CGW1"]['CF_Gway_ParkBrakeSw'] self.steer_state = cp.vl["MDPS12"]['CF_Mdps_ToiActive'] # 0 NOT ACTIVE, 1 ACTIVE self.lead_distance = cp.vl["SCC11"]['ACC_ObjDist'] diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 553d48a2b59fbc..76569d09156e06 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -20,7 +20,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, ret.radarOffCan = True # Most Hyundai car ports are community features for now - ret.communityFeature = candidate not in [CAR.SONATA] + ret.communityFeature = candidate not in [CAR.SONATA, CAR.PALISADE] ret.steerActuatorDelay = 0.1 # Default delay ret.steerRateCost = 0.5 diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 9a39cb8f31b49a..c36ecbd96eefbc 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -6,12 +6,16 @@ # Steer torque limits class SteerLimitParams: - STEER_MAX = 255 # 409 is the max, 255 is stock - STEER_DELTA_UP = 3 - STEER_DELTA_DOWN = 7 - STEER_DRIVER_ALLOWANCE = 50 - STEER_DRIVER_MULTIPLIER = 2 - STEER_DRIVER_FACTOR = 1 + def __init__(self, CP): + if CP.carFingerprint in [CAR.SONATA, CAR.PALISADE]: + self.STEER_MAX = 384 + else: + self.STEER_MAX = 255 + self.STEER_DELTA_UP = 3 + self.STEER_DELTA_DOWN = 7 + self.STEER_DRIVER_ALLOWANCE = 50 + self.STEER_DRIVER_MULTIPLIER = 2 + self.STEER_DRIVER_FACTOR = 1 class CAR: diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index 03f3a026b5b432..bc6c6d0eb9f27a 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -3,7 +3,7 @@ from opendbc.can.can_define import CANDefine from opendbc.can.parser import CANParser from selfdrive.car.interfaces import CarStateBase -from selfdrive.car.mazda.values import DBC, LKAS_LIMITS, CAR +from selfdrive.car.mazda.values import DBC, LKAS_LIMITS, GEN1 class CarState(CarStateBase): def __init__(self, CP): @@ -121,7 +121,7 @@ def get_can_parser(CP): ("WHEEL_SPEEDS", 100), ] - if CP.carFingerprint == CAR.CX5: + if CP.carFingerprint in GEN1: signals += [ ("LKAS_BLOCK", "STEER_RATE", 0), ("LKAS_TRACK_STATE", "STEER_RATE", 0), @@ -165,7 +165,7 @@ def get_cam_can_parser(CP): signals = [] checks = [] - if CP.carFingerprint == CAR.CX5: + if CP.carFingerprint in GEN1: signals += [ # sig_name, sig_address, default ("LKAS_REQUEST", "CAM_LKAS", 0), diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index dfa959da38de3d..81dff12b9c016f 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -25,26 +25,36 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, ret.radarOffCan = True - # Mazda port is a community feature for now - ret.communityFeature = True - ret.steerActuatorDelay = 0.1 ret.steerRateCost = 1.0 ret.steerLimitTimer = 0.8 tire_stiffness_factor = 0.70 # not optimized yet - if candidate in [CAR.CX5]: + if candidate == CAR.CX5: ret.mass = 3655 * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.7 ret.steerRatio = 15.5 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.2]] - + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.19], [0.019]] + ret.lateralTuning.pid.kf = 0.00006 + elif candidate == CAR.CX9: + ret.mass = 4217 * CV.LB_TO_KG + STD_CARGO_KG + ret.wheelbase = 3.1 + ret.steerRatio = 17.6 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.19], [0.019]] ret.lateralTuning.pid.kf = 0.00006 + elif candidate == CAR.Mazda3: + ret.mass = 2875 * CV.LB_TO_KG + STD_CARGO_KG + ret.wheelbase = 2.7 + ret.steerRatio = 14.0 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.19], [0.019]] + ret.lateralTuning.pid.kf = 0.00006 + - # No steer below disable speed - ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS + # No steer below disable speed + ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS ret.centerToFront = ret.wheelbase * 0.41 diff --git a/selfdrive/car/mazda/mazdacan.py b/selfdrive/car/mazda/mazdacan.py index 55b9218dbd6381..dabbd2129d8823 100644 --- a/selfdrive/car/mazda/mazdacan.py +++ b/selfdrive/car/mazda/mazdacan.py @@ -1,4 +1,4 @@ -from selfdrive.car.mazda.values import CAR, Buttons +from selfdrive.car.mazda.values import GEN1, Buttons def create_steering_control(packer, car_fingerprint, frame, apply_steer, lkas): @@ -40,7 +40,7 @@ def create_steering_control(packer, car_fingerprint, frame, apply_steer, lkas): csum = csum % 256 - if car_fingerprint == CAR.CX5: + if car_fingerprint in GEN1: values = { "LKAS_REQUEST" : apply_steer, "CTR" : ctr, @@ -69,7 +69,7 @@ def create_button_cmd(packer, car_fingerprint, button): can = 0 res = 0 - if car_fingerprint == CAR.CX5: + if car_fingerprint in GEN1: values = { "CAN_OFF" : can, "CAN_OFF_INV" : (can + 1) % 2, diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 5759d431a80ed1..4e194d61d15639 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -18,6 +18,8 @@ class SteerLimitParams: class CAR: CX5 = "Mazda CX-5 2017" + CX9 = "Mazda CX-9 2017" + Mazda3 = "Mazda3 2017" class LKAS_LIMITS: STEER_THRESHOLD = 15 @@ -41,13 +43,10 @@ class Buttons: # CX-5 2019 GTR { 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 254: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 608: 8, 628: 8, 736: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1171: 8, 1173: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1244: 8, 1260: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8, 1776: 8, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 - }, - - # Mazda 6 2017 GT - { - 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 628: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1182: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1456: 8, 1479: 8 - }, + } + ], + CAR.CX9: [ # CX-9 2017 Australia - old CAM connector { 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 138: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 522: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 583: 8, 605: 8, 606: 8, 628: 8, 832: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1177: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1247: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8 @@ -56,14 +55,20 @@ class Buttons: # CX-9 2016 - old CAM connector { 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 583: 8, 605: 8, 606: 8, 608: 8, 628: 8, 832: 8, 836: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2004: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }, + } + ], + CAR.Mazda3: [ # Mazda 3 2017 { 19: 5, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 628: 8, 832: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1169: 8, 1170: 8, 1173: 8, 1177: 8, 1180: 8, 1182: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1456: 8, 1479: 8, 2015: 8, 2024: 8, 2025: 8 }, - ], + # Mazda 6 2017 GT + { + 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 628: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1182: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1456: 8, 1479: 8 + } + ], } ECU_FINGERPRINT = { @@ -73,4 +78,8 @@ class Buttons: DBC = { CAR.CX5: dbc_dict('mazda_2017', None), + CAR.CX9: dbc_dict('mazda_2017', None), + CAR.Mazda3: dbc_dict('mazda_2017', None), } + +GEN1 = [ CAR.CX5, CAR.CX9, CAR.Mazda3 ] diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index d0298ec83829b1..4b703d5e90cb34 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -63,6 +63,7 @@ def update(self, c, can_strings): # create message ret = car.CarState.new_message() + ret.canValid = True # speeds ret.vEgo = self.speed @@ -82,9 +83,6 @@ def update(self, c, can_strings): curvature = self.yaw_rate / max(self.speed, 1.) ret.steeringAngle = curvature * self.CP.steerRatio * self.CP.wheelbase * CV.RAD_TO_DEG - events = [] - ret.events = events - return ret.as_reader() def apply(self, c): diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index e31eaee4ffa973..e97cc23af37acc 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -63,7 +63,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, elif candidate == CAR.COROLLA: stop_and_go = False - ret.safetyParam = 100 + ret.safetyParam = 88 ret.wheelbase = 2.70 ret.steerRatio = 18.27 tire_stiffness_factor = 0.444 # not optimized yet diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index da18bfba965ebf..f1d31fb4dbded5 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -309,6 +309,7 @@ class CAR: b'\x018966333P4700\x00\x00\x00\x00', b'\x018966333Q6000\x00\x00\x00\x00', b'\x018966333Q6200\x00\x00\x00\x00', + b'\x018966333W6000\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ b'8821F0601200 ', @@ -316,17 +317,20 @@ class CAR: b'8821F0603300 ', b'8821F0607200 ', b'8821F0608000 ', + b'8821F0609100 ', ], (Ecu.esp, 0x7b0, None): [ b'F152606210\x00\x00\x00\x00\x00\x00', b'F152606230\x00\x00\x00\x00\x00\x00', b'F152606290\x00\x00\x00\x00\x00\x00', b'F152633540\x00\x00\x00\x00\x00\x00', + b'F152633A20\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B33540\x00\x00\x00\x00\x00\x00', b'8965B33542\x00\x00\x00\x00\x00\x00', b'8965B33580\x00\x00\x00\x00\x00\x00', + b'8965B33621\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ # Same as 0x791 b'8821F0601200 ', @@ -334,6 +338,7 @@ class CAR: b'8821F0603300 ', b'8821F0607200 ', b'8821F0608000 ', + b'8821F0609100 ', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'8646F0601200 ', @@ -342,6 +347,7 @@ class CAR: b'8646F0605000 ', b'8646F0606000 ', b'8646F0606100 ', + b'8646F0607100 ', ], }, CAR.CAMRYH: { @@ -425,6 +431,7 @@ class CAR: (Ecu.dsu, 0x791, None): [ b'8821F0W01000 ', b'8821FF401600 ', + b'8821FF404000 ', b'8821FF404100 ', b'8821FF405100 ', b'8821FF406000 ', @@ -436,6 +443,7 @@ class CAR: b'F1526F4034\x00\x00\x00\x00\x00\x00', b'F1526F4044\x00\x00\x00\x00\x00\x00', b'F1526F4073\x00\x00\x00\x00\x00\x00', + b'F1526F4121\x00\x00\x00\x00\x00\x00', b'F1526F4122\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ @@ -450,6 +458,7 @@ class CAR: (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F0W01000 ', b'8821FF401600 ', + b'8821FF404000 ', b'8821FF404100 ', b'8821FF405100 ', b'8821FF406000 ', @@ -540,6 +549,7 @@ class CAR: b'\x018966312R3100\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ + b'\x0230ZN4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', @@ -548,6 +558,7 @@ class CAR: (Ecu.eps, 0x7a1, None): [ b'8965B12361\x00\x00\x00\x00\x00\x00', b'\x018965B12350\x00\x00\x00\x00\x00\x00', + b'\x018965B12470\x00\x00\x00\x00\x00\x00', b'\x018965B12500\x00\x00\x00\x00\x00\x00', b'\x018965B12520\x00\x00\x00\x00\x00\x00', b'\x018965B12530\x00\x00\x00\x00\x00\x00', @@ -556,6 +567,7 @@ class CAR: b'F152602191\x00\x00\x00\x00\x00\x00', b'\x01F152602280\x00\x00\x00\x00\x00\x00', b'\x01F152602560\x00\x00\x00\x00\x00\x00', + b'\x01F152602650\x00\x00\x00\x00\x00\x00', b'\x01F152612641\x00\x00\x00\x00\x00\x00', b'\x01F152612651\x00\x00\x00\x00\x00\x00', b'\x01F152612B10\x00\x00\x00\x00\x00\x00', @@ -573,6 +585,7 @@ class CAR: b'\x028646F12010D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F1201200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', ], @@ -593,6 +606,7 @@ class CAR: b'\x018965B12350\x00\x00\x00\x00\x00\x00', b'\x018965B12470\x00\x00\x00\x00\x00\x00', b'\x018965B12500\x00\x00\x00\x00\x00\x00', + b'\x018965B12520\x00\x00\x00\x00\x00\x00', b'\x018965B12530\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ @@ -604,6 +618,7 @@ class CAR: b'F152612840\x00\x00\x00\x00\x00\x00', b'F152612A10\x00\x00\x00\x00\x00\x00', b'F152642540\x00\x00\x00\x00\x00\x00', + b'F152612A00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301100\x00\x00\x00\x00', @@ -683,7 +698,9 @@ class CAR: b'\x01F15260E051\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ + b'\x01896630E62200\x00\x00\x00\x00', b'\x01896630E64100\x00\x00\x00\x00', + b'\x01896630E64200\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301400\x00\x00\x00\x00', @@ -698,6 +715,7 @@ class CAR: ], (Ecu.esp, 0x7b0, None): [ b'\x01F15264872300\x00\x00\x00\x00', + b'\x01F15264872400\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', @@ -747,6 +765,7 @@ class CAR: b'\x02896634784000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347A5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347A8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634765100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x03896634759100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', @@ -945,11 +964,13 @@ class CAR: b'\x018966342X6000\x00\x00\x00\x00', b'\x018966342W8000\x00\x00\x00\x00', b'\x028966342W4001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x02896634A14001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', b'\x02896634A23001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152642291\x00\x00\x00\x00\x00\x00', b'F152642330\x00\x00\x00\x00\x00\x00', + b'F152642331\x00\x00\x00\x00\x00\x00', b'F152642531\x00\x00\x00\x00\x00\x00', b'F152642532\x00\x00\x00\x00\x00\x00', b'F152642521\x00\x00\x00\x00\x00\x00', @@ -1075,9 +1096,12 @@ class CAR: (Ecu.engine, 0x700, None): [ b'\x01896630E37200\x00\x00\x00\x00', b'\x01896630E41000\x00\x00\x00\x00', + b'\x01896630E41100\x00\x00\x00\x00', b'\x01896630E41200\x00\x00\x00\x00', b'\x01896630E37300\x00\x00\x00\x00', + b'\x01896630E36300\x00\x00\x00\x00', b'\x018966348R8500\x00\x00\x00\x00', + b'\x018966348W1300\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152648472\x00\x00\x00\x00\x00\x00', @@ -1085,6 +1109,7 @@ class CAR: b'F152648492\x00\x00\x00\x00\x00\x00', b'F152648493\x00\x00\x00\x00\x00\x00', b'F152648474\x00\x00\x00\x00\x00\x00', + b'F152648630\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ b'881514810300\x00\x00\x00\x00', @@ -1095,10 +1120,12 @@ class CAR: b'8965B0E011\x00\x00\x00\x00\x00\x00', b'8965B0E012\x00\x00\x00\x00\x00\x00', b'8965B48102\x00\x00\x00\x00\x00\x00', + b'8965B48112\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F4701000\x00\x00\x00\x00', b'8821F4701100\x00\x00\x00\x00', + b'8821F4701200\x00\x00\x00\x00', b'8821F4701300\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ @@ -1106,6 +1133,7 @@ class CAR: b'8646F4801200\x00\x00\x00\x00', b'8646F4802001\x00\x00\x00\x00', b'8646F4802100\x00\x00\x00\x00', + b'8646F4802200\x00\x00\x00\x00', b'8646F4809000\x00\x00\x00\x00', ], }, @@ -1154,6 +1182,7 @@ class CAR: ], (Ecu.esp, 0x7b0, None): [ b'\x01F15260E031\x00\x00\x00\x00\x00\x00', + b'\x01F15260E041\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B48271\x00\x00\x00\x00\x00\x00', diff --git a/selfdrive/clocksd/SConscript b/selfdrive/clocksd/SConscript index 601e64bf163037..d1cf13e9e8428a 100644 --- a/selfdrive/clocksd/SConscript +++ b/selfdrive/clocksd/SConscript @@ -1,2 +1,2 @@ Import('env', 'common', 'cereal', 'messaging') -env.Program('clocksd.cc', LIBS=['diag', 'time_genoff', common, cereal, messaging, 'capnp', 'zmq', 'kj']) \ No newline at end of file +env.Program('clocksd.cc', LIBS=[common, cereal, messaging, 'capnp', 'zmq', 'kj']) diff --git a/selfdrive/clocksd/clocksd.cc b/selfdrive/clocksd/clocksd.cc index 2e17058e0ef4e6..d9fa9eda36a864 100644 --- a/selfdrive/clocksd/clocksd.cc +++ b/selfdrive/clocksd/clocksd.cc @@ -1,12 +1,22 @@ +#include +#include + #include #include +#include #include -#include #include -#include + +#include #include "messaging.hpp" #include "common/timing.h" +// Apple doesn't have timerfd +#ifndef __APPLE__ +#include +#endif + +#ifdef QCOM namespace { int64_t arm_cntpct() { int64_t v; @@ -14,13 +24,14 @@ namespace { return v; } } +#endif int main() { setpriority(PRIO_PROCESS, 0, -13); - int err = 0; PubMaster pm({"clocks"}); +#ifndef __APPLE__ int timerfd = timerfd_create(CLOCK_BOOTTIME, 0); assert(timerfd >= 0); @@ -30,34 +41,43 @@ int main() { spec.it_value.tv_sec = 1; spec.it_value.tv_nsec = 0; - err = timerfd_settime(timerfd, 0, &spec, 0); + int err = timerfd_settime(timerfd, 0, &spec, 0); assert(err == 0); uint64_t expirations = 0; while ((err = read(timerfd, &expirations, sizeof(expirations)))) { if (err < 0) break; +#else + // Just run at 1Hz on apple + while (true){ + std::this_thread::sleep_for(std::chrono::seconds(1)); +#endif uint64_t boottime = nanos_since_boot(); uint64_t monotonic = nanos_monotonic(); uint64_t monotonic_raw = nanos_monotonic_raw(); uint64_t wall_time = nanos_since_epoch(); +#ifdef QCOM uint64_t modem_uptime_v = arm_cntpct() / 19200ULL; // 19.2 mhz clock +#endif - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(boottime); - auto clocks = event.initClocks(); + MessageBuilder msg; + auto clocks = msg.initEvent().initClocks(); clocks.setBootTimeNanos(boottime); clocks.setMonotonicNanos(monotonic); clocks.setMonotonicRawNanos(monotonic_raw); clocks.setWallTimeNanos(wall_time); +#ifdef QCOM clocks.setModemUptimeMillis(modem_uptime_v); +#endif pm.send("clocks", msg); } +#ifndef __APPLE__ close(timerfd); +#endif return 0; -} \ No newline at end of file +} diff --git a/selfdrive/common/SConscript b/selfdrive/common/SConscript index 8ecf786ffea1dc..f70abf58c49b34 100644 --- a/selfdrive/common/SConscript +++ b/selfdrive/common/SConscript @@ -5,7 +5,9 @@ if SHARED: else: fxn = env.Library -_common = fxn('common', ['params.cc', 'swaglog.cc', 'util.c', 'cqueue.c'], LIBS="json11") +common_libs = ['params.cc', 'swaglog.cc', 'util.c', 'cqueue.c', 'gpio.cc', 'i2c.cc'] + +_common = fxn('common', common_libs, LIBS="json11") _visionipc = fxn('visionipc', ['visionipc.c', 'ipc.c']) files = [ @@ -42,4 +44,3 @@ else: _gpucommon = fxn('gpucommon', files, CPPDEFINES=defines, LIBS=_gpu_libs) Export('_common', '_visionipc', '_gpucommon', '_gpu_libs') - diff --git a/selfdrive/common/clutil.c b/selfdrive/common/clutil.c index 9a80c9067b297b..00d63cdcacee97 100644 --- a/selfdrive/common/clutil.c +++ b/selfdrive/common/clutil.c @@ -36,6 +36,44 @@ void clu_init(void) { #endif } +cl_device_id cl_get_device_id(cl_device_type device_type) { + bool opencl_platform_found = false; + cl_device_id device_id = NULL; + + cl_uint num_platforms = 0; + int err = clGetPlatformIDs(0, NULL, &num_platforms); + assert(err == 0); + cl_platform_id* platform_ids = malloc(sizeof(cl_platform_id) * num_platforms); + err = clGetPlatformIDs(num_platforms, platform_ids, NULL); + assert(err == 0); + + char cBuffer[1024]; + for (size_t i = 0; i < num_platforms; i++) { + err = clGetPlatformInfo(platform_ids[i], CL_PLATFORM_NAME, sizeof(cBuffer), &cBuffer, NULL); + assert(err == 0); + printf("platform[%zu] CL_PLATFORM_NAME: %s\n", i, cBuffer); + + cl_uint num_devices; + err = clGetDeviceIDs(platform_ids[i], device_type, 0, NULL, &num_devices); + if (err != 0 || !num_devices) { + continue; + } + // Get first device + err = clGetDeviceIDs(platform_ids[i], device_type, 1, &device_id, NULL); + assert(err == 0); + cl_print_info(platform_ids[i], device_id); + opencl_platform_found = true; + break; + } + free(platform_ids); + + if (!opencl_platform_found) { + printf("No valid openCL platform found\n"); + assert(opencl_platform_found); + } + return device_id; +} + cl_program cl_create_program_from_file(cl_context ctx, const char* path) { char* src_buf = read_file(path, NULL); assert(src_buf); diff --git a/selfdrive/common/clutil.h b/selfdrive/common/clutil.h index b87961eacdfbf8..abbda8c8064310 100644 --- a/selfdrive/common/clutil.h +++ b/selfdrive/common/clutil.h @@ -17,6 +17,7 @@ extern "C" { void clu_init(void); +cl_device_id cl_get_device_id(cl_device_type device_type); cl_program cl_create_program_from_file(cl_context ctx, const char* path); void cl_print_info(cl_platform_id platform, cl_device_id device); void cl_print_build_errors(cl_program program, cl_device_id device); diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc index 30604deb2e3405..30ef7ae8ea2319 100644 --- a/selfdrive/common/framebuffer.cc +++ b/selfdrive/common/framebuffer.cc @@ -1,3 +1,4 @@ +#include "util.h" #include #include #include @@ -37,13 +38,9 @@ extern "C" void framebuffer_swap(FramebufferState *s) { } extern "C" bool set_brightness(int brightness) { - FILE *f = fopen("/sys/class/leds/lcd-backlight/brightness", "wb"); - if (f != NULL) { - fprintf(f, "%d", brightness); - fclose(f); - return true; - } - return false; + char bright[64]; + snprintf(bright, sizeof(bright), "%d", brightness); + return 0 == write_file("/sys/class/leds/lcd-backlight/brightness", bright, strlen(bright)); } extern "C" void framebuffer_set_power(FramebufferState *s, int mode) { diff --git a/selfdrive/common/gpio.cc b/selfdrive/common/gpio.cc new file mode 100644 index 00000000000000..8a72388d468ea0 --- /dev/null +++ b/selfdrive/common/gpio.cc @@ -0,0 +1,29 @@ +#include "gpio.h" +#include "util.h" +#include +#include +#include + +// We assume that all pins have already been exported on boot, +// and that we have permission to write to them. + +int gpio_init(int pin_nr, bool output){ + char pin_dir_path[50]; + int pin_dir_path_len = snprintf(pin_dir_path, sizeof(pin_dir_path), + "/sys/class/gpio/gpio%d/direction", pin_nr); + if(pin_dir_path_len <= 0){ + return -1; + } + const char *value = output ? "out" : "in"; + return write_file(pin_dir_path, (void*)value, strlen(value)); +} + +int gpio_set(int pin_nr, bool high){ + char pin_val_path[50]; + int pin_val_path_len = snprintf(pin_val_path, sizeof(pin_val_path), + "/sys/class/gpio/gpio%d/value", pin_nr); + if(pin_val_path_len <= 0){ + return -1; + } + return write_file(pin_val_path, (void*)(high ? "1" : "0"), 1); +} diff --git a/selfdrive/common/gpio.h b/selfdrive/common/gpio.h new file mode 100644 index 00000000000000..479b4f7e066e9e --- /dev/null +++ b/selfdrive/common/gpio.h @@ -0,0 +1,35 @@ +#ifndef GPIO_H +#define GPIO_H + +#include + +// Pin definitions +#ifdef QCOM2 + #define GPIO_HUB_RST_N 30 + #define GPIO_UBLOX_RST_N 32 + #define GPIO_UBLOX_SAFEBOOT_N 33 + #define GPIO_UBLOX_PWR_EN 34 + #define GPIO_STM_RST_N 124 + #define GPIO_STM_BOOT0 134 +#else + #define GPIO_HUB_RST_N 0 + #define GPIO_UBLOX_RST_N 0 + #define GPIO_UBLOX_SAFEBOOT_N 0 + #define GPIO_UBLOX_PWR_EN 0 + #define GPIO_STM_RST_N 0 + #define GPIO_STM_BOOT0 0 +#endif + + +#ifdef __cplusplus +extern "C" { +#endif + +int gpio_init(int pin_nr, bool output); +int gpio_set(int pin_nr, bool high); + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif diff --git a/selfdrive/common/i2c.cc b/selfdrive/common/i2c.cc new file mode 100644 index 00000000000000..a37b144dc297a1 --- /dev/null +++ b/selfdrive/common/i2c.cc @@ -0,0 +1,80 @@ +#include "i2c.h" + +#include +#include +#include +#include +#include +#include +#include "common/swaglog.h" + +#define UNUSED(x) (void)(x) + +#ifdef QCOM2 +// TODO: decide if we want to isntall libi2c-dev everywhere +#include + +I2CBus::I2CBus(uint8_t bus_id){ + char bus_name[20]; + snprintf(bus_name, 20, "/dev/i2c-%d", bus_id); + + i2c_fd = open(bus_name, O_RDWR); + if(i2c_fd < 0){ + throw std::runtime_error("Failed to open I2C bus"); + } +} + +I2CBus::~I2CBus(){ + if(i2c_fd >= 0){ close(i2c_fd); } +} + +int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len){ + int ret = 0; + + ret = ioctl(i2c_fd, I2C_SLAVE, device_address); + if(ret < 0) { goto fail; } + + ret = i2c_smbus_read_i2c_block_data(i2c_fd, register_address, len, buffer); + if((ret < 0) || (ret != len)) { goto fail; } + +fail: + return ret; +} + +int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data){ + int ret = 0; + + ret = ioctl(i2c_fd, I2C_SLAVE, device_address); + if(ret < 0) { goto fail; } + + ret = i2c_smbus_write_byte_data(i2c_fd, register_address, data); + if(ret < 0) { goto fail; } + +fail: + return ret; +} + +#else + +I2CBus::I2CBus(uint8_t bus_id){ + UNUSED(bus_id); + i2c_fd = -1; +} + +I2CBus::~I2CBus(){} + +int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len){ + UNUSED(device_address); + UNUSED(register_address); + UNUSED(buffer); + UNUSED(len); + return -1; +} + +int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data){ + UNUSED(device_address); + UNUSED(register_address); + UNUSED(data); + return -1; +} +#endif diff --git a/selfdrive/common/i2c.h b/selfdrive/common/i2c.h new file mode 100644 index 00000000000000..d5788510d3f5e3 --- /dev/null +++ b/selfdrive/common/i2c.h @@ -0,0 +1,16 @@ +#pragma once + +#include +#include + +class I2CBus { + private: + int i2c_fd; + + public: + I2CBus(uint8_t bus_id); + ~I2CBus(); + + int read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len); + int set_register(uint8_t device_address, uint register_address, uint8_t data); +}; diff --git a/selfdrive/common/modeldata.h b/selfdrive/common/modeldata.h index 111e20a413d474..77f4a1b7a17155 100644 --- a/selfdrive/common/modeldata.h +++ b/selfdrive/common/modeldata.h @@ -1,41 +1,7 @@ -#ifndef MODELDATA_H -#define MODELDATA_H +#pragma once #define MODEL_PATH_DISTANCE 192 #define POLYFIT_DEGREE 4 #define SPEED_PERCENTILES 10 #define DESIRE_PRED_SIZE 32 #define OTHER_META_SIZE 4 - -typedef struct PathData { - float points[MODEL_PATH_DISTANCE]; - float prob; - float std; - float stds[MODEL_PATH_DISTANCE]; - float poly[POLYFIT_DEGREE]; - float validLen; -} PathData; - -typedef struct LeadData { - float dist; - float prob; - float std; - float rel_y; - float rel_y_std; - float rel_v; - float rel_v_std; - float rel_a; - float rel_a_std; -} LeadData; - -typedef struct ModelData { - PathData path; - PathData left_lane; - PathData right_lane; - LeadData lead; - LeadData lead_future; - float meta[OTHER_META_SIZE + DESIRE_PRED_SIZE]; - float speed[SPEED_PERCENTILES]; -} ModelData; - -#endif diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index 4d9c214d373237..d511ebf415f14d 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -268,45 +268,19 @@ int delete_db_value(const char* key, bool persistent_param) { } int read_db_value(const char* key, char** value, size_t* value_sz, bool persistent_param) { - int lock_fd = -1; - int result; char path[1024]; const char* params_path = persistent_param ? persistent_params_path : default_params_path; - result = snprintf(path, sizeof(path), "%s/.lock", params_path); - if (result < 0) { - goto cleanup; - } - lock_fd = open(path, 0); - - result = snprintf(path, sizeof(path), "%s/d/%s", params_path, key); + int result = snprintf(path, sizeof(path), "%s/d/%s", params_path, key); if (result < 0) { - goto cleanup; - } - - // Take lock. - result = flock(lock_fd, LOCK_EX); - if (result < 0) { - goto cleanup; + return result; } - // Read value. - // TODO(mgraczyk): If there is a lot of contention, we can release the lock - // after opening the file, before reading. *value = static_cast(read_file(path, value_sz)); if (*value == NULL) { - result = -22; - goto cleanup; + return -22; } - - result = 0; - -cleanup: - // Release lock. - if (lock_fd >= 0) { - close(lock_fd); - } - return result; + return 0; } void read_db_value_blocking(const char* key, char** value, size_t* value_sz, bool persistent_param) { @@ -330,8 +304,11 @@ int read_db_all(std::map *params, bool persistent_para int lock_fd = open(lock_path.c_str(), 0); if (lock_fd < 0) return -1; - err = flock(lock_fd, LOCK_EX); - if (err < 0) return err; + err = flock(lock_fd, LOCK_SH); + if (err < 0) { + close(lock_fd); + return err; + } std::string key_path = util::string_format("%s/d", params_path); DIR *d = opendir(key_path.c_str()); @@ -366,3 +343,8 @@ std::vector read_db_bytes(const char* param_name, bool persistent_param) { } return bytes; } + +bool read_db_bool(const char* param_name, bool persistent_param) { + std::vector bytes = read_db_bytes(param_name, persistent_param); + return bytes.size() > 0 and bytes[0] == '1'; +} diff --git a/selfdrive/common/params.h b/selfdrive/common/params.h index 49af04b4fdcf70..394c9b6ed7e45c 100644 --- a/selfdrive/common/params.h +++ b/selfdrive/common/params.h @@ -40,4 +40,5 @@ void read_db_value_blocking(const char* key, char** value, size_t* value_sz, boo #include int read_db_all(std::map *params, bool persistent_param = false); std::vector read_db_bytes(const char* param_name, bool persistent_param = false); +bool read_db_bool(const char* param_name, bool persistent_param = false); #endif diff --git a/selfdrive/common/spinner.c b/selfdrive/common/spinner.c index 99e0ed4229d0aa..2054229cc00707 100644 --- a/selfdrive/common/spinner.c +++ b/selfdrive/common/spinner.c @@ -61,6 +61,7 @@ int spin(int argc, char** argv) { FramebufferState *fb = framebuffer_init("spinner", 0x00001000, false, &fb_w, &fb_h); assert(fb); + framebuffer_set_power(fb, HWC_POWER_MODE_NORMAL); NVGcontext *vg = nvgCreateGLES3(NVG_ANTIALIAS | NVG_STENCIL_STROKES); assert(vg); diff --git a/selfdrive/common/swaglog.cc b/selfdrive/common/swaglog.cc index 41b6358d989ebe..9d90347547caf4 100644 --- a/selfdrive/common/swaglog.cc +++ b/selfdrive/common/swaglog.cc @@ -93,15 +93,13 @@ void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func {"created", seconds_since_epoch()} }; - char* log_s = strdup(log_j.dump().c_str()); - assert(log_s); + std::string log_s = log_j.dump(); free(msg_buf); char levelnum_c = levelnum; zmq_send(s.sock, &levelnum_c, 1, ZMQ_NOBLOCK | ZMQ_SNDMORE); - zmq_send(s.sock, log_s, strlen(log_s), ZMQ_NOBLOCK); - free(log_s); + zmq_send(s.sock, log_s.c_str(), log_s.length(), ZMQ_NOBLOCK); pthread_mutex_unlock(&s.lock); } diff --git a/selfdrive/common/touch.c b/selfdrive/common/touch.c index 2225ed215c0ea9..0ab1e38c009b55 100644 --- a/selfdrive/common/touch.c +++ b/selfdrive/common/touch.c @@ -94,31 +94,3 @@ int touch_poll(TouchState *s, int* out_x, int* out_y, int timeout) { } return up; } - -int touch_read(TouchState *s, int* out_x, int* out_y) { - assert(out_x && out_y); - struct input_event event; - int err = read(s->fd, &event, sizeof(event)); - if (err < sizeof(event)) { - return -1; - } - bool up = false; - switch (event.type) { - case EV_ABS: - if (event.code == ABS_MT_POSITION_X) { - s->last_x = event.value; - } else if (event.code == ABS_MT_POSITION_Y) { - s->last_y = event.value; - } - up = true; - break; - default: - break; - } - if (up) { - // adjust for flippening - *out_x = s->last_y; - *out_y = 1080 - s->last_x; - } - return up; -} diff --git a/selfdrive/common/touch.h b/selfdrive/common/touch.h index c48f66b9827214..fa0faa271b5008 100644 --- a/selfdrive/common/touch.h +++ b/selfdrive/common/touch.h @@ -1,5 +1,4 @@ -#ifndef TOUCH_H -#define TOUCH_H +#pragma once #ifdef __cplusplus extern "C" { @@ -12,10 +11,7 @@ typedef struct TouchState { void touch_init(TouchState *s); int touch_poll(TouchState *s, int *out_x, int *out_y, int timeout); -int touch_read(TouchState *s, int* out_x, int* out_y); #ifdef __cplusplus } #endif - -#endif diff --git a/selfdrive/common/util.c b/selfdrive/common/util.c index 3728dabcd0ca81..33930f9ec1d952 100644 --- a/selfdrive/common/util.c +++ b/selfdrive/common/util.c @@ -3,7 +3,8 @@ #include #include #include - +#include +#include #ifdef __linux__ #include #include @@ -41,6 +42,16 @@ void* read_file(const char* path, size_t* out_len) { return buf; } +int write_file(const char* path, const void* data, size_t size) { + int fd = open(path, O_WRONLY); + if (fd == -1) { + return -1; + } + ssize_t n = write(fd, data, size); + close(fd); + return n == size ? 0 : -1; +} + void set_thread_name(const char* name) { #ifdef __linux__ // pthread_setname_np is dumb (fails instead of truncates) @@ -50,7 +61,6 @@ void set_thread_name(const char* name) { int set_realtime_priority(int level) { #ifdef __linux__ - long tid = syscall(SYS_gettid); // should match python using chrt @@ -64,8 +74,7 @@ int set_realtime_priority(int level) { } int set_core_affinity(int core) { -#ifdef QCOM - +#ifdef __linux__ long tid = syscall(SYS_gettid); cpu_set_t rt_cpu; diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h index a9052146c7498d..18d9619ce05d65 100644 --- a/selfdrive/common/util.h +++ b/selfdrive/common/util.h @@ -41,6 +41,7 @@ extern "C" { // Returns NULL on failure, otherwise the NULL-terminated file contents. // The result must be freed by the caller. void* read_file(const char* path, size_t* out_len); +int write_file(const char* path, const void* data, size_t size); void set_thread_name(const char* name); diff --git a/selfdrive/common/utilpp.h b/selfdrive/common/utilpp.h index 6a68b5fba2d1d7..e0547e0c16c56d 100644 --- a/selfdrive/common/utilpp.h +++ b/selfdrive/common/utilpp.h @@ -1,5 +1,4 @@ -#ifndef UTILPP_H -#define UTILPP_H +#pragma once #include #include @@ -63,4 +62,16 @@ inline std::string readlink(std::string path) { } -#endif +struct unique_fd { + unique_fd(int fd = -1) : fd_(fd) {} + unique_fd& operator=(unique_fd&& uf) { + fd_ = uf.fd_; + uf.fd_ = -1; + return *this; + } + ~unique_fd() { + if (fd_ != -1) close(fd_); + } + operator int() const { return fd_; } + int fd_; +}; diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index d95231d5c66484..ddbf695504c82a 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.7.8-release" +#define COMMA_VERSION "0.7.9-release" diff --git a/selfdrive/common/visionbuf_cl.c b/selfdrive/common/visionbuf_cl.c index c68950baa81bac..21f100507235bc 100644 --- a/selfdrive/common/visionbuf_cl.c +++ b/selfdrive/common/visionbuf_cl.c @@ -110,6 +110,7 @@ void visionbuf_free(const VisionBuf* buf) { #if __OPENCL_VERSION__ >= 200 clSVMFree(buf->ctx, buf->addr); #else + clReleaseCommandQueue(buf->copy_q); munmap(buf->addr, buf->len); close(buf->fd); #endif diff --git a/selfdrive/common/visionipc.c b/selfdrive/common/visionipc.c index bae05ccc777268..6820491156fb3c 100644 --- a/selfdrive/common/visionipc.c +++ b/selfdrive/common/visionipc.c @@ -90,6 +90,7 @@ int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, Visi err = vipc_send(s->ipc_fd, &p); if (err < 0) { close(s->ipc_fd); + s->ipc_fd = -1; return -1; } @@ -97,6 +98,7 @@ int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, Visi err = vipc_recv(s->ipc_fd, &rp); if (err <= 0) { close(s->ipc_fd); + s->ipc_fd = -1; return -1; } assert(rp.type == VIPC_STREAM_BUFS); @@ -190,5 +192,5 @@ void visionstream_destroy(VisionStream *s) { } } if (s->bufs) free(s->bufs); - close(s->ipc_fd); + if (s->ipc_fd >= 0) close(s->ipc_fd); } diff --git a/selfdrive/common/visionipc.h b/selfdrive/common/visionipc.h index 4844a71b1d756b..1b216f52555303 100644 --- a/selfdrive/common/visionipc.h +++ b/selfdrive/common/visionipc.h @@ -23,8 +23,10 @@ typedef enum VisionIPCPacketType { typedef enum VisionStreamType { VISION_STREAM_RGB_BACK, VISION_STREAM_RGB_FRONT, + VISION_STREAM_RGB_WIDE, VISION_STREAM_YUV, VISION_STREAM_YUV_FRONT, + VISION_STREAM_YUV_WIDE, VISION_STREAM_MAX, } VisionStreamType; @@ -35,6 +37,10 @@ typedef struct VisionUIInfo { int front_box_x, front_box_y; int front_box_width, front_box_height; + + int wide_box_x, wide_box_y; + int wide_box_width, wide_box_height; + } VisionUIInfo; typedef struct VisionStreamBufs { diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 2546a598af7b0f..fe576192e79c9b 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -1,10 +1,9 @@ #!/usr/bin/env python3 import os -import gc from cereal import car, log -from common.android import ANDROID, get_sound_card_online +from common.hardware import HARDWARE from common.numpy_fast import clip -from common.realtime import sec_since_boot, set_realtime_priority, set_core_affinity, Ratekeeper, DT_CTRL +from common.realtime import sec_since_boot, config_rt_process, Priority, Ratekeeper, DT_CTRL from common.profiler import Profiler from common.params import Params, put_nonblocking import cereal.messaging as messaging @@ -21,13 +20,16 @@ from selfdrive.controls.lib.alertmanager import AlertManager from selfdrive.controls.lib.vehicle_model import VehicleModel from selfdrive.controls.lib.planner import LON_MPC_STEP -from selfdrive.locationd.calibration_helpers import Calibration +from selfdrive.locationd.calibrationd import Calibration LDW_MIN_SPEED = 31 * CV.MPH_TO_MS LANE_DEPARTURE_THRESHOLD = 0.1 STEER_ANGLE_SATURATION_TIMEOUT = 1.0 / DT_CTRL STEER_ANGLE_SATURATION_THRESHOLD = 2.5 # Degrees +SIMULATION = "SIMULATION" in os.environ +NOSENSOR = "NOSENSOR" in os.environ + ThermalStatus = log.ThermalData.ThermalStatus State = log.ControlsState.OpenpilotState HwType = log.HealthData.HwType @@ -40,9 +42,7 @@ class Controls: def __init__(self, sm=None, pm=None, can_sock=None): - gc.disable() - set_realtime_priority(53) - set_core_affinity(3) + config_rt_process(3, Priority.CTRL_HIGH) # Setup sockets self.pm = pm @@ -79,11 +79,11 @@ def __init__(self, sm=None, pm=None, can_sock=None): internet_needed or not openpilot_enabled_toggle # detect sound card presence and ensure successful init - sounds_available = not ANDROID or get_sound_card_online() + sounds_available = HARDWARE.get_sound_card_online() car_recognized = self.CP.carName != 'mock' # If stock camera is disconnected, we loaded car controls and it's not dashcam mode - controller_available = self.CP.enableCamera and self.CI.CC is not None and not passive + controller_available = self.CP.enableCamera and self.CI.CC is not None and not passive and not self.CP.dashcamOnly community_feature_disallowed = self.CP.communityFeature and not community_feature_toggle self.read_only = not car_recognized or not controller_available or \ self.CP.dashcamOnly or community_feature_disallowed @@ -94,7 +94,6 @@ def __init__(self, sm=None, pm=None, can_sock=None): cp_bytes = self.CP.to_bytes() params.put("CarParams", cp_bytes) put_nonblocking("CarParamsCache", cp_bytes) - put_nonblocking("LongitudinalControl", "1" if self.CP.openpilotLongitudinalControl else "0") self.CC = car.CarControl.new_message() self.AM = AlertManager() @@ -139,7 +138,7 @@ def __init__(self, sm=None, pm=None, can_sock=None): self.events.add(EventName.internetConnectivityNeeded, static=True) if community_feature_disallowed: self.events.add(EventName.communityFeatureDisallowed, static=True) - if self.read_only and not passive: + if not car_recognized: self.events.add(EventName.carUnrecognized, static=True) if hw_type == HwType.whitePanda: self.events.add(EventName.whitePandaUnsupported, static=True) @@ -192,7 +191,7 @@ def update_events(self, CS): else: self.events.add(EventName.preLaneChangeRight) elif self.sm['pathPlan'].laneChangeState in [LaneChangeState.laneChangeStarting, - LaneChangeState.laneChangeFinishing]: + LaneChangeState.laneChangeFinishing]: self.events.add(EventName.laneChange) if self.can_rcv_error or (not CS.canValid and self.sm.frame > 5 / DT_CTRL): @@ -206,12 +205,13 @@ def update_events(self, CS): self.events.add(EventName.commIssue) if not self.sm['pathPlan'].mpcSolutionValid: self.events.add(EventName.plannerError) - if not self.sm['liveLocationKalman'].sensorsOK and os.getenv("NOSENSOR") is None: + if not self.sm['liveLocationKalman'].sensorsOK and not NOSENSOR: if self.sm.frame > 5 / DT_CTRL: # Give locationd some time to receive all the inputs self.events.add(EventName.sensorDataInvalid) - if not self.sm['liveLocationKalman'].gpsOK and (self.distance_traveled > 1000) and os.getenv("NOSENSOR") is None: + if not self.sm['liveLocationKalman'].gpsOK and (self.distance_traveled > 1000): # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes - self.events.add(EventName.noGps) + if not (SIMULATION or NOSENSOR): # TODO: send GPS in carla + self.events.add(EventName.noGps) if not self.sm['pathPlan'].paramsValid: self.events.add(EventName.vehicleModelInvalid) if not self.sm['liveLocationKalman'].posenetOK: @@ -229,12 +229,12 @@ def update_events(self, CS): self.events.add(EventName.relayMalfunction) if self.sm['plan'].fcw: self.events.add(EventName.fcw) - if self.sm['model'].frameDropPerc > 1: - self.events.add(EventName.modeldLagging) + if self.sm['model'].frameDropPerc > 1 and (not SIMULATION): + self.events.add(EventName.modeldLagging) # Only allow engagement with brake pressed when stopped behind another stopped car if CS.brakePressed and self.sm['plan'].vTargetFuture >= STARTING_TARGET_SPEED \ - and not self.CP.radarOffCan and CS.vEgo < 0.3: + and self.CP.openpilotLongitudinalControl and CS.vEgo < 0.3: self.events.add(EventName.noTarget) def data_sample(self): diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index 870d8d4b7e5803..6eaa86d3ec425e 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -1,24 +1,21 @@ import os import copy import json +from typing import List, Optional from cereal import car, log from common.basedir import BASEDIR from common.params import Params from common.realtime import DT_CTRL +from selfdrive.controls.lib.events import Alert from selfdrive.swaglog import cloudlog -AlertSize = log.ControlsState.AlertSize -AlertStatus = log.ControlsState.AlertStatus -VisualAlert = car.CarControl.HUDControl.VisualAlert -AudibleAlert = car.CarControl.HUDControl.AudibleAlert - with open(os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json")) as f: OFFROAD_ALERTS = json.load(f) -def set_offroad_alert(alert, show_alert, extra_text=None): +def set_offroad_alert(alert: str, show_alert: bool, extra_text: Optional[str] = None) -> None: if show_alert: a = OFFROAD_ALERTS[alert] if extra_text is not None: @@ -29,19 +26,30 @@ def set_offroad_alert(alert, show_alert, extra_text=None): Params().delete(alert) -class AlertManager(): +class AlertManager: def __init__(self): - self.activealerts = [] + self.activealerts: List[Alert] = [] + self.clear_current_alert() - def alert_present(self): + def alert_present(self) -> bool: return len(self.activealerts) > 0 - def add_many(self, frame, alerts, enabled=True): + def clear_current_alert(self) -> None: + self.alert_type: str = "" + self.alert_text_1: str = "" + self.alert_text_2: str = "" + self.alert_status = log.ControlsState.AlertStatus.normal + self.alert_size = log.ControlsState.AlertSize.none + self.visual_alert = car.CarControl.HUDControl.VisualAlert.none + self.audible_alert = car.CarControl.HUDControl.AudibleAlert.none + self.alert_rate: float = 0. + + def add_many(self, frame: int, alerts: List[Alert], enabled: bool = True) -> None: for a in alerts: self.add(frame, a, enabled=enabled) - def add(self, frame, alert, enabled=True): + def add(self, frame: int, alert: Alert, enabled: bool = True) -> None: added_alert = copy.copy(alert) added_alert.start_time = frame * DT_CTRL @@ -54,26 +62,18 @@ def add(self, frame, alert, enabled=True): # sort by priority first and then by start_time self.activealerts.sort(key=lambda k: (k.alert_priority, k.start_time), reverse=True) - def process_alerts(self, frame): + def process_alerts(self, frame: int) -> None: cur_time = frame * DT_CTRL # first get rid of all the expired alerts self.activealerts = [a for a in self.activealerts if a.start_time + max(a.duration_sound, a.duration_hud_alert, a.duration_text) > cur_time] - current_alert = self.activealerts[0] if self.alert_present() else None - # start with assuming no alerts - self.alert_type = "" - self.alert_text_1 = "" - self.alert_text_2 = "" - self.alert_status = AlertStatus.normal - self.alert_size = AlertSize.none - self.visual_alert = VisualAlert.none - self.audible_alert = AudibleAlert.none - self.alert_rate = 0. - - if current_alert: + self.clear_current_alert() + + current_alert = self.activealerts[0] if self.alert_present() else None + if current_alert is not None: self.alert_type = current_alert.alert_type if current_alert.start_time + current_alert.duration_sound > cur_time: diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 205c6a1722a557..67a6838d7478dc 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -1,9 +1,11 @@ from functools import total_ordering +from typing import Dict, Union, Callable, Any from cereal import log, car +import cereal.messaging as messaging from common.realtime import DT_CTRL from selfdrive.config import Conversions as CV -from selfdrive.locationd.calibration_helpers import Filter +from selfdrive.locationd.calibrationd import MIN_SPEED_FILTER AlertSize = log.ControlsState.AlertSize AlertStatus = log.ControlsState.AlertStatus @@ -97,18 +99,18 @@ def to_msg(self): @total_ordering class Alert: def __init__(self, - alert_text_1, - alert_text_2, + alert_text_1: str, + alert_text_2: str, alert_status, alert_size, alert_priority, visual_alert, audible_alert, - duration_sound, - duration_hud_alert, - duration_text, - alert_rate=0., - creation_delay=0.): + duration_sound: float, + duration_hud_alert: float, + duration_text: float, + alert_rate: float = 0., + creation_delay: float = 0.): self.alert_type = "" self.alert_text_1 = alert_text_1 @@ -131,14 +133,14 @@ def __init__(self, tst = car.CarControl.new_message() tst.hudControl.visualAlert = self.visual_alert - def __str__(self): + def __str__(self) -> str: return self.alert_text_1 + "/" + self.alert_text_2 + " " + str(self.alert_priority) + " " + str( self.visual_alert) + " " + str(self.audible_alert) - def __gt__(self, alert2): + def __gt__(self, alert2) -> bool: return self.alert_priority > alert2.alert_priority - def __eq__(self, alert2): + def __eq__(self, alert2) -> bool: return self.alert_priority == alert2.alert_priority class NoEntryAlert(Alert): @@ -174,25 +176,25 @@ def __init__(self, audible_alert=True): # ********** alert callback functions ********** -def below_steer_speed_alert(CP, sm, metric): +def below_steer_speed_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> Alert: speed = int(round(CP.minSteerSpeed * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH))) - unit = "kph" if metric else "mph" + unit = "km/h" if metric else "mph" return Alert( "TAKE CONTROL", "Steer Unavailable Below %d %s" % (speed, unit), AlertStatus.userPrompt, AlertSize.mid, Priority.MID, VisualAlert.steerRequired, AudibleAlert.none, 0., 0.4, .3) -def calibration_incomplete_alert(CP, sm, metric): - speed = int(Filter.MIN_SPEED * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH)) - unit = "kph" if metric else "mph" +def calibration_incomplete_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> Alert: + speed = int(MIN_SPEED_FILTER * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH)) + unit = "km/h" if metric else "mph" return Alert( "Calibration in Progress: %d%%" % sm['liveCalibration'].calPerc, "Drive Above %d %s" % (speed, unit), AlertStatus.normal, AlertSize.mid, Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2) -def no_gps_alert(CP, sm, metric): +def no_gps_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> Alert: gps_integrated = sm['health'].hwType in [log.HealthData.HwType.uno, log.HealthData.HwType.dos] return Alert( "Poor GPS reception", @@ -200,13 +202,13 @@ def no_gps_alert(CP, sm, metric): AlertStatus.normal, AlertSize.mid, Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=300.) -def wrong_car_mode_alert(CP, sm, metric): +def wrong_car_mode_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> Alert: text = "Cruise Mode Disabled" if CP.carName == "honda": text = "Main Switch Off" return NoEntryAlert(text, duration_hud_alert=0.) -EVENTS = { +EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, bool], Alert]]]] = { # ********** events with no alerts ********** # ********** events only containing alerts displayed in all states ********** @@ -227,14 +229,6 @@ def wrong_car_mode_alert(CP, sm, metric): Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., 15.), }, - EventName.startupWhitePanda: { - ET.PERMANENT: Alert( - "WARNING: White panda is deprecated", - "Upgrade to comma two or black panda", - AlertStatus.userPrompt, AlertSize.mid, - Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., 15.), - }, - EventName.startupMaster: { ET.PERMANENT: Alert( "WARNING: This branch is not tested", @@ -287,7 +281,6 @@ def wrong_car_mode_alert(CP, sm, metric): EventName.communityFeatureDisallowed: { # LOW priority to overcome Cruise Error ET.PERMANENT: Alert( - "", "Community Feature Detected", "Enable Community Features in Developer Settings", AlertStatus.normal, AlertSize.mid, @@ -341,7 +334,7 @@ def wrong_car_mode_alert(CP, sm, metric): "openpilot will not brake while gas pressed", "", AlertStatus.normal, AlertSize.small, - Priority.LOWEST, VisualAlert.none, AudibleAlert.none, .0, .0, .1), + Priority.LOWEST, VisualAlert.none, AudibleAlert.none, .0, .0, .1, creation_delay=1.), }, EventName.vehicleModelInvalid: { @@ -413,7 +406,7 @@ def wrong_car_mode_alert(CP, sm, metric): "CHECK DRIVER FACE VISIBILITY", "Driver Monitor Model Output Uncertain", AlertStatus.normal, AlertSize.mid, - Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .4, 0., 1.), + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .4, 0., 1.5), }, EventName.manualRestart: { @@ -535,7 +528,7 @@ def wrong_car_mode_alert(CP, sm, metric): "TAKE CONTROL", "Attempting Refocus: Camera Focus Invalid", AlertStatus.userPrompt, AlertSize.mid, - Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimeWarning1, .4, 2., 3.), + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimeWarning1, .4, 2., 3., creation_delay=3.1), }, EventName.outOfSpace: { @@ -593,7 +586,12 @@ def wrong_car_mode_alert(CP, sm, metric): }, EventName.calibrationInvalid: { - ET.SOFT_DISABLE: SoftDisableAlert("Calibration Invalid: Reposition Device and Recalibrate"), + ET.PERMANENT: Alert( + "Calibration Invalid", + "Reposition Device and Recalibrate", + AlertStatus.normal, AlertSize.mid, + Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + ET.SOFT_DISABLE: SoftDisableAlert("Calibration Invalid: Reposition Device & Recalibrate"), ET.NO_ENTRY: NoEntryAlert("Calibration Invalid: Reposition Device & Recalibrate"), }, @@ -716,6 +714,11 @@ def wrong_car_mode_alert(CP, sm, metric): }, EventName.reverseGear: { + ET.PERMANENT: Alert( + "Reverse\nGear", + "", + AlertStatus.normal, AlertSize.full, + Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=0.5), ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Reverse Gear"), ET.NO_ENTRY: NoEntryAlert("Reverse Gear"), }, diff --git a/selfdrive/controls/lib/long_mpc.py b/selfdrive/controls/lib/long_mpc.py index b83354065f53cd..f9bf15cc048067 100644 --- a/selfdrive/controls/lib/long_mpc.py +++ b/selfdrive/controls/lib/long_mpc.py @@ -56,7 +56,7 @@ def set_cur_state(self, v, a): self.cur_state[0].v_ego = v self.cur_state[0].a_ego = a - def update(self, pm, CS, lead, v_cruise_setpoint): + def update(self, pm, CS, lead): v_ego = CS.vEgo # Setup current mpc state diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index 5262f480a7ad37..f31dcb05bfc1e0 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -14,9 +14,6 @@ STARTING_BRAKE_RATE = 0.8 # brake_travel/s while releasing on restart BRAKE_STOPPING_TARGET = 0.5 # apply at least this amount of brake to maintain the vehicle stationary -_MAX_SPEED_ERROR_BP = [0., 30.] # speed breakpoints -_MAX_SPEED_ERROR_V = [1.5, .8] # max positive v_pid error VS actual speed; this avoids controls windup due to slow pedal resp - RATE = 100.0 @@ -86,8 +83,7 @@ def update(self, active, CS, v_target, v_target_future, a_target, CP): v_ego_pid = max(CS.vEgo, MIN_CAN_SPEED) # Without this we get jumps, CAN bus reports 0 when speed < 0.3 if self.long_control_state == LongCtrlState.off or CS.gasPressed: - self.v_pid = v_ego_pid - self.pid.reset() + self.reset(v_ego_pid) output_gb = 0. # tracking objects and driving @@ -113,15 +109,13 @@ def update(self, active, CS, v_target, v_target_future, a_target, CP): output_gb -= STOPPING_BRAKE_RATE / RATE output_gb = clip(output_gb, -brake_max, gas_max) - self.v_pid = CS.vEgo - self.pid.reset() + self.reset(CS.vEgo) # Intention is to move again, release brake fast before handing control to PID elif self.long_control_state == LongCtrlState.starting: if output_gb < -0.2: output_gb += STARTING_BRAKE_RATE / RATE - self.v_pid = CS.vEgo - self.pid.reset() + self.reset(CS.vEgo) self.last_output_gb = output_gb final_gas = clip(output_gb, 0., gas_max) diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py index 553e5bb6facd5c..0412df36d30b2c 100755 --- a/selfdrive/controls/lib/planner.py +++ b/selfdrive/controls/lib/planner.py @@ -15,10 +15,7 @@ from selfdrive.controls.lib.long_mpc import LongitudinalMpc from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX -MAX_SPEED = 255.0 - LON_MPC_STEP = 0.2 # first step is 0.2s -MAX_SPEED_ERROR = 2.0 AWARENESS_DECEL = -0.2 # car smoothly decel at .2m/s^2 when user is distracted # lookup tables VS speed to determine min and max accels in cruise @@ -36,9 +33,6 @@ _A_TOTAL_MAX_V = [1.7, 3.2] _A_TOTAL_MAX_BP = [20., 40.] -# 75th percentile -SPEED_PERCENTILE_IDX = 7 - def calc_cruise_accel_limits(v_ego, following): a_cruise_min = interp(v_ego, _A_CRUISE_MIN_BP, _A_CRUISE_MIN_V) @@ -162,8 +156,8 @@ def update(self, sm, pm, CP, VM, PP): self.mpc1.set_cur_state(self.v_acc_start, self.a_acc_start) self.mpc2.set_cur_state(self.v_acc_start, self.a_acc_start) - self.mpc1.update(pm, sm['carState'], lead_1, v_cruise_setpoint) - self.mpc2.update(pm, sm['carState'], lead_2, v_cruise_setpoint) + self.mpc1.update(pm, sm['carState'], lead_1) + self.mpc2.update(pm, sm['carState'], lead_2) self.choose_solution(v_cruise_setpoint, enabled) diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index b439681a3a2303..44dd1ec621d428 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -1,9 +1,7 @@ #!/usr/bin/env python3 -import gc - from cereal import car from common.params import Params -from common.realtime import set_realtime_priority +from common.realtime import Priority, config_rt_process from selfdrive.swaglog import cloudlog from selfdrive.controls.lib.planner import Planner from selfdrive.controls.lib.vehicle_model import VehicleModel @@ -12,10 +10,8 @@ def plannerd_thread(sm=None, pm=None): - gc.disable() - # start the loop - set_realtime_priority(52) + config_rt_process(2, Priority.CTRL_LOW) cloudlog.info("plannerd is waiting for CarParams") CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) @@ -27,7 +23,8 @@ def plannerd_thread(sm=None, pm=None): VM = VehicleModel(CP) if sm is None: - sm = messaging.SubMaster(['carState', 'controlsState', 'radarState', 'model', 'liveParameters']) + sm = messaging.SubMaster(['carState', 'controlsState', 'radarState', 'model', 'liveParameters'], + poll=['radarState', 'model']) if pm is None: pm = messaging.PubMaster(['plan', 'liveLongitudinalMpc', 'pathPlan', 'liveMpc']) diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 0ba14dcf260cd6..c2643d76e5c4e5 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -7,7 +7,7 @@ from cereal import car from common.numpy_fast import interp from common.params import Params -from common.realtime import Ratekeeper, set_realtime_priority +from common.realtime import Ratekeeper, Priority, set_realtime_priority from selfdrive.config import RADAR_TO_CAMERA from selfdrive.controls.lib.cluster.fastcluster_py import cluster_points_centroid from selfdrive.controls.lib.radar_helpers import Cluster, Track @@ -99,7 +99,7 @@ def __init__(self, radar_ts, delay=0): self.ready = False - def update(self, frame, sm, rr, has_radar): + def update(self, frame, sm, rr, enable_lead): self.current_time = 1e-9*max([sm.logMonoTime[key] for key in sm.logMonoTime.keys()]) if sm.updated['controlsState']: @@ -166,7 +166,7 @@ def update(self, frame, sm, rr, has_radar): dat.radarState.radarErrors = list(rr.errors) dat.radarState.controlsStateMonoTime = sm.logMonoTime['controlsState'] - if has_radar: + if enable_lead: dat.radarState.leadOne = get_lead(self.v_ego, self.ready, clusters, sm['model'].lead, low_speed_override=True) dat.radarState.leadTwo = get_lead(self.v_ego, self.ready, clusters, sm['model'].leadFuture, low_speed_override=False) return dat @@ -174,7 +174,7 @@ def update(self, frame, sm, rr, has_radar): # fuses camera and radar data for best lead detection def radard_thread(sm=None, pm=None, can_sock=None): - set_realtime_priority(52) + set_realtime_priority(Priority.CTRL_LOW) # wait for stats about the car to come in from controls cloudlog.info("radard is waiting for CarParams") @@ -200,7 +200,8 @@ def radard_thread(sm=None, pm=None, can_sock=None): rk = Ratekeeper(1.0 / CP.radarTimeStep, print_delay_threshold=None) RD = RadarD(CP.radarTimeStep, RI.delay) - has_radar = not CP.radarOffCan + # TODO: always log leads once we can hide them conditionally + enable_lead = CP.openpilotLongitudinalControl or not CP.radarOffCan while 1: can_strings = messaging.drain_sock_raw(can_sock, wait_for_one=True) @@ -211,7 +212,7 @@ def radard_thread(sm=None, pm=None, can_sock=None): sm.update(0) - dat = RD.update(rk.frame, sm, rr, has_radar) + dat = RD.update(rk.frame, sm, rr, enable_lead) dat.radarState.cumLagMs = -rk.remaining*1000. pm.send('radarState', dat) diff --git a/selfdrive/crash.py b/selfdrive/crash.py index 7459f7166873d7..22d6aa068029bd 100644 --- a/selfdrive/crash.py +++ b/selfdrive/crash.py @@ -6,9 +6,9 @@ from selfdrive.version import version, dirty from selfdrive.swaglog import cloudlog -from common.android import ANDROID +from common.hardware import PC -if os.getenv("NOLOG") or os.getenv("NOCRASH") or not ANDROID: +if os.getenv("NOLOG") or os.getenv("NOCRASH") or PC: def capture_exception(*args, **kwargs): pass diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py index 28cabe6c8cbeef..9b5681e89bceb8 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -30,8 +30,16 @@ SLEEP_INTERVAL = 0.2 monitored_proc_names = [ - 'ubloxd', 'thermald', 'uploader', 'deleter', 'controlsd', 'plannerd', 'radard', 'mapd', 'loggerd', 'logmessaged', 'tombstoned', - 'logcatd', 'proclogd', 'boardd', 'pandad', './ui', 'ui', 'calibrationd', 'params_learner', 'modeld', 'dmonitoringd', 'dmonitoringmodeld', 'camerad', 'sensord', 'updated', 'gpsd', 'athena', 'locationd', 'paramsd'] + # openpilot procs + 'controlsd', 'locationd', 'loggerd','plannerd', + 'ubloxd', 'thermald', 'uploader', 'deleter', 'radard', 'logmessaged', 'tombstoned', + 'logcatd', 'proclogd', 'boardd', 'pandad', './ui', 'ui', 'calibrationd', 'params_learner', 'modeld', 'dmonitoringd', + 'dmonitoringmodeld', 'camerad', 'sensord', 'updated', 'gpsd', 'athena', 'locationd', 'paramsd', + + # android procs + 'SurfaceFlinger', 'sensors.qcom' +] + cpu_time_names = ['user', 'system', 'children_user', 'children_system'] timer = getattr(time, 'monotonic', time.time) diff --git a/selfdrive/debug/cycle_alerts.py b/selfdrive/debug/cycle_alerts.py index 63b7d758c5901f..45bc8984c215c6 100755 --- a/selfdrive/debug/cycle_alerts.py +++ b/selfdrive/debug/cycle_alerts.py @@ -3,56 +3,65 @@ # pylint: skip-file # type: ignore -import argparse import time import cereal.messaging as messaging -from selfdrive.controls.lib.events import EVENTS, Alert +from selfdrive.car.honda.interface import CarInterface +from selfdrive.controls.lib.events import ET, EVENTS, Events +from selfdrive.controls.lib.alertmanager import AlertManager -def now_millis(): return time.time() * 1000 -ALERTS = [a for _, et in EVENTS.items() for _, a in et.items() if isinstance(a, Alert)] +def cycle_alerts(duration=200, is_metric=False): + alerts = list(EVENTS.keys()) + print(alerts) -#from cereal import car -#ALERTS = [a for a in ALERTS if a.audible_alert == car.CarControl.HUDControl.AudibleAlert.chimeWarningRepeat] - -default_alerts = sorted(ALERTS, key=lambda alert: (alert.alert_size, len(alert.alert_text_2))) - -def cycle_alerts(duration_millis, alerts=None): - if alerts is None: - alerts = default_alerts + CP = CarInterface.get_params("HONDA CIVIC 2016 TOURING") + sm = messaging.SubMaster(['thermal', 'health', 'frame', 'model', 'liveCalibration', + 'dMonitoringState', 'plan', 'pathPlan', 'liveLocationKalman']) controls_state = messaging.pub_sock('controlsState') + thermal = messaging.pub_sock('thermal') idx, last_alert_millis = 0, 0 - alert = alerts[0] + + events = Events() + AM = AlertManager() + + frame = 0 + while 1: - if (now_millis() - last_alert_millis) > duration_millis: - alert = alerts[idx] + if frame % duration == 0: idx = (idx + 1) % len(alerts) - last_alert_millis = now_millis() - print('sending {}'.format(str(alert))) + events.clear() + events.add(alerts[idx]) + + + current_alert_types = [ET.PERMANENT, ET.USER_DISABLE, ET.IMMEDIATE_DISABLE, + ET.SOFT_DISABLE, ET.PRE_ENABLE, ET.NO_ENTRY, + ET.ENABLE, ET.WARNING] + a = events.create_alerts(current_alert_types, [CP, sm, is_metric]) + AM.add_many(frame, a) + AM.process_alerts(frame) dat = messaging.new_message() dat.init('controlsState') - dat.controlsState.alertType = alert.alert_type - dat.controlsState.alertText1 = alert.alert_text_1 - dat.controlsState.alertText2 = alert.alert_text_2 - dat.controlsState.alertSize = alert.alert_size - #dat.controlsState.alertStatus = alert.alert_status - dat.controlsState.alertSound = alert.audible_alert + dat.controlsState.alertText1 = AM.alert_text_1 + dat.controlsState.alertText2 = AM.alert_text_2 + dat.controlsState.alertSize = AM.alert_size + dat.controlsState.alertStatus = AM.alert_status + dat.controlsState.alertBlinkingRate = AM.alert_rate + dat.controlsState.alertType = AM.alert_type + dat.controlsState.alertSound = AM.audible_alert controls_state.send(dat.to_bytes()) + dat = messaging.new_message() + dat.init('thermal') + dat.thermal.started = True + thermal.send(dat.to_bytes()) + + frame += 1 time.sleep(0.01) if __name__ == '__main__': - parser = argparse.ArgumentParser() - parser.add_argument('--duration', type=int, default=1000) - parser.add_argument('--alert-types', nargs='+') - args = parser.parse_args() - alerts = None - if args.alert_types: - alerts = [next(a for a in ALERTS if a.alert_type==alert_type) for alert_type in args.alert_types] - - cycle_alerts(args.duration, alerts=alerts) + cycle_alerts() diff --git a/selfdrive/debug/disable_ecu.py b/selfdrive/debug/disable_ecu.py new file mode 100644 index 00000000000000..9dace9a6858f97 --- /dev/null +++ b/selfdrive/debug/disable_ecu.py @@ -0,0 +1,40 @@ +#!/usr/bin/env python3 +import traceback + +import cereal.messaging as messaging +from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery +from selfdrive.swaglog import cloudlog + +EXT_DIAG_REQUEST = b'\x10\x03' +EXT_DIAG_RESPONSE = b'\x50\x03' +COM_CONT_REQUEST = b'\x28\x83\x03' +COM_CONT_RESPONSE = b'' + +def disable_ecu(ecu_addr, logcan, sendcan, bus, timeout=0.1, retry=5, debug=False): + print(f"ecu disable {hex(ecu_addr)} ...") + for i in range(retry): + try: + # enter extended diagnostic session + query = IsoTpParallelQuery(sendcan, logcan, bus, [ecu_addr], [EXT_DIAG_REQUEST], [EXT_DIAG_RESPONSE], debug=debug) + for addr, dat in query.get_data(timeout).items(): # pylint: disable=unused-variable + print("ecu communication control disable tx/rx ...") + # communication control disable tx and rx + query = IsoTpParallelQuery(sendcan, logcan, bus, [ecu_addr], [COM_CONT_REQUEST], [COM_CONT_RESPONSE], debug=debug) + query.get_data(0) + return True + print(f"ecu disable retry ({i+1}) ...") + except Exception: + cloudlog.warning(f"ecu disable exception: {traceback.format_exc()}") + + return False + + +if __name__ == "__main__": + import time + sendcan = messaging.pub_sock('sendcan') + logcan = messaging.sub_sock('can') + time.sleep(1) + + # honda bosch radar disable + disabled = disable_ecu(0x18DAB0F1, logcan, sendcan, 1, debug=False) + print(f"disabled: {disabled}") diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index cfdb387b913f99..112ca96a93aa36 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -61,4 +61,11 @@ print("{} = {}".format(".".join(value), item)) print("") else: - print(evt) + try: + print(evt) + except UnicodeDecodeError: + w = evt.which() + s = f"( logMonoTime {evt.logMonoTime} \n {w} = " + s += str(evt.__getattr__(w)) + s += f"\n valid = {evt.valid} )" + print(s) diff --git a/selfdrive/debug/get_fingerprint.py b/selfdrive/debug/get_fingerprint.py index 9ece7d7268cb32..2695d457d19f72 100755 --- a/selfdrive/debug/get_fingerprint.py +++ b/selfdrive/debug/get_fingerprint.py @@ -17,6 +17,9 @@ msgs = {} while True: lc = messaging.recv_sock(logcan, True) + if lc is None: + continue + for c in lc.can: # read also msgs sent by EON on CAN bus 0x80 and filter out the # addr with more than 11 bits diff --git a/selfdrive/debug/uiview.py b/selfdrive/debug/uiview.py old mode 100644 new mode 100755 index 899f932ad6b500..e31d6cf3c399cc --- a/selfdrive/debug/uiview.py +++ b/selfdrive/debug/uiview.py @@ -3,12 +3,12 @@ import cereal.messaging as messaging from selfdrive.manager import start_managed_process, kill_managed_process -services = ['controlsState', 'thermal'] # the services needed to be spoofed to start ui offroad -procs = ['camerad', 'ui'] +services = ['controlsState', 'thermal', 'radarState'] # the services needed to be spoofed to start ui offroad +procs = ['camerad', 'ui', 'modeld', 'calibrationd'] [start_managed_process(p) for p in procs] # start needed processes pm = messaging.PubMaster(services) -dat_cs, dat_thermal = [messaging.new_message(s) for s in services] +dat_cs, dat_thermal, dat_radar = [messaging.new_message(s) for s in services] dat_cs.controlsState.rearViewCam = False # ui checks for these two messages dat_thermal.thermal.started = True @@ -16,6 +16,7 @@ while True: pm.send('controlsState', dat_cs) pm.send('thermal', dat_thermal) + pm.send('radarState', dat_radar) time.sleep(1 / 100) # continually send, rate doesn't matter for thermal except KeyboardInterrupt: [kill_managed_process(p) for p in procs] diff --git a/selfdrive/locationd/calibration_helpers.py b/selfdrive/locationd/calibration_helpers.py deleted file mode 100644 index c7886d30190f1b..00000000000000 --- a/selfdrive/locationd/calibration_helpers.py +++ /dev/null @@ -1,10 +0,0 @@ -import math - -class Filter: - MIN_SPEED = 7 # m/s (~15.5mph) - MAX_YAW_RATE = math.radians(3) # per second - -class Calibration: - UNCALIBRATED = 0 - CALIBRATED = 1 - INVALID = 2 diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index a27e284a9ccdf9..9cda80cfe8c1c0 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -1,4 +1,10 @@ #!/usr/bin/env python3 +''' +This process finds calibration values. More info on what these calibration values +are can be found here https://github.com/commaai/openpilot/tree/master/common/transformations +While the roll calibration is a real value that can be estimated, here we assume it's zero, +and the image input into the neural network is not corrected for roll. +''' import os import copy @@ -6,177 +12,196 @@ import numpy as np import cereal.messaging as messaging from selfdrive.config import Conversions as CV -from selfdrive.locationd.calibration_helpers import Calibration from selfdrive.swaglog import cloudlog from common.params import Params, put_nonblocking from common.transformations.model import model_height -from common.transformations.camera import view_frame_from_device_frame, get_view_frame_from_road_frame, \ - get_calib_from_vp, vp_from_rpy, H, W, FOCAL +from common.transformations.camera import get_view_frame_from_road_frame +from common.transformations.orientation import rot_from_euler, euler_from_rot MIN_SPEED_FILTER = 15 * CV.MPH_TO_MS MAX_VEL_ANGLE_STD = np.radians(0.25) MAX_YAW_RATE_FILTER = np.radians(2) # per second -# This is all 20Hz, blocks needed for efficiency +# This is at model frequency, blocks needed for efficiency +SMOOTH_CYCLES = 400 BLOCK_SIZE = 100 -INPUTS_NEEDED = 5 # allow to update VP every so many frames +INPUTS_NEEDED = 5 # Minimum blocks needed for valid calibration INPUTS_WANTED = 50 # We want a little bit more than we need for stability -WRITE_CYCLES = 10 # write every 1000 cycles -VP_INIT = np.array([W/2., H/2.]) +MAX_ALLOWED_SPREAD = np.radians(2) +RPY_INIT = np.array([0.0,0.0,0.0]) # These values are needed to accomodate biggest modelframe -VP_VALIDITY_CORNERS = np.array([[W//2 - 63, 300], [W//2 + 63, 520]]) +PITCH_LIMITS = np.array([-0.09074112085129739, 0.14907572052989657]) +YAW_LIMITS = np.array([-0.06912048084718224, 0.06912048084718235]) DEBUG = os.getenv("DEBUG") is not None -def is_calibration_valid(vp): - return vp[0] > VP_VALIDITY_CORNERS[0, 0] and vp[0] < VP_VALIDITY_CORNERS[1, 0] and \ - vp[1] > VP_VALIDITY_CORNERS[0, 1] and vp[1] < VP_VALIDITY_CORNERS[1, 1] +class Calibration: + UNCALIBRATED = 0 + CALIBRATED = 1 + INVALID = 2 -def sanity_clip(vp): - if np.isnan(vp).any(): - vp = VP_INIT - return np.array([np.clip(vp[0], VP_VALIDITY_CORNERS[0, 0] - 5, VP_VALIDITY_CORNERS[1, 0] + 5), - np.clip(vp[1], VP_VALIDITY_CORNERS[0, 1] - 5, VP_VALIDITY_CORNERS[1, 1] + 5)]) +def is_calibration_valid(rpy): + return (PITCH_LIMITS[0] < rpy[1] < PITCH_LIMITS[1]) and (YAW_LIMITS[0] < rpy[2] < YAW_LIMITS[1]) -def intrinsics_from_vp(vp): - return np.array([ - [FOCAL, 0., vp[0]], - [ 0., FOCAL, vp[1]], - [ 0., 0., 1.]]) +def sanity_clip(rpy): + if np.isnan(rpy).any(): + rpy = RPY_INIT + return np.array([rpy[0], + np.clip(rpy[1], PITCH_LIMITS[0] - .005, PITCH_LIMITS[1] + .005), + np.clip(rpy[2], YAW_LIMITS[0] - .005, YAW_LIMITS[1] + .005)]) class Calibrator(): def __init__(self, param_put=False): self.param_put = param_put - self.vp = copy.copy(VP_INIT) - self.vps = np.zeros((INPUTS_WANTED, 2)) - self.idx = 0 - self.block_idx = 0 - self.valid_blocks = 0 - self.cal_status = Calibration.UNCALIBRATED - self.just_calibrated = False - self.v_ego = 0 - # Read calibration - if param_put: - calibration_params = Params().get("CalibrationParams") - else: - calibration_params = None - if calibration_params: + # Read saved calibration + calibration_params = Params().get("CalibrationParams") + + rpy_init = RPY_INIT + valid_blocks = 0 + + if param_put and calibration_params: try: calibration_params = json.loads(calibration_params) - self.vp = vp_from_rpy(calibration_params["calib_radians"]) - if not np.isfinite(self.vp).all(): - self.vp = copy.copy(VP_INIT) - self.vps = np.tile(self.vp, (INPUTS_WANTED, 1)) - self.valid_blocks = calibration_params['valid_blocks'] - if not np.isfinite(self.valid_blocks) or self.valid_blocks < 0: - self.valid_blocks = 0 - self.update_status() + rpy_init = calibration_params["calib_radians"] + valid_blocks = calibration_params['valid_blocks'] except Exception: cloudlog.exception("CalibrationParams file found but error encountered") + self.reset(rpy_init, valid_blocks) + self.update_status() + + def reset(self, rpy_init=RPY_INIT, valid_blocks=0, smooth_from=None): + if not np.isfinite(rpy_init).all(): + self.rpy = copy.copy(RPY_INIT) + else: + self.rpy = rpy_init + if not np.isfinite(valid_blocks) or valid_blocks < 0: + self.valid_blocks = 0 + else: + self.valid_blocks = valid_blocks + self.rpys = np.tile(self.rpy, (INPUTS_WANTED, 1)) + + self.idx = 0 + self.block_idx = 0 + self.v_ego = 0 + + if smooth_from is None: + self.old_rpy = RPY_INIT + self.old_rpy_weight = 0.0 + else: + self.old_rpy = smooth_from + self.old_rpy_weight = 1.0 def update_status(self): - start_status = self.cal_status + if self.valid_blocks > 0: + max_rpy_calib = np.array(np.max(self.rpys[:self.valid_blocks], axis=0)) + min_rpy_calib = np.array(np.min(self.rpys[:self.valid_blocks], axis=0)) + self.calib_spread = np.abs(max_rpy_calib - min_rpy_calib) + else: + self.calib_spread = np.zeros(3) + if self.valid_blocks < INPUTS_NEEDED: self.cal_status = Calibration.UNCALIBRATED + elif is_calibration_valid(self.rpy): + self.cal_status = Calibration.CALIBRATED else: - self.cal_status = Calibration.CALIBRATED if is_calibration_valid(self.vp) else Calibration.INVALID - end_status = self.cal_status + self.cal_status = Calibration.INVALID - self.just_calibrated = False - if start_status == Calibration.UNCALIBRATED and end_status != Calibration.UNCALIBRATED: - self.just_calibrated = True + # If spread is too high, assume mounting was changed and reset to last block. + # Make the transition smooth. Abrupt transistion are not good foor feedback loop through supercombo model. + if max(self.calib_spread) > MAX_ALLOWED_SPREAD and self.cal_status == Calibration.CALIBRATED: + self.reset(self.rpys[self.block_idx - 1], valid_blocks=INPUTS_NEEDED, smooth_from=self.rpy) + + write_this_cycle = (self.idx == 0) and (self.block_idx % (INPUTS_WANTED//5) == 5) + if self.param_put and write_this_cycle: + # TODO: this should use the liveCalibration struct from cereal + cal_params = {"calib_radians": list(self.rpy), + "valid_blocks": int(self.valid_blocks)} + put_nonblocking("CalibrationParams", json.dumps(cal_params).encode('utf8')) def handle_v_ego(self, v_ego): self.v_ego = v_ego + def get_smooth_rpy(self): + if self.old_rpy_weight > 0: + return self.old_rpy_weight * self.old_rpy + (1.0 - self.old_rpy_weight) * self.rpy + else: + return self.rpy + def handle_cam_odom(self, trans, rot, trans_std, rot_std): + self.old_rpy_weight = min(0.0, self.old_rpy_weight - 1/SMOOTH_CYCLES) + straight_and_fast = ((self.v_ego > MIN_SPEED_FILTER) and (trans[0] > MIN_SPEED_FILTER) and (abs(rot[2]) < MAX_YAW_RATE_FILTER)) certain_if_calib = ((np.arctan2(trans_std[1], trans[0]) < MAX_VEL_ANGLE_STD) or (self.valid_blocks < INPUTS_NEEDED)) if straight_and_fast and certain_if_calib: - # intrinsics are not eon intrinsics, since this is calibrated frame - intrinsics = intrinsics_from_vp(self.vp) - new_vp = intrinsics.dot(view_frame_from_device_frame.dot(trans)) - new_vp = new_vp[:2]/new_vp[2] - new_vp = sanity_clip(new_vp) + observed_rpy = np.array([0, + -np.arctan2(trans[2], trans[0]), + np.arctan2(trans[1], trans[0])]) + new_rpy = euler_from_rot(rot_from_euler(self.get_smooth_rpy()).dot(rot_from_euler(observed_rpy))) + new_rpy = sanity_clip(new_rpy) - self.vps[self.block_idx] = (self.idx*self.vps[self.block_idx] + (BLOCK_SIZE - self.idx) * new_vp) / float(BLOCK_SIZE) + self.rpys[self.block_idx] = (self.idx*self.rpys[self.block_idx] + (BLOCK_SIZE - self.idx) * new_rpy) / float(BLOCK_SIZE) self.idx = (self.idx + 1) % BLOCK_SIZE if self.idx == 0: self.block_idx += 1 self.valid_blocks = max(self.block_idx, self.valid_blocks) self.block_idx = self.block_idx % INPUTS_WANTED if self.valid_blocks > 0: - self.vp = np.mean(self.vps[:self.valid_blocks], axis=0) + self.rpy = np.mean(self.rpys[:self.valid_blocks], axis=0) + + self.update_status() - if self.param_put and ((self.idx == 0 and self.block_idx == 0) or self.just_calibrated): - calib = get_calib_from_vp(self.vp) - cal_params = {"calib_radians": list(calib), - "valid_blocks": self.valid_blocks} - put_nonblocking("CalibrationParams", json.dumps(cal_params).encode('utf8')) - return new_vp + return new_rpy else: return None def send_data(self, pm): - calib = get_calib_from_vp(self.vp) - if self.valid_blocks > 0: - max_vp_calib = np.array(get_calib_from_vp(np.max(self.vps[:self.valid_blocks], axis=0))) - min_vp_calib = np.array(get_calib_from_vp(np.min(self.vps[:self.valid_blocks], axis=0))) - calib_spread = np.abs(max_vp_calib - min_vp_calib) - else: - calib_spread = np.zeros(3) - extrinsic_matrix = get_view_frame_from_road_frame(0, calib[1], calib[2], model_height) + smooth_rpy = self.get_smooth_rpy() + extrinsic_matrix = get_view_frame_from_road_frame(0, smooth_rpy[1], smooth_rpy[2], model_height) cal_send = messaging.new_message('liveCalibration') cal_send.liveCalibration.validBlocks = self.valid_blocks cal_send.liveCalibration.calStatus = self.cal_status cal_send.liveCalibration.calPerc = min(100 * (self.valid_blocks * BLOCK_SIZE + self.idx) // (INPUTS_NEEDED * BLOCK_SIZE), 100) cal_send.liveCalibration.extrinsicMatrix = [float(x) for x in extrinsic_matrix.flatten()] - cal_send.liveCalibration.rpyCalib = [float(x) for x in calib] - cal_send.liveCalibration.rpyCalibSpread = [float(x) for x in calib_spread] + cal_send.liveCalibration.rpyCalib = [float(x) for x in smooth_rpy] + cal_send.liveCalibration.rpyCalibSpread = [float(x) for x in self.calib_spread] pm.send('liveCalibration', cal_send) def calibrationd_thread(sm=None, pm=None): if sm is None: - sm = messaging.SubMaster(['cameraOdometry', 'carState']) + sm = messaging.SubMaster(['cameraOdometry', 'carState'], poll=['cameraOdometry']) if pm is None: pm = messaging.PubMaster(['liveCalibration']) calibrator = Calibrator(param_put=True) - send_counter = 0 while 1: - sm.update() - - # if no inputs still publish calibration - if not sm.updated['carState'] and not sm.updated['cameraOdometry']: - calibrator.send_data(pm) - continue + timeout = 0 if sm.frame == -1 else 100 + sm.update(timeout) - if sm.updated['carState']: + if sm.updated['cameraOdometry']: calibrator.handle_v_ego(sm['carState'].vEgo) - if send_counter % 25 == 0: - calibrator.send_data(pm) - send_counter += 1 + new_rpy = calibrator.handle_cam_odom(sm['cameraOdometry'].trans, + sm['cameraOdometry'].rot, + sm['cameraOdometry'].transStd, + sm['cameraOdometry'].rotStd) - if sm.updated['cameraOdometry']: - new_vp = calibrator.handle_cam_odom(sm['cameraOdometry'].trans, - sm['cameraOdometry'].rot, - sm['cameraOdometry'].transStd, - sm['cameraOdometry'].rotStd) + if DEBUG and new_rpy is not None: + print('got new rpy', new_rpy) - if DEBUG and new_vp is not None: - print('got new vp', new_vp) + # 4Hz driven by cameraOdometry + if sm.frame % 5 == 0: + calibrator.send_data(pm) def main(sm=None, pm=None): diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index ad820b4ea21a5c..1d1d353315ad4f 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -13,8 +13,6 @@ KalmanStatus = log.LiveLocationKalman.Status -CARSTATE_DECIMATION = 5 - class ParamsLearner: def __init__(self, CP, steer_ratio, stiffness_factor, angle_offset): @@ -32,7 +30,6 @@ def __init__(self, CP, steer_ratio, stiffness_factor, angle_offset): self.speed = 0 self.steering_pressed = False self.steering_angle = 0 - self.carstate_counter = 0 self.valid = True @@ -51,18 +48,16 @@ def handle_log(self, t, which, msg): self.kf.predict_and_observe(t, ObservationKind.ANGLE_OFFSET_FAST, np.array([[[0]]])) elif which == 'carState': - self.carstate_counter += 1 - if self.carstate_counter % CARSTATE_DECIMATION == 0: - self.steering_angle = msg.steeringAngle - self.steering_pressed = msg.steeringPressed - self.speed = msg.vEgo + self.steering_angle = msg.steeringAngle + self.steering_pressed = msg.steeringPressed + self.speed = msg.vEgo - in_linear_region = abs(self.steering_angle) < 45 or not self.steering_pressed - self.active = self.speed > 5 and in_linear_region + in_linear_region = abs(self.steering_angle) < 45 or not self.steering_pressed + self.active = self.speed > 5 and in_linear_region - if self.active: - self.kf.predict_and_observe(t, ObservationKind.STEER_ANGLE, np.array([[[math.radians(msg.steeringAngle)]]])) - self.kf.predict_and_observe(t, ObservationKind.ROAD_FRAME_X_SPEED, np.array([[[self.speed]]])) + if self.active: + self.kf.predict_and_observe(t, ObservationKind.STEER_ANGLE, np.array([[[math.radians(msg.steeringAngle)]]])) + self.kf.predict_and_observe(t, ObservationKind.ROAD_FRAME_X_SPEED, np.array([[[self.speed]]])) if not self.active: # Reset time when stopped so uncertainty doesn't grow @@ -72,7 +67,7 @@ def handle_log(self, t, which, msg): def main(sm=None, pm=None): if sm is None: - sm = messaging.SubMaster(['liveLocationKalman', 'carState']) + sm = messaging.SubMaster(['liveLocationKalman', 'carState'], poll=['liveLocationKalman']) if pm is None: pm = messaging.PubMaster(['liveParameters']) @@ -111,12 +106,11 @@ def main(sm=None, pm=None): sm.update() for which, updated in sm.updated.items(): - if not updated: - continue - t = sm.logMonoTime[which] * 1e-9 - learner.handle_log(t, which, sm[which]) + if updated: + t = sm.logMonoTime[which] * 1e-9 + learner.handle_log(t, which, sm[which]) - if sm.updated['carState'] and (learner.carstate_counter % CARSTATE_DECIMATION == 0): + if sm.updated['liveLocationKalman']: msg = messaging.new_message('liveParameters') msg.logMonoTime = sm.logMonoTime['carState'] @@ -135,7 +129,7 @@ def main(sm=None, pm=None): min_sr <= msg.liveParameters.steerRatio <= max_sr, )) - if learner.carstate_counter % 6000 == 0: # once a minute + if sm.frame % 1200 == 0: # once a minute params = { 'carFingerprint': CP.carFingerprint, 'steerRatio': msg.liveParameters.steerRatio, diff --git a/selfdrive/locationd/ublox_msg.cc b/selfdrive/locationd/ublox_msg.cc index 0bc8c0e6ff2b48..ce4e4dcac33865 100644 --- a/selfdrive/locationd/ublox_msg.cc +++ b/selfdrive/locationd/ublox_msg.cc @@ -193,10 +193,8 @@ inline bool UbloxMsgParser::valid_so_far() { kj::Array UbloxMsgParser::gen_solution() { nav_pvt_msg *msg = (nav_pvt_msg *)&msg_parse_buf[UBLOX_HEADER_SIZE]; - capnp::MallocMessageBuilder msg_builder; - cereal::Event::Builder event = msg_builder.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto gpsLoc = event.initGpsLocationExternal(); + MessageBuilder msg_builder; + auto gpsLoc = msg_builder.initEvent().initGpsLocationExternal(); gpsLoc.setSource(cereal::GpsLocationData::SensorSource::UBLOX); gpsLoc.setFlags(msg->flags); gpsLoc.setLatitude(msg->lat * 1e-07); @@ -236,11 +234,8 @@ kj::Array UbloxMsgParser::gen_raw() { return kj::Array(); } rxm_raw_msg_extra *measurements = (rxm_raw_msg_extra *)&msg_parse_buf[UBLOX_HEADER_SIZE + sizeof(rxm_raw_msg)]; - capnp::MallocMessageBuilder msg_builder; - cereal::Event::Builder event = msg_builder.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto gnss = event.initUbloxGnss(); - auto mr = gnss.initMeasurementReport(); + MessageBuilder msg_builder; + auto mr = msg_builder.initEvent().initUbloxGnss().initMeasurementReport(); mr.setRcvTow(msg->rcvTow); mr.setGpsWeek(msg->week); mr.setLeapSeconds(msg->leapS); @@ -295,11 +290,8 @@ kj::Array UbloxMsgParser::gen_nav_data() { nav_frame_buffer[msg->gnssId][msg->svid][subframeId] = words; if(nav_frame_buffer[msg->gnssId][msg->svid].size() == 5) { EphemerisData ephem_data(msg->svid, nav_frame_buffer[msg->gnssId][msg->svid]); - capnp::MallocMessageBuilder msg_builder; - cereal::Event::Builder event = msg_builder.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto gnss = event.initUbloxGnss(); - auto eph = gnss.initEphemeris(); + MessageBuilder msg_builder; + auto eph = msg_builder.initEvent().initUbloxGnss().initEphemeris(); eph.setSvId(ephem_data.svId); eph.setToc(ephem_data.toc); eph.setGpsWeek(ephem_data.gpsWeek); @@ -343,11 +335,8 @@ kj::Array UbloxMsgParser::gen_nav_data() { kj::Array UbloxMsgParser::gen_mon_hw() { mon_hw_msg *msg = (mon_hw_msg *)&msg_parse_buf[UBLOX_HEADER_SIZE]; - capnp::MallocMessageBuilder msg_builder; - cereal::Event::Builder event = msg_builder.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto gnss = event.initUbloxGnss(); - auto hwStatus = gnss.initHwStatus(); + MessageBuilder msg_builder; + auto hwStatus = msg_builder.initEvent().initUbloxGnss().initHwStatus(); hwStatus.setNoisePerMS(msg->noisePerMS); hwStatus.setAgcCnt(msg->agcCnt); hwStatus.setAStatus((cereal::UbloxGnss::HwStatus::AntennaSupervisorState) msg->aStatus); diff --git a/selfdrive/locationd/ubloxd_test.cc b/selfdrive/locationd/ubloxd_test.cc index 8653cedeab4ec3..d1118e4d29737c 100644 --- a/selfdrive/locationd/ubloxd_test.cc +++ b/selfdrive/locationd/ubloxd_test.cc @@ -47,15 +47,11 @@ Message * poll_ubloxraw_msg(Poller * poller) { size_t consuming = min(len - consumed, 128); if(consumed < len) { // create message - capnp::MallocMessageBuilder msg_builder; - cereal::Event::Builder event = msg_builder.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - - auto ublox_raw = event.initUbloxRaw(consuming); + MessageBuilder msg_builder; + auto ublox_raw = msg_builder.initEvent().initUbloxRaw(consuming); memcpy(ublox_raw.begin(), (void *)(data + consumed), consuming); - auto words = capnp::messageToFlatArray(msg_builder); - auto bytes = words.asBytes(); + auto bytes = msg_builder.toBytes(); Message * msg = new ZMQMessage(); msg->init((char*)bytes.begin(), bytes.size()); diff --git a/selfdrive/logcatd/SConscript b/selfdrive/logcatd/SConscript index 67ad673002ba8e..7f87cbaddf423f 100644 --- a/selfdrive/logcatd/SConscript +++ b/selfdrive/logcatd/SConscript @@ -1,2 +1,6 @@ -Import('env', 'cereal', 'messaging') -env.Program('logcatd.cc', LIBS=[cereal, messaging, 'cutils', 'zmq', 'czmq', 'capnp', 'kj']) +Import('env', 'cereal', 'messaging', 'arch') + +if arch == "aarch64": + env.Program('logcatd', 'logcatd_android.cc', LIBS=[cereal, messaging, 'cutils', 'zmq', 'czmq', 'capnp', 'kj']) +else: + env.Program('logcatd', 'logcatd_systemd.cc', LIBS=[cereal, messaging, 'zmq', 'capnp', 'kj', 'systemd', 'json11']) diff --git a/selfdrive/logcatd/logcatd.cc b/selfdrive/logcatd/logcatd_android.cc similarity index 88% rename from selfdrive/logcatd/logcatd.cc rename to selfdrive/logcatd/logcatd_android.cc index 181e29df1103c2..9a1753b1d67c6b 100644 --- a/selfdrive/logcatd/logcatd.cc +++ b/selfdrive/logcatd/logcatd_android.cc @@ -40,10 +40,8 @@ int main() { continue; } - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto androidEntry = event.initAndroidLog(); + MessageBuilder msg; + auto androidEntry = msg.initEvent().initAndroidLog(); androidEntry.setId(log_msg.id()); androidEntry.setTs(entry.tv_sec * 1000000000ULL + entry.tv_nsec); androidEntry.setPriority(entry.priority); diff --git a/selfdrive/logcatd/logcatd_systemd.cc b/selfdrive/logcatd/logcatd_systemd.cc new file mode 100644 index 00000000000000..adc18791418742 --- /dev/null +++ b/selfdrive/logcatd/logcatd_systemd.cc @@ -0,0 +1,71 @@ +#include +#include +#include +#include + +#include "json11.hpp" +#include + +#include "common/timing.h" +#include "messaging.hpp" + +int main(int argc, char *argv[]) { + PubMaster pm({"androidLog"}); + + sd_journal *journal; + assert(sd_journal_open(&journal, 0) >= 0); + assert(sd_journal_get_fd(journal) >= 0); // needed so sd_journal_wait() works properly if files rotate + assert(sd_journal_seek_tail(journal) >= 0); + + int r; + while (true) { + r = sd_journal_next(journal); + assert(r >= 0); + + // Wait for new message if we didn't receive anything + if (r == 0){ + do { + r = sd_journal_wait(journal, (uint64_t)-1); + assert(r >= 0); + } while (r == SD_JOURNAL_NOP); + + r = sd_journal_next(journal); + assert(r >= 0); + + if (r == 0) continue; // Try again if we still didn't get anything + } + + uint64_t timestamp = 0; + r = sd_journal_get_realtime_usec(journal, ×tamp); + assert(r >= 0); + + const void *data; + size_t length; + std::map kv; + + SD_JOURNAL_FOREACH_DATA(journal, data, length){ + std::string str((char*)data, length); + + // Split "KEY=VALUE"" on "=" and put in map + std::size_t found = str.find("="); + if (found != std::string::npos){ + kv[str.substr(0, found)] = str.substr(found + 1, std::string::npos); + } + } + + MessageBuilder msg; + + // Build message + auto androidEntry = msg.initEvent().initAndroidLog(); + androidEntry.setTs(timestamp); + androidEntry.setMessage(json11::Json(kv).dump()); + if (kv.count("_PID")) androidEntry.setPid(std::atoi(kv["_PID"].c_str())); + if (kv.count("PRIORITY")) androidEntry.setPriority(std::atoi(kv["PRIORITY"].c_str())); + if (kv.count("SYSLOG_IDENTIFIER")) androidEntry.setTag(kv["SYSLOG_IDENTIFIER"]); + + pm.send("androidLog", msg); + } + + sd_journal_close(journal); + return 0; +} diff --git a/selfdrive/loggerd/config.py b/selfdrive/loggerd/config.py index 0ee6fa671d0327..f859e8cb4acb61 100644 --- a/selfdrive/loggerd/config.py +++ b/selfdrive/loggerd/config.py @@ -6,24 +6,26 @@ else: ROOT = '/data/media/0/realdata/' + +CAMERA_FPS = 20 SEGMENT_LENGTH = 60 def get_available_percent(default=None): - try: - statvfs = os.statvfs(ROOT) - available_percent = 100.0 * statvfs.f_bavail / statvfs.f_blocks - except OSError: - available_percent = default + try: + statvfs = os.statvfs(ROOT) + available_percent = 100.0 * statvfs.f_bavail / statvfs.f_blocks + except OSError: + available_percent = default - return available_percent + return available_percent def get_available_bytes(default=None): - try: - statvfs = os.statvfs(ROOT) - available_bytes = statvfs.f_bavail * statvfs.f_frsize - except OSError: - available_bytes = default + try: + statvfs = os.statvfs(ROOT) + available_bytes = statvfs.f_bavail * statvfs.f_frsize + except OSError: + available_bytes = default - return available_bytes + return available_bytes diff --git a/selfdrive/loggerd/encoder.c b/selfdrive/loggerd/encoder.c index 297f65cf8501e6..4939a48535b074 100644 --- a/selfdrive/loggerd/encoder.c +++ b/selfdrive/loggerd/encoder.c @@ -474,17 +474,16 @@ int encoder_encode_frame(EncoderState *s, // this sometimes freezes... put it outside the encoder lock so we can still trigger rotates... // THIS IS A REALLY BAD IDEA, but apparently the race has to happen 30 times to trigger this - pthread_mutex_unlock(&s->lock); + //pthread_mutex_unlock(&s->lock); OMX_BUFFERHEADERTYPE* in_buf = queue_pop(&s->free_in); - pthread_mutex_lock(&s->lock); - - if (s->rotating) { - encoder_close(s); - encoder_open(s, s->next_path); - s->segment = s->next_segment; - s->rotating = false; - } + //pthread_mutex_lock(&s->lock); + // if (s->rotating) { + // encoder_close(s); + // encoder_open(s, s->next_path); + // s->segment = s->next_segment; + // s->rotating = false; + // } int ret = s->counter; uint8_t *in_buf_ptr = in_buf->pBuffer; @@ -638,6 +637,7 @@ void encoder_close(EncoderState *s) { if (s->remuxing) { av_write_trailer(s->ofmt_ctx); + avcodec_free_context(&s->codec_ctx); avio_closep(&s->ofmt_ctx->pb); avformat_free_context(s->ofmt_ctx); } else { diff --git a/selfdrive/loggerd/logger.cc b/selfdrive/loggerd/logger.cc index e0d0a73652202e..0cec20f68006ed 100644 --- a/selfdrive/loggerd/logger.cc +++ b/selfdrive/loggerd/logger.cc @@ -12,22 +12,17 @@ #include #include +#include "messaging.hpp" #include "common/swaglog.h" #include "logger.h" -#include -#include "cereal/gen/cpp/log.capnp.h" - static void log_sentinel(LoggerState *s, cereal::Sentinel::SentinelType type) { - capnp::MallocMessageBuilder msg; - auto event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto sen = event.initSentinel(); + MessageBuilder msg; + auto sen = msg.initEvent().initSentinel(); sen.setType(type); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); + auto bytes = msg.toBytes(); logger_log(s, bytes.begin(), bytes.size(), true); } diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index 9cc3043a704963..c7487677aebf3f 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -10,6 +10,7 @@ #include #include #include +#include #include #include @@ -51,10 +52,21 @@ #include "cereal/gen/cpp/log.capnp.h" +#define CAM_IDX_FCAM 0 +#define CAM_IDX_DCAM 1 +#define CAM_IDX_ECAM 2 + #define CAMERA_FPS 20 #define SEGMENT_LENGTH 60 + +#define MAIN_BITRATE 5000000 +#ifndef QCOM2 +#define DCAM_BITRATE 2500000 +#else +#define DCAM_BITRATE MAIN_BITRATE +#endif + #define LOG_ROOT "/data/media/0/realdata" -#define ENABLE_LIDAR 0 #define RAW_CLIP_LENGTH 100 // 5 seconds at 20fps #define RAW_CLIP_FREQUENCY (randrange(61, 8*60)) // once every ~4 minutes @@ -84,21 +96,34 @@ struct LoggerdState { uint32_t last_frame_id; uint32_t rotate_last_frame_id; int rotate_segment; + int rotate_seq_id; + + pthread_mutex_t rotate_lock; + int num_encoder; + int should_close; + int finish_close; }; LoggerdState s; #ifndef DISABLE_ENCODER -void encoder_thread(bool is_streaming, bool raw_clips, bool front) { +void encoder_thread(bool is_streaming, bool raw_clips, int cam_idx) { int err; - if (front) { - std::vector value = read_db_bytes("RecordFront"); - if (value.size() == 0 || value[0] != '1') return; + // 0:f, 1:d, 2:e + if (cam_idx == CAM_IDX_DCAM) { + // TODO: add this back + #ifndef QCOM2 + if (!read_db_bool("RecordFront")) return; LOGW("recording front camera"); - + #endif set_thread_name("FrontCameraEncoder"); - } else { + } else if (cam_idx == CAM_IDX_FCAM) { set_thread_name("RearCameraEncoder"); + } else if (cam_idx == CAM_IDX_ECAM) { + set_thread_name("WideCameraEncoder"); + } else { + LOGE("unexpected camera index provided"); + assert(false); } VisionStream stream; @@ -108,20 +133,27 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { EncoderState encoder_alt; bool has_encoder_alt = false; + pthread_mutex_lock(&s.rotate_lock); + int my_idx = s.num_encoder; + s.num_encoder += 1; + pthread_mutex_unlock(&s.rotate_lock); + int encoder_segment = -1; int cnt = 0; - PubSocket *idx_sock = PubSocket::create(s.ctx, front ? "frontEncodeIdx" : "encodeIdx"); + PubSocket *idx_sock = PubSocket::create(s.ctx, cam_idx == CAM_IDX_DCAM ? "frontEncodeIdx" : (cam_idx == CAM_IDX_ECAM ? "wideEncodeIdx" : "encodeIdx")); assert(idx_sock != NULL); LoggerHandle *lh = NULL; while (!do_exit) { VisionStreamBufs buf_info; - if (front) { + if (cam_idx == CAM_IDX_DCAM) { err = visionstream_init(&stream, VISION_STREAM_YUV_FRONT, false, &buf_info); - } else { + } else if (cam_idx == CAM_IDX_FCAM) { err = visionstream_init(&stream, VISION_STREAM_YUV, false, &buf_info); + } else if (cam_idx == CAM_IDX_ECAM) { + err = visionstream_init(&stream, VISION_STREAM_YUV_WIDE, false, &buf_info); } if (err != 0) { LOGD("visionstream connect fail"); @@ -131,11 +163,11 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { if (!encoder_inited) { LOGD("encoder init %dx%d", buf_info.width, buf_info.height); - encoder_init(&encoder, front ? "dcamera.hevc" : "fcamera.hevc", buf_info.width, buf_info.height, CAMERA_FPS, front ? 2500000 : 5000000, true, false); + encoder_init(&encoder, cam_idx == CAM_IDX_DCAM ? "dcamera.hevc" : (cam_idx == CAM_IDX_ECAM ? "ecamera.hevc" : "fcamera.hevc"), buf_info.width, buf_info.height, CAMERA_FPS, cam_idx == CAM_IDX_DCAM ? DCAM_BITRATE:MAIN_BITRATE, true, false); #ifndef QCOM2 // TODO: fix qcamera on tici - if (!front) { + if (cam_idx == CAM_IDX_FCAM) { encoder_init(&encoder_alt, "qcamera.ts", 480, 360, CAMERA_FPS, 128000, false, true); has_encoder_alt = true; } @@ -176,19 +208,20 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { uint8_t *v = u + (buf_info.width/2)*(buf_info.height/2); { + // all the rotation stuff bool should_rotate = false; std::unique_lock lk(s.lock); - if (!front) { + if (cam_idx == CAM_IDX_FCAM) { // TODO: should wait for three cameras on tici? // wait if log camera is older on back camera while ( extra.frame_id > s.last_frame_id //if the log camera is older, wait for it to catch up. && (extra.frame_id-s.last_frame_id) < 8 // but if its too old then there probably was a discontinuity (visiond restarted) && !do_exit) { s.cv.wait(lk); } - should_rotate = extra.frame_id > s.rotate_last_frame_id && encoder_segment < s.rotate_segment; + should_rotate = extra.frame_id > s.rotate_last_frame_id && encoder_segment < s.rotate_segment && s.rotate_seq_id == my_idx; } else { // front camera is best effort - should_rotate = encoder_segment < s.rotate_segment; + should_rotate = encoder_segment < s.rotate_segment && s.rotate_seq_id == my_idx; } if (do_exit) break; @@ -197,6 +230,8 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { LOG("rotate encoder to %s", s.segment_path); encoder_rotate(&encoder, s.segment_path, s.rotate_segment); + s.rotate_seq_id = (my_idx + 1) % s.num_encoder; + if (has_encoder_alt) { encoder_rotate(&encoder_alt, s.segment_path, s.rotate_segment); } @@ -211,8 +246,43 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { } lh = logger_get_handle(&s.logger); } - } + if (encoder.rotating) { + pthread_mutex_lock(&s.rotate_lock); + s.should_close += 1; + pthread_mutex_unlock(&s.rotate_lock); + + while(s.should_close > 0 && s.should_close < s.num_encoder) { + // printf("%d waiting for others to reach close, %d/%d \n", my_idx, s.should_close, s.num_encoder); + s.cv.wait(lk); + } + + pthread_mutex_lock(&s.rotate_lock); + if (s.should_close == s.num_encoder) { + s.should_close = 1 - s.num_encoder; + } else { + s.should_close += 1; + } + encoder_close(&encoder); + encoder_open(&encoder, encoder.next_path); + encoder.segment = encoder.next_segment; + encoder.rotating = false; + if (has_encoder_alt) { + encoder_close(&encoder_alt); + encoder_open(&encoder_alt, encoder_alt.next_path); + encoder_alt.segment = encoder_alt.next_segment; + encoder_alt.rotating = false; + } + s.finish_close += 1; + pthread_mutex_unlock(&s.rotate_lock); + + while(s.finish_close > 0 && s.finish_close < s.num_encoder) { + // printf("%d waiting for others to actually close, %d/%d \n", my_idx, s.finish_close, s.num_encoder); + s.cv.wait(lk); + } + s.finish_close = 0; + } + } { // encode hevc int out_segment = -1; @@ -220,7 +290,6 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { y, u, v, buf_info.width, buf_info.height, &out_segment, &extra); - if (has_encoder_alt) { int out_segment_alt = -1; encoder_encode_frame(&encoder_alt, @@ -230,18 +299,20 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { } // publish encode index - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto eidx = event.initEncodeIdx(); + MessageBuilder msg; + auto eidx = msg.initEvent().initEncodeIdx(); eidx.setFrameId(extra.frame_id); - eidx.setType(front ? cereal::EncodeIndex::Type::FRONT : cereal::EncodeIndex::Type::FULL_H_E_V_C); +#ifdef QCOM2 + eidx.setType(cereal::EncodeIndex::Type::FULL_H_E_V_C); +#else + eidx.setType(cam_idx == CAM_IDX_DCAM ? cereal::EncodeIndex::Type::FRONT : cereal::EncodeIndex::Type::FULL_H_E_V_C); +#endif eidx.setEncodeId(cnt); eidx.setSegmentNum(out_segment); eidx.setSegmentId(out_id); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); + auto bytes = msg.toBytes(); + if (idx_sock->send((char*)bytes.begin(), bytes.size()) < 0) { printf("err sending encodeIdx pkt: %s\n", strerror(errno)); } @@ -262,18 +333,15 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { } // publish encode index - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto eidx = event.initEncodeIdx(); + MessageBuilder msg; + auto eidx = msg.initEvent().initEncodeIdx(); eidx.setFrameId(extra.frame_id); eidx.setType(cereal::EncodeIndex::Type::FULL_LOSSLESS_CLIP); eidx.setEncodeId(cnt); eidx.setSegmentNum(out_segment); eidx.setSegmentId(out_id); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); + auto bytes = msg.toBytes(); if (lh) { lh_log(lh, bytes.begin(), bytes.size(), false); } @@ -323,78 +391,6 @@ void encoder_thread(bool is_streaming, bool raw_clips, bool front) { } #endif -#if ENABLE_LIDAR - -#include -#include -#include -#include - -#define VELODYNE_DATA_PORT 2368 -#define VELODYNE_TELEMETRY_PORT 8308 - -#define MAX_LIDAR_PACKET 2048 - -int lidar_thread() { - // increase kernel max buffer size - system("sysctl -w net.core.rmem_max=26214400"); - set_thread_name("lidar"); - - int sock; - if ((sock = socket(AF_INET, SOCK_DGRAM, 0)) < 0) { - perror("cannot create socket"); - return -1; - } - - int a = 26214400; - if (setsockopt(sock, SOL_SOCKET, SO_RCVBUF, &a, sizeof(int)) == -1) { - perror("cannot set socket opts"); - return -1; - } - - struct sockaddr_in addr; - memset(&addr, 0, sizeof(struct sockaddr_in)); - addr.sin_family = AF_INET; - addr.sin_port = htons(VELODYNE_DATA_PORT); - inet_aton("192.168.5.11", &(addr.sin_addr)); - - if (bind(sock, (struct sockaddr *) &addr, sizeof(addr)) < 0) { - perror("cannot bind LIDAR socket"); - return -1; - } - - capnp::byte buf[MAX_LIDAR_PACKET]; - - while (!do_exit) { - // receive message - struct sockaddr from; - socklen_t fromlen = sizeof(from); - int cnt = recvfrom(sock, (void *)buf, MAX_LIDAR_PACKET, 0, &from, &fromlen); - if (cnt <= 0) { - printf("bug in lidar recieve!\n"); - continue; - } - - // create message for log - capnp::MallocMessageBuilder msg; - auto event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto lidar_pts = event.initLidarPts(); - - // copy in the buffer - // TODO: can we remove this copy? does it matter? - kj::ArrayPtr bufferPtr = kj::arrayPtr(buf, cnt); - lidar_pts.setPkt(bufferPtr); - - // log it - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - logger_log(&s.logger, bytes.begin(), bytes.size()); - } - return 0; -} -#endif - } void append_property(const char* key, const char* value, void *cookie) { @@ -405,10 +401,8 @@ void append_property(const char* key, const char* value, void *cookie) { } kj::Array gen_init_data() { - capnp::MallocMessageBuilder msg; - auto event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto init = event.initInitData(); + MessageBuilder msg; + auto init = msg.initEvent().initInitData(); init.setDeviceType(cereal::InitData::DeviceType::NEO); init.setVersion(capnp::Text::Reader(COMMA_VERSION)); @@ -466,8 +460,7 @@ kj::Array gen_init_data() { init.setGitRemote(capnp::Text::Reader(git_remote.data(), git_remote.size())); } - std::vector passive = read_db_bytes("Passive"); - init.setPassive(passive.size() > 0 && passive[0] == '1'); + init.setPassive(read_db_bool("Passive")); { // log params std::map params; @@ -510,11 +503,8 @@ static void bootlog() { LOGW("bootlog to %s", s.segment_path); { - capnp::MallocMessageBuilder msg; - auto event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - - auto boot = event.initBoot(); + MessageBuilder msg; + auto boot = msg.initEvent().initBoot(); boot.setWallTimeNanos(nanos_since_epoch()); @@ -524,8 +514,7 @@ static void bootlog() { std::string lastPmsg = util::read_file("/sys/fs/pstore/pmsg-ramoops-0"); boot.setLastPmsg(capnp::Data::Reader((const kj::byte*)lastPmsg.data(), lastPmsg.size())); - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); + auto bytes = msg.toBytes(); logger_log(&s.logger, bytes.begin(), bytes.size(), false); } @@ -540,6 +529,11 @@ int main(int argc, char** argv) { return 0; } + int segment_length = SEGMENT_LENGTH; + if (getenv("LOGGERD_TEST")) { + segment_length = atoi(getenv("LOGGERD_SEGMENT_LENGTH")); + } + setpriority(PRIO_PROCESS, 0, -12); clear_locks(); @@ -602,24 +596,29 @@ int main(int argc, char** argv) { double start_ts = seconds_since_boot(); double last_rotate_ts = start_ts; - + s.rotate_seq_id = 0; + s.should_close = 0; + s.finish_close = 0; + s.num_encoder = 0; + pthread_mutex_init(&s.rotate_lock, NULL); #ifndef DISABLE_ENCODER // rear camera - std::thread encoder_thread_handle(encoder_thread, is_streaming, false, false); + std::thread encoder_thread_handle(encoder_thread, is_streaming, false, CAM_IDX_FCAM); // front camera - std::thread front_encoder_thread_handle(encoder_thread, false, false, true); -#endif + std::thread front_encoder_thread_handle(encoder_thread, false, false, CAM_IDX_DCAM); -#if ENABLE_LIDAR - std::thread lidar_thread_handle(lidar_thread); + #ifdef QCOM2 + // wide camera + std::thread wide_encoder_thread_handle(encoder_thread, false, false, CAM_IDX_ECAM); + #endif #endif uint64_t msg_count = 0; uint64_t bytes_count = 0; while (!do_exit) { - for (auto sock : poller->poll(100 * 1000)){ + for (auto sock : poller->poll(100 * 1000)) { while (true) { Message * msg = sock->receive(true); if (msg == NULL){ @@ -659,10 +658,10 @@ int main(int argc, char** argv) { } double ts = seconds_since_boot(); - if (ts - last_rotate_ts > SEGMENT_LENGTH) { + if (ts - last_rotate_ts > segment_length) { // rotate the log - last_rotate_ts += SEGMENT_LENGTH; + last_rotate_ts += segment_length; std::lock_guard guard(s.lock); s.rotate_last_frame_id = s.last_frame_id; @@ -684,16 +683,14 @@ int main(int argc, char** argv) { #ifndef DISABLE_ENCODER + #ifdef QCOM2 + wide_encoder_thread_handle.join(); + #endif front_encoder_thread_handle.join(); encoder_thread_handle.join(); LOGW("encoder joined"); #endif -#if ENABLE_LIDAR - lidar_thread_handle.join(); - LOGW("lidar joined"); -#endif - logger_close(&s.logger); for (auto s : socks){ diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index 34bfc7895902b9..08c1f323ec2063 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -1,29 +1,32 @@ #!/usr/bin/env python3 +import ctypes +import inspect +import json import os +import random import re +import subprocess +import threading import time -import json -import random -import ctypes -import inspect -import requests import traceback -import threading -import subprocess -from selfdrive.swaglog import cloudlog -from selfdrive.loggerd.config import ROOT +import requests -from common import android -from common.params import Params +from cereal import log +from common.hardware import HARDWARE from common.api import Api -from common.xattr import getxattr, setxattr +from common.params import Params +from selfdrive.loggerd.xattr_cache import getxattr, setxattr +from selfdrive.loggerd.config import ROOT +from selfdrive.swaglog import cloudlog +NetworkType = log.ThermalData.NetworkType UPLOAD_ATTR_NAME = 'user.upload' UPLOAD_ATTR_VALUE = b'1' fake_upload = os.getenv("FAKEUPLOAD") is not None + def raise_on_thread(t, exctype): '''Raises an exception in the threads with id tid''' for ctid, tobj in threading._active.items(): @@ -69,27 +72,15 @@ def clear_locks(root): cloudlog.exception("clear_locks failed") def is_on_wifi(): - # ConnectivityManager.getActiveNetworkInfo() - try: - # TODO: figure out why the android service call sometimes dies with SIGUSR2 (signal from MSGQ) - result = android.parse_service_call_string(android.service_call(["connectivity", "2"])) - if result is None: - return True - return 'WIFI' in result - except Exception: - cloudlog.exception("is_on_wifi failed") - return False + return HARDWARE.get_network_type() == NetworkType.wifi def is_on_hotspot(): try: result = subprocess.check_output(["ifconfig", "wlan0"], stderr=subprocess.STDOUT, encoding='utf8') result = re.findall(r"inet addr:((\d+\.){3}\d+)", result)[0][0] - - is_android = result.startswith('192.168.43.') - is_ios = result.startswith('172.20.10.') - is_entune = result.startswith('10.0.2.') - - return (is_android or is_ios or is_entune) + return (result.startswith('192.168.43.') or # android + result.startswith('172.20.10.') or # ios + result.startswith('10.0.2.')) # toyota entune except Exception: return False @@ -105,7 +96,7 @@ def __init__(self, dongle_id, root): self.last_exc = None self.immediate_priority = {"qlog.bz2": 0, "qcamera.ts": 1} - self.high_priority = {"rlog.bz2": 0, "fcamera.hevc": 1, "dcamera.hevc": 2} + self.high_priority = {"rlog.bz2": 0, "fcamera.hevc": 1, "dcamera.hevc": 2, "ecamera.hevc": 3} def get_upload_sort(self, name): if name in self.immediate_priority: @@ -137,11 +128,11 @@ def gen_upload_files(self): is_uploaded = True # deleter could have deleted if is_uploaded: continue - yield (name, key, fn) def next_file_to_upload(self, with_raw): upload_files = list(self.gen_upload_files()) + # try to upload qlog files first for name, key, fn in upload_files: if name in self.immediate_priority: @@ -246,17 +237,19 @@ def uploader_fn(exit_event): uploader = Uploader(dongle_id, ROOT) backoff = 0.1 - while True: + counter = 0 + should_upload = False + while not exit_event.is_set(): offroad = params.get("IsOffroad") == b'1' allow_raw_upload = (params.get("IsUploadRawEnabled") != b"0") and offroad - on_hotspot = is_on_hotspot() - on_wifi = is_on_wifi() - should_upload = on_wifi and not on_hotspot - - if exit_event.is_set(): - return + check_network = (counter % 12 == 0 if offroad else True) + if check_network: + on_hotspot = is_on_hotspot() + on_wifi = is_on_wifi() + should_upload = on_wifi and not on_hotspot d = uploader.next_file_to_upload(with_raw=allow_raw_upload and should_upload) + counter += 1 if d is None: # Nothing to upload time.sleep(60 if offroad else 5) continue @@ -277,5 +270,6 @@ def uploader_fn(exit_event): def main(): uploader_fn(threading.Event()) + if __name__ == "__main__": main() diff --git a/selfdrive/loggerd/xattr_cache.py b/selfdrive/loggerd/xattr_cache.py new file mode 100644 index 00000000000000..aa97f0c777084c --- /dev/null +++ b/selfdrive/loggerd/xattr_cache.py @@ -0,0 +1,13 @@ +from common.xattr import getxattr as getattr1 +from common.xattr import setxattr as setattr1 + +cached_attributes = {} +def getxattr(path, attr_name): + if (path, attr_name) not in cached_attributes: + response = getattr1(path, attr_name) + cached_attributes[(path, attr_name)] = response + return cached_attributes[(path, attr_name)] + +def setxattr(path, attr_name, attr_value): + cached_attributes.pop((path, attr_name), None) + return setattr1(path, attr_name, attr_value) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index e9ef36a2fc97ee..898297d64c555b 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -14,7 +14,7 @@ from common.basedir import BASEDIR, PARAMS -from common.android import ANDROID +from common.hardware import HARDWARE, ANDROID, PC WEBCAM = os.getenv("WEBCAM") is not None sys.path.append(os.path.join(BASEDIR, "pyextra")) os.environ['BASEDIR'] = BASEDIR @@ -156,7 +156,6 @@ def unblock_stdout(): from selfdrive.version import version, dirty from selfdrive.loggerd.config import ROOT from selfdrive.launcher import launcher -from common import android from common.apk import update_apks, pm_apply_packages, start_offroad ThermalStatus = cereal.log.ThermalData.ThermalStatus @@ -189,6 +188,7 @@ def unblock_stdout(): "updated": "selfdrive.updated", "dmonitoringmodeld": ("selfdrive/modeld", ["./dmonitoringmodeld"]), "modeld": ("selfdrive/modeld", ["./modeld"]), + "rtshield": "selfdrive.rtshield", } daemon_processes = { @@ -216,14 +216,18 @@ def get_running(): 'logmessaged', 'ui', 'uploader', + 'deleter', ] -if ANDROID: +if not PC: persistent_processes += [ 'logcatd', 'tombstoned', + ] + +if ANDROID: + persistent_processes += [ 'updated', - 'deleter', ] car_started_processes = [ @@ -231,14 +235,12 @@ def get_running(): 'plannerd', 'loggerd', 'radard', - 'dmonitoringd', 'calibrationd', 'paramsd', 'camerad', - 'modeld', 'proclogd', - 'ubloxd', 'locationd', + 'clocksd', ] driver_view_processes = [ @@ -249,17 +251,28 @@ def get_running(): if WEBCAM: car_started_processes += [ + 'dmonitoringd', 'dmonitoringmodeld', ] -if ANDROID: +if not PC: car_started_processes += [ + 'ubloxd', 'sensord', - 'clocksd', - 'gpsd', + 'dmonitoringd', 'dmonitoringmodeld', ] +if ANDROID: + car_started_processes += [ + 'gpsd', + 'rtshield', + ] + +# starting dmonitoringmodeld when modeld is initializing can sometimes \ +# result in a weird snpe state where dmon constantly uses more cpu than normal. +car_started_processes += ['modeld'] + def register_managed_process(name, desc, car_started=False): global managed_processes, car_started_processes, persistent_processes print("registering %s" % name) @@ -365,6 +378,7 @@ def kill_managed_process(name): join_process(running[name], 15) if running[name].exitcode is None: cloudlog.critical("unkillable process %s failed to die!" % name) + # TODO: Use method from HARDWARE if ANDROID: cloudlog.critical("FORCE REBOOTING PHONE!") os.system("date >> /sdcard/unkillable_reboot") @@ -536,7 +550,7 @@ def uninstall(): with open('/cache/recovery/command', 'w') as f: f.write('--wipe_data\n') # IPowerManager.reboot(confirm=false, reason="recovery", wait=true) - android.reboot(reason="recovery") + HARDWARE.reboot(reason="recovery") def main(): os.environ['PARAMS_PATH'] = PARAMS @@ -561,11 +575,6 @@ def main(): ("HasCompletedSetup", "0"), ("IsUploadRawEnabled", "1"), ("IsLdwEnabled", "1"), - ("IsGeofenceEnabled", "-1"), - ("SpeedLimitOffset", "0"), - ("LongitudinalControl", "0"), - ("LimitSetSpeed", "0"), - ("LimitSetSpeedNeural", "0"), ("LastUpdateTime", datetime.datetime.utcnow().isoformat().encode('utf8')), ("OpenpilotEnabledToggle", "1"), ("LaneChangeEnabled", "1"), @@ -616,8 +625,7 @@ def main(): cloudlog.exception("Manager failed to start") # Show last 3 lines of traceback - error = traceback.format_exc(3) - + error = traceback.format_exc(-3) error = "Manager failed to start\n \n" + error with TextWindow(error) as t: t.wait_for_exit() diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 6f9f6608e24fe4..18f279bf785e01 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -1,7 +1,7 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc') lenv = env.Clone() -libs = [cereal, messaging, common, 'OpenCL', 'SNPE', 'capnp', 'zmq', 'kj', 'yuv', gpucommon, visionipc] +libs = [cereal, messaging, common, 'OpenCL', 'SNPE', 'symphony-cpu', 'capnp', 'zmq', 'kj', 'yuv', gpucommon, visionipc] TEST_THNEED = False @@ -19,9 +19,9 @@ if arch == "aarch64": lenv['CFLAGS'].append("-DUSE_THNEED") lenv['CXXFLAGS'].append("-DUSE_THNEED") elif arch == "larch64": - libs += ['gsl', 'CB', 'symphony-cpu', 'pthread'] + libs += ['gsl', 'CB', 'pthread'] else: - libs += ['symphony-cpu', 'pthread'] + libs += ['pthread'] # for tensorflow support common_src += ['runners/tfmodel.cc'] diff --git a/selfdrive/modeld/dmonitoringmodeld b/selfdrive/modeld/dmonitoringmodeld index 51b520d74333e0..e68c13103dc556 100755 --- a/selfdrive/modeld/dmonitoringmodeld +++ b/selfdrive/modeld/dmonitoringmodeld @@ -1,5 +1,16 @@ #!/bin/sh -export LD_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/aarch64/:$HOME/openpilot/phonelibs/snpe/larch64:$HOME/openpilot/phonelibs/snpe/x86_64-linux-clang:$LD_LIBRARY_PATH" -export ADSP_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/aarch64/" -exec ./_dmonitoringmodeld +if [ -d /system ]; then + if [ -f /TICI ]; then # QCOM2 + export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/phonelibs/snpe/larch64:$LD_LIBRARY_PATH" + export ADSP_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/larch64/" + else # QCOM + export LD_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/aarch64/:$LD_LIBRARY_PATH" + export ADSP_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/aarch64/" + fi +else + # PC + export LD_LIBRARY_PATH="$HOME/openpilot/phonelibs/snpe/x86_64-linux-clang:/openpilot/phonelibs/snpe/x86_64:$HOME/openpilot/phonelibs/snpe/x86_64:$LD_LIBRARY_PATH" +fi + +exec ./_dmonitoringmodeld diff --git a/selfdrive/modeld/dmonitoringmodeld.cc b/selfdrive/modeld/dmonitoringmodeld.cc index 28776f94ee95ad..4eeb292ef584a9 100644 --- a/selfdrive/modeld/dmonitoringmodeld.cc +++ b/selfdrive/modeld/dmonitoringmodeld.cc @@ -25,11 +25,13 @@ int main(int argc, char **argv) { int err; set_realtime_priority(51); +#ifdef QCOM2 + set_core_affinity(5); +#endif + signal(SIGINT, (sighandler_t)set_do_exit); signal(SIGTERM, (sighandler_t)set_do_exit); - // messaging - SubMaster sm({"dMonitoringState"}); PubMaster pm({"driverState"}); // init the models @@ -49,7 +51,6 @@ int main(int argc, char **argv) { LOGW("connected with buffer size: %d", buf_info.buf_len); double last = 0; - int chk_counter = 0; while (!do_exit) { VIPCBuf *buf; VIPCBufExtra extra; @@ -58,23 +59,9 @@ int main(int argc, char **argv) { printf("visionstream get failed\n"); break; } - //printf("frame_id: %d %dx%d\n", extra.frame_id, buf_info.width, buf_info.height); - if (!dmonitoringmodel.is_rhd_checked) { - if (chk_counter >= RHD_CHECK_INTERVAL) { - if (sm.update(0) > 0) { - auto state = sm["dMonitoringState"].getDMonitoringState(); - dmonitoringmodel.is_rhd = state.getIsRHD(); - dmonitoringmodel.is_rhd_checked = state.getRhdChecked(); - } - chk_counter = 0; - } - chk_counter += 1; - } double t1 = millis_since_boot(); - DMonitoringResult res = dmonitoring_eval_frame(&dmonitoringmodel, buf->addr, buf_info.width, buf_info.height); - double t2 = millis_since_boot(); // send dm packet @@ -82,6 +69,11 @@ int main(int argc, char **argv) { LOGD("dmonitoring process: %.2fms, from last %.2fms", t2-t1, t1-last); last = t1; +#ifdef QCOM2 + // this makes it run at about 2.7Hz on tici CPU to deal with modeld lags + // TODO: DSP needs to be freed (again) + usleep(250000); +#endif } visionstream_destroy(&stream); } diff --git a/selfdrive/modeld/modeld b/selfdrive/modeld/modeld index 5369034dfeeede..66868595723991 100755 --- a/selfdrive/modeld/modeld +++ b/selfdrive/modeld/modeld @@ -1,4 +1,12 @@ #!/bin/sh -export LD_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/aarch64/:$HOME/openpilot/phonelibs/snpe/larch64:$HOME/openpilot/phonelibs/snpe/x86_64-linux-clang:$LD_LIBRARY_PATH" +if [ -d /system ]; then + if [ -f /TICI ]; then # QCOM2 + export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/phonelibs/snpe/larch64:$LD_LIBRARY_PATH" + else # QCOM + export LD_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/aarch64/:$LD_LIBRARY_PATH" + fi +else + # PC + export LD_LIBRARY_PATH="$HOME/openpilot/phonelibs/snpe/x86_64-linux-clang:/openpilot/phonelibs/snpe/x86_64:$HOME/openpilot/phonelibs/snpe/x86_64:$LD_LIBRARY_PATH" +fi exec ./_modeld - diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 33dafc86cf0304..0f1c22c3424b95 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -6,6 +6,7 @@ #include "common/visionbuf.h" #include "common/visionipc.h" #include "common/swaglog.h" +#include "common/clutil.h" #include "models/driving.h" #include "messaging.hpp" @@ -36,11 +37,26 @@ void* live_thread(void *arg) { -1.09890110e-03, 0.00000000e+00, 2.81318681e-01, -1.84808520e-20, 9.00738606e-04,-4.28751576e-02; +#ifndef QCOM2 Eigen::Matrix eon_intrinsics; eon_intrinsics << 910.0, 0.0, 582.0, 0.0, 910.0, 437.0, 0.0, 0.0, 1.0; +#else + Eigen::Matrix eon_intrinsics; + eon_intrinsics << + 2648.0, 0.0, 1928.0/2, + 0.0, 2648.0, 1208.0/2, + 0.0, 0.0, 1.0; +#endif + + // debayering does a 2x downscale + mat3 yuv_transform = transform_scale_buffer((mat3){{ + 1.0, 0.0, 0.0, + 0.0, 1.0, 0.0, + 0.0, 0.0, 1.0, + }}, 0.5); while (!do_exit) { if (sm.update(10) > 0){ @@ -58,12 +74,13 @@ void* live_thread(void *arg) { camera_frame_from_ground.col(2) = camera_frame_from_road_frame.col(3); auto warp_matrix = camera_frame_from_ground * ground_from_medmodel_frame; - - pthread_mutex_lock(&transform_lock); + mat3 transform = {}; for (int i=0; i<3*3; i++) { - cur_transform.v[i] = warp_matrix(i / 3, i % 3); + transform.v[i] = warp_matrix(i / 3, i % 3); } - + mat3 model_transform = matmul3(yuv_transform, transform); + pthread_mutex_lock(&transform_lock); + cur_transform = model_transform; run_model = true; pthread_mutex_unlock(&transform_lock); } @@ -75,9 +92,18 @@ int main(int argc, char **argv) { int err; set_realtime_priority(51); +#ifdef QCOM + set_core_affinity(2); +#elif QCOM2 + // CPU usage is much lower when pinned to a single big core + set_core_affinity(4); +#endif + signal(SIGINT, (sighandler_t)set_do_exit); signal(SIGTERM, (sighandler_t)set_do_exit); + pthread_mutex_init(&transform_lock, NULL); + // start calibration thread pthread_t live_thread_handle; err = pthread_create(&live_thread_handle, NULL, live_thread, NULL); @@ -87,78 +113,25 @@ int main(int argc, char **argv) { PubMaster pm({"model", "cameraOdometry"}); SubMaster sm({"pathPlan", "frame"}); -#ifdef QCOM +#if defined(QCOM) || defined(QCOM2) cl_device_type device_type = CL_DEVICE_TYPE_DEFAULT; #else cl_device_type device_type = CL_DEVICE_TYPE_CPU; #endif // cl init - cl_device_id device_id; - cl_context context; - cl_command_queue q; - { - cl_uint num_platforms; - err = clGetPlatformIDs(0, NULL, &num_platforms); - assert(err == 0); - - cl_platform_id * platform_ids = new cl_platform_id[num_platforms]; - err = clGetPlatformIDs(num_platforms, platform_ids, NULL); - assert(err == 0); - - LOGD("got %d opencl platform(s)", num_platforms); - - char cBuffer[1024]; - bool opencl_platform_found = false; - - for (size_t i = 0; i < num_platforms; i++){ - err = clGetPlatformInfo(platform_ids[i], CL_PLATFORM_NAME, sizeof(cBuffer), &cBuffer, NULL); - assert(err == 0); - LOGD("platform[%zu] CL_PLATFORM_NAME: %s", i, cBuffer); - - cl_uint num_devices; - err = clGetDeviceIDs(platform_ids[i], device_type, 0, NULL, &num_devices); - if (err != 0|| !num_devices){ - continue; - } - - // Get first device - err = clGetDeviceIDs(platform_ids[i], device_type, 1, &device_id, NULL); - assert(err == 0); - - context = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); - assert(err == 0); - - q = clCreateCommandQueue(context, device_id, 0, &err); - assert(err == 0); - - opencl_platform_found = true; - break; - } - - delete[] platform_ids; - - if (!opencl_platform_found){ - LOGE("No valid openCL platform found"); - assert(opencl_platform_found); - } - + cl_device_id device_id = cl_get_device_id(device_type); + cl_context context = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); + assert(err == 0); - LOGD("opencl init complete"); - } + cl_command_queue q = clCreateCommandQueue(context, device_id, 0, &err); + assert(err == 0); // init the models ModelState model; model_init(&model, device_id, context, true); LOGW("models loaded, modeld starting"); - // debayering does a 2x downscale - mat3 yuv_transform = transform_scale_buffer((mat3){{ - 1.0, 0.0, 0.0, - 0.0, 1.0, 0.0, - 0.0, 0.0, 1.0, - }}, 0.5); - // loop VisionStream stream; while (!do_exit) { @@ -194,7 +167,7 @@ int main(int argc, char **argv) { } pthread_mutex_lock(&transform_lock); - mat3 transform = cur_transform; + mat3 model_transform = cur_transform; const bool run_model_this_iter = run_model; pthread_mutex_unlock(&transform_lock); @@ -211,8 +184,6 @@ int main(int argc, char **argv) { vec_desire[desire] = 1.0; } - mat3 model_transform = matmul3(yuv_transform, transform); - mt1 = millis_since_boot(); // TODO: don't make copies! @@ -249,5 +220,6 @@ int main(int argc, char **argv) { clReleaseCommandQueue(q); clReleaseContext(context); + pthread_mutex_destroy(&transform_lock); return 0; } diff --git a/selfdrive/modeld/models/commonmodel.c b/selfdrive/modeld/models/commonmodel.c index eebf4761afa33d..0bdc61bbe32e47 100644 --- a/selfdrive/modeld/models/commonmodel.c +++ b/selfdrive/modeld/models/commonmodel.c @@ -7,25 +7,23 @@ void frame_init(ModelFrame* frame, int width, int height, cl_device_id device_id, cl_context context) { int err; - frame->device_id = device_id; - frame->context = context; transform_init(&frame->transform, context, device_id); frame->transformed_width = width; frame->transformed_height = height; - frame->transformed_y_cl = clCreateBuffer(frame->context, CL_MEM_READ_WRITE, + frame->transformed_y_cl = clCreateBuffer(context, CL_MEM_READ_WRITE, (size_t)frame->transformed_width*frame->transformed_height, NULL, &err); assert(err == 0); - frame->transformed_u_cl = clCreateBuffer(frame->context, CL_MEM_READ_WRITE, + frame->transformed_u_cl = clCreateBuffer(context, CL_MEM_READ_WRITE, (size_t)(frame->transformed_width/2)*(frame->transformed_height/2), NULL, &err); assert(err == 0); - frame->transformed_v_cl = clCreateBuffer(frame->context, CL_MEM_READ_WRITE, + frame->transformed_v_cl = clCreateBuffer(context, CL_MEM_READ_WRITE, (size_t)(frame->transformed_width/2)*(frame->transformed_height/2), NULL, &err); assert(err == 0); frame->net_input_size = ((width*height*3)/2)*sizeof(float); - frame->net_input = clCreateBuffer(frame->context, CL_MEM_READ_WRITE, + frame->net_input = clCreateBuffer(context, CL_MEM_READ_WRITE, frame->net_input_size, (void*)NULL, &err); assert(err == 0); diff --git a/selfdrive/modeld/models/commonmodel.h b/selfdrive/modeld/models/commonmodel.h index bb52366481c763..7aed3d7998ee01 100644 --- a/selfdrive/modeld/models/commonmodel.h +++ b/selfdrive/modeld/models/commonmodel.h @@ -20,10 +20,6 @@ float softplus(float input); float sigmoid(float input); typedef struct ModelFrame { - cl_device_id device_id; - cl_context context; - - // input Transform transform; int transformed_width, transformed_height; cl_mem transformed_y_cl, transformed_u_cl, transformed_v_cl; diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index 4f4203a38a1811..14f45dd904a2ad 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -2,12 +2,13 @@ #include "dmonitoring.h" #include "common/mat.h" #include "common/timing.h" +#include "common/params.h" #include #define MODEL_WIDTH 320 #define MODEL_HEIGHT 640 -#define FULL_W 852 +#define FULL_W 852 // should get these numbers from camerad #if defined(QCOM) || defined(QCOM2) #define input_lambda(x) (x - 128.f) * 0.0078125f @@ -21,9 +22,13 @@ void dmonitoring_init(DMonitoringModelState* s) { #else const char* model_path = "../../models/dmonitoring_model.dlc"; #endif - s->m = new DefaultRunModel(model_path, (float*)&s->output, OUTPUT_SIZE, USE_DSP_RUNTIME); - s->is_rhd = false; - s->is_rhd_checked = false; +#ifdef QCOM2 + int runtime = USE_CPU_RUNTIME; +#else + int runtime = USE_DSP_RUNTIME; +#endif + s->m = new DefaultRunModel(model_path, (float*)&s->output, OUTPUT_SIZE, runtime); + s->is_rhd = read_db_bool("IsRHD"); } template @@ -35,14 +40,30 @@ static inline T *get_buffer(std::vector &buf, const size_t size) { } DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height) { - uint8_t *raw_buf = (uint8_t*) stream_buf; uint8_t *raw_y_buf = raw_buf; uint8_t *raw_u_buf = raw_y_buf + (width * height); uint8_t *raw_v_buf = raw_u_buf + ((width/2) * (height/2)); - int cropped_width = height/2; - int cropped_height = height; +#ifndef QCOM2 + const int cropped_width = height/2; + const int cropped_height = height; + const int global_x_offset = 0; + const int global_y_offset = 0; + const int crop_x_offset = width - cropped_width; + const int crop_y_offset = 0; +#else + const int full_width_tici = 1928; + const int full_height_tici = 1208; + const int adapt_width_tici = 808; + + const int cropped_height = adapt_width_tici / 1.33; + const int cropped_width = cropped_height / 2; + const int global_x_offset = full_width_tici / 2 - adapt_width_tici / 2; + const int global_y_offset = full_height_tici / 2 - cropped_height / 2; + const int crop_x_offset = adapt_width_tici - cropped_width; + const int crop_y_offset = 0; +#endif int resized_width = MODEL_WIDTH; int resized_height = MODEL_HEIGHT; @@ -52,22 +73,21 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ uint8_t *cropped_v_buf = cropped_u_buf + ((cropped_width/2) * (cropped_height/2)); if (!s->is_rhd) { - for (int r = 0; r < height/2; r++) { - memcpy(cropped_y_buf + 2*r*cropped_width, raw_y_buf + 2*r*width + (width - cropped_width), cropped_width); - memcpy(cropped_y_buf + (2*r+1)*cropped_width, raw_y_buf + (2*r+1)*width + (width - cropped_width), cropped_width); - memcpy(cropped_u_buf + r*cropped_width/2, raw_u_buf + r*width/2 + ((width/2) - (cropped_width/2)), cropped_width/2); - memcpy(cropped_v_buf + r*cropped_width/2, raw_v_buf + r*width/2 + ((width/2) - (cropped_width/2)), cropped_width/2); + for (int r = 0; r < cropped_height/2; r++) { + memcpy(cropped_y_buf + 2*r*cropped_width, raw_y_buf + (2*r + global_y_offset + crop_y_offset)*width + global_x_offset + crop_x_offset, cropped_width); + memcpy(cropped_y_buf + (2*r+1)*cropped_width, raw_y_buf + (2*r + global_y_offset + crop_y_offset + 1)*width + global_x_offset + crop_x_offset, cropped_width); + memcpy(cropped_u_buf + r*cropped_width/2, raw_u_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + (global_x_offset + crop_x_offset)/2, cropped_width/2); + memcpy(cropped_v_buf + r*cropped_width/2, raw_v_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + (global_x_offset + crop_x_offset)/2, cropped_width/2); } } else { - // not tested uint8_t *premirror_cropped_y_buf = get_buffer(s->premirror_cropped_buf, cropped_width*cropped_height*3/2); uint8_t *premirror_cropped_u_buf = premirror_cropped_y_buf + (cropped_width * cropped_height); uint8_t *premirror_cropped_v_buf = premirror_cropped_u_buf + ((cropped_width/2) * (cropped_height/2)); - for (int r = 0; r < height/2; r++) { - memcpy(premirror_cropped_y_buf + 2*r*cropped_width, raw_y_buf + 2*r*width, cropped_width); - memcpy(premirror_cropped_y_buf + (2*r+1)*cropped_width, raw_y_buf + (2*r+1)*width, cropped_width); - memcpy(premirror_cropped_u_buf + r*cropped_width/2, raw_u_buf + r*width/2, cropped_width/2); - memcpy(premirror_cropped_v_buf + r*cropped_width/2, raw_v_buf + r*width/2, cropped_width/2); + for (int r = 0; r < cropped_height/2; r++) { + memcpy(premirror_cropped_y_buf + (2*r)*cropped_width, raw_y_buf + (2*r + global_y_offset + crop_y_offset)*width + global_x_offset, cropped_width); + memcpy(premirror_cropped_y_buf + (2*r+1)*cropped_width, raw_y_buf + (2*r + global_y_offset + crop_y_offset + 1)*width + global_x_offset, cropped_width); + memcpy(premirror_cropped_u_buf + r*cropped_width/2, raw_u_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + global_x_offset/2, cropped_width/2); + memcpy(premirror_cropped_v_buf + r*cropped_width/2, raw_v_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + global_x_offset/2, cropped_width/2); } libyuv::I420Mirror(premirror_cropped_y_buf, cropped_width, premirror_cropped_u_buf, cropped_width/2, @@ -103,9 +123,9 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ // Y_ul net_input_buf[(c*MODEL_HEIGHT/2) + r] = input_lambda(resized_buf[(2*r*resized_width) + (2*c)]); // Y_ur - net_input_buf[(c*MODEL_HEIGHT/2) + r + ((MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = input_lambda(resized_buf[(2*r*resized_width) + (2*c+1)]); + net_input_buf[(c*MODEL_HEIGHT/2) + r + (2*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = input_lambda(resized_buf[(2*r*resized_width) + (2*c+1)]); // Y_dl - net_input_buf[(c*MODEL_HEIGHT/2) + r + (2*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = input_lambda(resized_buf[(2*r*resized_width+1) + (2*c)]); + net_input_buf[(c*MODEL_HEIGHT/2) + r + ((MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = input_lambda(resized_buf[(2*r*resized_width+1) + (2*c)]); // Y_dr net_input_buf[(c*MODEL_HEIGHT/2) + r + (3*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = input_lambda(resized_buf[(2*r*resized_width+1) + (2*c+1)]); // U @@ -147,11 +167,8 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult &res){ // make msg - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - - auto framed = event.initDriverState(); + MessageBuilder msg; + auto framed = msg.initEvent().initDriverState(); framed.setFrameId(frame_id); kj::ArrayPtr face_orientation(&res.face_orientation[0], ARRAYSIZE(res.face_orientation)); diff --git a/selfdrive/modeld/models/dmonitoring.h b/selfdrive/modeld/models/dmonitoring.h index 439b9c0051f688..b1b6819d57f7e4 100644 --- a/selfdrive/modeld/models/dmonitoring.h +++ b/selfdrive/modeld/models/dmonitoring.h @@ -10,7 +10,6 @@ extern "C" { #endif #define OUTPUT_SIZE 34 -#define RHD_CHECK_INTERVAL 10 typedef struct DMonitoringResult { float face_orientation[3]; @@ -28,7 +27,6 @@ typedef struct DMonitoringResult { typedef struct DMonitoringModelState { RunModel *m; bool is_rhd; - bool is_rhd_checked; float output[OUTPUT_SIZE]; std::vector resized_buf; std::vector cropped_buf; diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index f58e7b1964de4d..14c66161657794 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -54,14 +54,11 @@ void model_init(ModelState* s, cl_device_id device_id, cl_context context, int t s->traffic_convention = std::make_unique(TRAFFIC_CONVENTION_LEN); s->m->addTrafficConvention(s->traffic_convention.get(), TRAFFIC_CONVENTION_LEN); - std::vector result = read_db_bytes("IsRHD"); - if (result.size() > 0) { - bool is_rhd = result[0] == '1'; - if (is_rhd) { - s->traffic_convention[1] = 1.0; - } else { - s->traffic_convention[0] = 1.0; - } + bool is_rhd = read_db_bool("IsRHD"); + if (is_rhd) { + s->traffic_convention[1] = 1.0; + } else { + s->traffic_convention[0] = 1.0; } #endif @@ -162,8 +159,8 @@ void fill_path(cereal::ModelData::PathData::Builder path, const float * data, bo float prob; float valid_len; - // clamp to 5 and 192 - valid_len = fmin(192, fmax(5, data[MODEL_PATH_DISTANCE*2])); + // clamp to 5 and MODEL_PATH_DISTANCE + valid_len = fmin(MODEL_PATH_DISTANCE, fmax(5, data[MODEL_PATH_DISTANCE*2])); for (int i=0; i(); - event.setLogMonoTime(nanos_since_boot()); - uint32_t frame_age = (frame_id > vipc_frame_id) ? (frame_id - vipc_frame_id) : 0; - auto framed = event.initModel(); + MessageBuilder msg; + auto framed = msg.initEvent(frame_drop < MAX_FRAME_DROP).initModel(); framed.setFrameId(vipc_frame_id); framed.setFrameAge(frame_age); framed.setFrameDropPerc(frame_drop * 100); framed.setTimestampEof(timestamp_eof); - auto lpath = framed.initPath(); - fill_path(lpath, net_outputs.path, false, 0); - auto left_lane = framed.initLeftLane(); - fill_path(left_lane, net_outputs.left_lane, true, 1.8); - auto right_lane = framed.initRightLane(); - fill_path(right_lane, net_outputs.right_lane, true, -1.8); - auto longi = framed.initLongitudinal(); - fill_longi(longi, net_outputs.long_x, net_outputs.long_v, net_outputs.long_a); - + fill_path(framed.initPath(), net_outputs.path, false, 0); + fill_path(framed.initLeftLane(), net_outputs.left_lane, true, 1.8); + fill_path(framed.initRightLane(), net_outputs.right_lane, true, -1.8); + fill_longi(framed.initLongitudinal(), net_outputs.long_x, net_outputs.long_v, net_outputs.long_a); // Find the distribution that corresponds to the current lead int mdn_max_idx = 0; @@ -268,8 +256,7 @@ void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, mdn_max_idx = i; } } - auto lead = framed.initLead(); - fill_lead(lead, net_outputs.lead, mdn_max_idx, t_offset); + fill_lead(framed.initLead(), net_outputs.lead, mdn_max_idx, t_offset); // Find the distribution that corresponds to the lead in 2s mdn_max_idx = 0; t_offset = 1; @@ -278,23 +265,14 @@ void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, mdn_max_idx = i; } } - auto lead_future = framed.initLeadFuture(); - fill_lead(lead_future, net_outputs.lead, mdn_max_idx, t_offset); - - - auto meta = framed.initMeta(); - fill_meta(meta, net_outputs.meta); - event.setValid(frame_drop < MAX_FRAME_DROP); + fill_lead(framed.initLeadFuture(), net_outputs.lead, mdn_max_idx, t_offset); + fill_meta(framed.initMeta(), net_outputs.meta); pm.send("model", msg); } void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, uint32_t vipc_dropped_frames, float frame_drop, const ModelDataRaw &net_outputs, uint64_t timestamp_eof) { - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - float trans_arr[3]; float trans_std_arr[3]; float rot_arr[3]; @@ -308,7 +286,8 @@ void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, rot_std_arr[i] = M_PI * (softplus(net_outputs.pose[9 + i]) + 1e-6) / 180.0; } - auto posenetd = event.initCameraOdometry(); + MessageBuilder msg; + auto posenetd = msg.initEvent(vipc_dropped_frames < 1).initCameraOdometry(); kj::ArrayPtr trans_vs(&trans_arr[0], 3); posenetd.setTrans(trans_vs); kj::ArrayPtr rot_vs(&rot_arr[0], 3); @@ -318,11 +297,8 @@ void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, kj::ArrayPtr rot_std_vs(&rot_std_arr[0], 3); posenetd.setRotStd(rot_std_vs); - posenetd.setTimestampEof(timestamp_eof); posenetd.setFrameId(vipc_frame_id); - event.setValid(vipc_dropped_frames < 1); - pm.send("cameraOdometry", msg); } diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index 2bf4d61500cbef..52e7401a3b18ec 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -9,6 +9,7 @@ #include "common/mat.h" #include "common/util.h" +#include "common/modeldata.h" #include "commonmodel.h" #include "runners/run.h" @@ -22,13 +23,8 @@ #define MODEL_FRAME_SIZE MODEL_WIDTH * MODEL_HEIGHT * 3 / 2 #define MODEL_NAME "supercombo_dlc" -#define MODEL_PATH_DISTANCE 192 -#define POLYFIT_DEGREE 4 -#define SPEED_PERCENTILES 10 #define DESIRE_LEN 8 #define TRAFFIC_CONVENTION_LEN 2 -#define DESIRE_PRED_SIZE 32 -#define OTHER_META_SIZE 4 #define LEAD_MDN_N 5 // probs for 5 groups #define MDN_VALS 4 // output xyva for each lead group #define SELECTION 3 //output 3 group (lead now, in 2s and 6s) diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index 5a92d94bf4f211..38da13453a2473 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -13,7 +13,7 @@ void PrintErrorStringAndExit() { SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime) { output = loutput; output_size = loutput_size; -#ifdef QCOM +#if defined(QCOM) || defined(QCOM2) if (runtime==USE_GPU_RUNTIME) { Runtime = zdl::DlSystem::Runtime_t::GPU; } else if (runtime==USE_DSP_RUNTIME) { @@ -35,7 +35,7 @@ SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int // create model runner zdl::SNPE::SNPEBuilder snpeBuilder(container.get()); while (!snpe) { -#ifdef QCOM +#if defined(QCOM) || defined(QCOM2) snpe = snpeBuilder.setOutputLayers({}) .setRuntimeProcessor(Runtime) .setUseUserSuppliedBuffers(true) diff --git a/selfdrive/modeld/runners/snpemodel.h b/selfdrive/modeld/runners/snpemodel.h index f7f217cdc67820..90c26664f62bc0 100644 --- a/selfdrive/modeld/runners/snpemodel.h +++ b/selfdrive/modeld/runners/snpemodel.h @@ -38,7 +38,7 @@ class SNPEModel : public RunModel { Thneed *thneed = NULL; #endif -#ifdef QCOM +#if defined(QCOM) || defined(QCOM2) zdl::DlSystem::Runtime_t Runtime; #endif diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index 66a1f2d879ddc9..c8d6d158730d4b 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -1,31 +1,23 @@ #!/usr/bin/env python3 -import gc from cereal import car -from common.realtime import set_realtime_priority from common.params import Params import cereal.messaging as messaging from selfdrive.controls.lib.events import Events from selfdrive.monitoring.driver_monitor import DriverStatus, MAX_TERMINAL_ALERTS, MAX_TERMINAL_DURATION -from selfdrive.locationd.calibration_helpers import Calibration +from selfdrive.locationd.calibrationd import Calibration def dmonitoringd_thread(sm=None, pm=None): - gc.disable() - set_realtime_priority(53) - - # Pub/Sub Sockets if pm is None: pm = messaging.PubMaster(['dMonitoringState']) if sm is None: - sm = messaging.SubMaster(['driverState', 'liveCalibration', 'carState', 'model']) - - params = Params() + sm = messaging.SubMaster(['driverState', 'liveCalibration', 'carState', 'model'], poll=['driverState']) driver_status = DriverStatus() - is_rhd = params.get("IsRHD") - driver_status.is_rhd_region = is_rhd == b"1" - driver_status.is_rhd_region_checked = is_rhd is not None + driver_status.is_rhd_region = Params().get("IsRHD") == b"1" + + offroad = Params().get("IsOffroad") == b"1" sm['liveCalibration'].calStatus = Calibration.INVALID sm['liveCalibration'].rpyCalib = [0, 0, 0] @@ -39,12 +31,14 @@ def dmonitoringd_thread(sm=None, pm=None): v_cruise_last = 0 driver_engaged = False - offroad = params.get("IsOffroad") == b"1" # 10Hz <- dmonitoringmodeld while True: sm.update() + if not sm.updated['driverState']: + continue + # Get interaction if sm.updated['carState']: v_cruise = sm['carState'].cruiseState.speed @@ -56,43 +50,40 @@ def dmonitoringd_thread(sm=None, pm=None): driver_status.update(Events(), True, sm['carState'].cruiseState.enabled, sm['carState'].standstill) v_cruise_last = v_cruise - # Get model meta if sm.updated['model']: driver_status.set_policy(sm['model']) # Get data from dmonitoringmodeld - if sm.updated['driverState']: - events = Events() - driver_status.get_pose(sm['driverState'], sm['liveCalibration'].rpyCalib, sm['carState'].vEgo, sm['carState'].cruiseState.enabled) - - # Block engaging after max number of distrations - if driver_status.terminal_alert_cnt >= MAX_TERMINAL_ALERTS or driver_status.terminal_time >= MAX_TERMINAL_DURATION: - events.add(car.CarEvent.EventName.tooDistracted) - - # Update events from driver state - driver_status.update(events, driver_engaged, sm['carState'].cruiseState.enabled, sm['carState'].standstill) - - # build dMonitoringState packet - dat = messaging.new_message('dMonitoringState') - dat.dMonitoringState = { - "events": events.to_msg(), - "faceDetected": driver_status.face_detected, - "isDistracted": driver_status.driver_distracted, - "awarenessStatus": driver_status.awareness, - "isRHD": driver_status.is_rhd_region, - "rhdChecked": driver_status.is_rhd_region_checked, - "posePitchOffset": driver_status.pose.pitch_offseter.filtered_stat.mean(), - "posePitchValidCount": driver_status.pose.pitch_offseter.filtered_stat.n, - "poseYawOffset": driver_status.pose.yaw_offseter.filtered_stat.mean(), - "poseYawValidCount": driver_status.pose.yaw_offseter.filtered_stat.n, - "stepChange": driver_status.step_change, - "awarenessActive": driver_status.awareness_active, - "awarenessPassive": driver_status.awareness_passive, - "isLowStd": driver_status.pose.low_std, - "hiStdCount": driver_status.hi_stds, - "isPreview": offroad, - } - pm.send('dMonitoringState', dat) + events = Events() + driver_status.get_pose(sm['driverState'], sm['liveCalibration'].rpyCalib, sm['carState'].vEgo, sm['carState'].cruiseState.enabled) + + # Block engaging after max number of distrations + if driver_status.terminal_alert_cnt >= MAX_TERMINAL_ALERTS or driver_status.terminal_time >= MAX_TERMINAL_DURATION: + events.add(car.CarEvent.EventName.tooDistracted) + + # Update events from driver state + driver_status.update(events, driver_engaged, sm['carState'].cruiseState.enabled, sm['carState'].standstill) + + # build dMonitoringState packet + dat = messaging.new_message('dMonitoringState') + dat.dMonitoringState = { + "events": events.to_msg(), + "faceDetected": driver_status.face_detected, + "isDistracted": driver_status.driver_distracted, + "awarenessStatus": driver_status.awareness, + "isRHD": driver_status.is_rhd_region, + "posePitchOffset": driver_status.pose.pitch_offseter.filtered_stat.mean(), + "posePitchValidCount": driver_status.pose.pitch_offseter.filtered_stat.n, + "poseYawOffset": driver_status.pose.yaw_offseter.filtered_stat.mean(), + "poseYawValidCount": driver_status.pose.yaw_offseter.filtered_stat.n, + "stepChange": driver_status.step_change, + "awarenessActive": driver_status.awareness_active, + "awarenessPassive": driver_status.awareness_passive, + "isLowStd": driver_status.pose.low_std, + "hiStdCount": driver_status.hi_stds, + "isPreview": offroad, + } + pm.send('dMonitoringState', dat) def main(sm=None, pm=None): dmonitoringd_thread(sm, pm) diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index 76487e24e3d165..1122e1b7aaaf00 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -15,8 +15,8 @@ # ****************************************************************************************** _AWARENESS_TIME = 70. # one minute limit without user touching steering wheels make the car enter a terminal status -_AWARENESS_PRE_TIME_TILL_TERMINAL = 15. # a first alert is issued 25s before expiration -_AWARENESS_PROMPT_TIME_TILL_TERMINAL = 6. # a second alert is issued 15s before start decelerating the car +_AWARENESS_PRE_TIME_TILL_TERMINAL = 15. # a first alert is issued 15s before expiration +_AWARENESS_PROMPT_TIME_TILL_TERMINAL = 6. # a second alert is issued 6s before start decelerating the car _DISTRACTED_TIME = 11. _DISTRACTED_PRE_TIME_TILL_TERMINAL = 8. _DISTRACTED_PROMPT_TIME_TILL_TERMINAL = 6. @@ -24,10 +24,10 @@ _FACE_THRESHOLD = 0.6 _EYE_THRESHOLD = 0.6 _SG_THRESHOLD = 0.5 -_BLINK_THRESHOLD = 0.5 # 0.225 +_BLINK_THRESHOLD = 0.5 _BLINK_THRESHOLD_SLACK = 0.65 _BLINK_THRESHOLD_STRICT = 0.5 -_PITCH_WEIGHT = 1.35 # 1.5 # pitch matters a lot more +_PITCH_WEIGHT = 1.35 # pitch matters a lot more _POSESTD_THRESHOLD = 0.14 _METRIC_THRESHOLD = 0.4 _METRIC_THRESHOLD_SLACK = 0.55 @@ -116,6 +116,7 @@ def __init__(self): self.step_change = 0. self.active_monitoring_mode = True self.hi_stds = 0 + self.hi_std_alert_enabled = True self.threshold_prompt = _DISTRACTED_PROMPT_TIME_TILL_TERMINAL / _DISTRACTED_TIME self.is_rhd_region = False @@ -212,7 +213,7 @@ def get_pose(self, driver_state, cal_rpy, car_speed, op_engaged): self._set_timers(self.face_detected and not is_model_uncertain) if self.face_detected and not self.pose.low_std: if not is_model_uncertain: - self.step_change *= max(0, (model_std_max-0.5)*(model_std_max-2)) + self.step_change *= min(1.0, max(0.6, 1.6*(model_std_max-0.5)*(model_std_max-2))) self.hi_stds += 1 elif self.face_detected and self.pose.low_std: self.hi_stds = 0 @@ -228,8 +229,9 @@ def update(self, events, driver_engaged, ctrl_active, standstill): driver_attentive = self.driver_distraction_filter.x < 0.37 awareness_prev = self.awareness - if self.face_detected and self.hi_stds * DT_DMON > _HI_STD_TIMEOUT: + if self.face_detected and self.hi_stds * DT_DMON > _HI_STD_TIMEOUT and self.hi_std_alert_enabled: events.add(EventName.driverMonitorLowAcc) + self.hi_std_alert_enabled = False # only showed once until orange prompt resets it if (driver_attentive and self.face_detected and self.pose.low_std and self.awareness > 0): # only restore awareness when paying attention and alert is not red @@ -255,6 +257,7 @@ def update(self, events, driver_engaged, ctrl_active, standstill): elif self.awareness <= self.threshold_prompt: # prompt orange alert alert = EventName.promptDriverDistracted if self.active_monitoring_mode else EventName.promptDriverUnresponsive + self.hi_std_alert_enabled = True elif self.awareness <= self.threshold_pre: # pre green alert alert = EventName.preDriverDistracted if self.active_monitoring_mode else EventName.preDriverUnresponsive diff --git a/selfdrive/pandad.py b/selfdrive/pandad.py index 64fde86686beec..a3ddaf4845b00a 100755 --- a/selfdrive/pandad.py +++ b/selfdrive/pandad.py @@ -3,8 +3,25 @@ import os import time +from common.hardware import TICI +from common.gpio import GPIO_HUB_RST_N, GPIO_STM_BOOT0, GPIO_STM_RST_N, gpio_init, gpio_set +from panda import BASEDIR, Panda, PandaDFU, build_st from selfdrive.swaglog import cloudlog -from panda import Panda, PandaDFU, BASEDIR, build_st + + +def set_panda_power(power=True): + if not TICI: + return + + gpio_init(GPIO_STM_RST_N, True) + gpio_init(GPIO_STM_BOOT0, True) + + gpio_set(GPIO_STM_RST_N, False) + gpio_set(GPIO_HUB_RST_N, True) + + time.sleep(0.1) + + gpio_set(GPIO_STM_RST_N, power) def get_firmware_fn(): @@ -88,10 +105,12 @@ def update_panda(): def main(): + set_panda_power() update_panda() os.chdir("boardd") os.execvp("./boardd", ["./boardd"]) + if __name__ == "__main__": main() diff --git a/selfdrive/proclogd/proclogd.cc b/selfdrive/proclogd/proclogd.cc index c8e5f65a506899..24b42c5bf4b8ba 100644 --- a/selfdrive/proclogd/proclogd.cc +++ b/selfdrive/proclogd/proclogd.cc @@ -38,11 +38,8 @@ int main() { while (1) { - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto procLog = event.initProcLog(); - + MessageBuilder msg; + auto procLog = msg.initEvent().initProcLog(); auto orphanage = msg.getOrphanage(); // stat diff --git a/selfdrive/registration.py b/selfdrive/registration.py index 6e1596f35a2cc1..de2231a45842f0 100644 --- a/selfdrive/registration.py +++ b/selfdrive/registration.py @@ -4,12 +4,13 @@ from datetime import datetime, timedelta from selfdrive.swaglog import cloudlog from selfdrive.version import version, terms_version, training_version, get_git_commit, get_git_branch, get_git_remote -from common.android import get_imei, get_serial, get_subscriber_info +from common.hardware import HARDWARE from common.api import api_get from common.params import Params from common.file_helpers import mkdirs_exists_ok from common.basedir import PERSIST + def register(): params = Params() params.put("Version", version) @@ -19,7 +20,7 @@ def register(): params.put("GitCommit", get_git_commit(default="")) params.put("GitBranch", get_git_branch(default="")) params.put("GitRemote", get_git_remote(default="")) - params.put("SubscriberInfo", get_subscriber_info()) + params.put("SubscriberInfo", HARDWARE.get_subscriber_info()) # create a key for auth # your private key is kept on your device persist partition and never sent to our servers @@ -50,7 +51,7 @@ def register(): try: cloudlog.info("getting pilotauth") resp = api_get("v2/pilotauth/", method='POST', timeout=15, - imei=get_imei(0), imei2=get_imei(1), serial=get_serial(), public_key=public_key, register_token=register_token) + imei=HARDWARE.get_imei(0), imei2=HARDWARE.get_imei(1), serial=HARDWARE.get_serial(), public_key=public_key, register_token=register_token) dongleauth = json.loads(resp.text) dongle_id = dongleauth["dongle_id"] diff --git a/selfdrive/rtshield.py b/selfdrive/rtshield.py new file mode 100644 index 00000000000000..e76022501b1520 --- /dev/null +++ b/selfdrive/rtshield.py @@ -0,0 +1,16 @@ +#!/usr/bin/env python3 +import time +from common.realtime import set_core_affinity, set_realtime_priority + + +# RT shield - ensure CPU 3 always remains available for RT processes +# runs as SCHED_FIFO with minimum priority to ensure kthreads don't +# get scheduled onto CPU 3, but it's always preemptible by realtime +# openpilot processes + +def main(): + set_core_affinity(3) + set_realtime_priority(1) + + while True: + time.sleep(0.000001) diff --git a/selfdrive/sensord/SConscript b/selfdrive/sensord/SConscript index b578ac9514354a..b5c8b78f999a14 100644 --- a/selfdrive/sensord/SConscript +++ b/selfdrive/sensord/SConscript @@ -1,5 +1,17 @@ -Import('env', 'common', 'cereal', 'messaging') -env.Program('_sensord', 'sensors.cc', LIBS=['hardware', common, cereal, messaging, 'capnp', 'zmq', 'kj']) -lenv = env.Clone() -lenv['LIBPATH'] += ['/system/vendor/lib64'] -lenv.Program('_gpsd', ['gpsd.cc'], LIBS=['hardware', common, 'diag', 'time_genoff', cereal, messaging, 'capnp', 'zmq', 'kj']) +Import('env', 'arch', 'common', 'cereal', 'messaging') +if arch == "aarch64": + env.Program('_sensord', 'sensors_qcom.cc', LIBS=['hardware', common, cereal, messaging, 'capnp', 'zmq', 'kj']) + lenv = env.Clone() + lenv['LIBPATH'] += ['/system/vendor/lib64'] + lenv.Program('_gpsd', ['gpsd.cc'], LIBS=['hardware', common, 'diag', 'time_genoff', cereal, messaging, 'capnp', 'zmq', 'kj']) +else: + sensors = [ + 'sensors/file_sensor.cc', + 'sensors/i2c_sensor.cc', + 'sensors/light_sensor.cc', + 'sensors/bmx055_accel.cc', + 'sensors/bmx055_gyro.cc', + 'sensors/bmx055_magn.cc', + 'sensors/bmx055_temp.cc', + ] + env.Program('_sensord', ['sensors_qcom2.cc'] + sensors, LIBS=[common, cereal, messaging, 'capnp', 'zmq', 'kj']) diff --git a/selfdrive/sensord/gpsd.cc b/selfdrive/sensord/gpsd.cc index 4bf71faf6196e0..1978a239c8d7aa 100644 --- a/selfdrive/sensord/gpsd.cc +++ b/selfdrive/sensord/gpsd.cc @@ -35,14 +35,10 @@ void set_do_exit(int sig) { void nmea_callback(GpsUtcTime timestamp, const char* nmea, int length) { - uint64_t log_time = nanos_since_boot(); uint64_t log_time_wall = nanos_since_epoch(); - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(log_time); - - auto nmeaData = event.initGpsNMEA(); + MessageBuilder msg; + auto nmeaData = msg.initEvent().initGpsNMEA(); nmeaData.setTimestamp(timestamp); nmeaData.setLocalWallTime(log_time_wall); nmeaData.setNmea(nmea); @@ -52,13 +48,9 @@ void nmea_callback(GpsUtcTime timestamp, const char* nmea, int length) { void location_callback(GpsLocation* location) { //printf("got location callback\n"); - uint64_t log_time = nanos_since_boot(); - - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(log_time); - auto locationData = event.initGpsLocation(); + MessageBuilder msg; + auto locationData = msg.initEvent().initGpsLocation(); locationData.setFlags(location->flags); locationData.setLatitude(location->latitude); locationData.setLongitude(location->longitude); diff --git a/selfdrive/sensord/sensors/bmx055_accel.cc b/selfdrive/sensord/sensors/bmx055_accel.cc new file mode 100644 index 00000000000000..5eea0bcdfa0933 --- /dev/null +++ b/selfdrive/sensord/sensors/bmx055_accel.cc @@ -0,0 +1,71 @@ +#include +#include "common/swaglog.h" +#include "common/timing.h" + +#include "bmx055_accel.hpp" + + +BMX055_Accel::BMX055_Accel(I2CBus *bus) : I2CSensor(bus) {} + +int BMX055_Accel::init(){ + int ret = 0; + uint8_t buffer[1]; + + ret = read_register(BMX055_ACCEL_I2C_REG_ID, buffer, 1); + if(ret < 0){ + LOGE("Reading chip ID failed: %d", ret); + goto fail; + } + + if(buffer[0] != BMX055_ACCEL_CHIP_ID){ + LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_ACCEL_CHIP_ID); + ret = -1; + goto fail; + } + + // High bandwidth + // ret = set_register(BMX055_ACCEL_I2C_REG_HBW, BMX055_ACCEL_HBW_ENABLE); + // if (ret < 0){ + // goto fail; + // } + + // Low bandwidth + ret = set_register(BMX055_ACCEL_I2C_REG_HBW, BMX055_ACCEL_HBW_DISABLE); + if (ret < 0){ + goto fail; + } + ret = set_register(BMX055_ACCEL_I2C_REG_BW, BMX055_ACCEL_BW_125HZ); + if (ret < 0){ + goto fail; + } + +fail: + return ret; +} + +void BMX055_Accel::get_event(cereal::SensorEventData::Builder &event){ + uint64_t start_time = nanos_since_boot(); + uint8_t buffer[6]; + int len = read_register(BMX055_ACCEL_I2C_REG_FIFO, buffer, sizeof(buffer)); + assert(len == 6); + + // 12 bit = +-2g + float scale = 9.81 * 2.0f / (1 << 11); + float x = -read_12_bit(buffer[0], buffer[1]) * scale; + float y = -read_12_bit(buffer[2], buffer[3]) * scale; + float z = read_12_bit(buffer[4], buffer[5]) * scale; + + event.setSource(cereal::SensorEventData::SensorSource::BMX055); + event.setVersion(1); + event.setSensor(SENSOR_ACCELEROMETER); + event.setType(SENSOR_TYPE_ACCELEROMETER); + event.setTimestamp(start_time); + + float xyz[] = {x, y, z}; + kj::ArrayPtr vs(&xyz[0], 3); + + auto svec = event.initAcceleration(); + svec.setV(vs); + svec.setStatus(true); + +} diff --git a/selfdrive/sensord/sensors/bmx055_accel.hpp b/selfdrive/sensord/sensors/bmx055_accel.hpp new file mode 100644 index 00000000000000..4e613af7c98506 --- /dev/null +++ b/selfdrive/sensord/sensors/bmx055_accel.hpp @@ -0,0 +1,36 @@ +#pragma once + +#include "sensors/i2c_sensor.hpp" + +// Address of the chip on the bus +#define BMX055_ACCEL_I2C_ADDR 0x18 + +// Registers of the chip +#define BMX055_ACCEL_I2C_REG_ID 0x00 +#define BMX055_ACCEL_I2C_REG_TEMP 0x08 +#define BMX055_ACCEL_I2C_REG_BW 0x10 +#define BMX055_ACCEL_I2C_REG_HBW 0x13 +#define BMX055_ACCEL_I2C_REG_FIFO 0x3F + +// Constants +#define BMX055_ACCEL_CHIP_ID 0xFA + +#define BMX055_ACCEL_HBW_ENABLE 0b10000000 +#define BMX055_ACCEL_HBW_DISABLE 0b00000000 + +#define BMX055_ACCEL_BW_7_81HZ 0b01000 +#define BMX055_ACCEL_BW_15_63HZ 0b01001 +#define BMX055_ACCEL_BW_31_25HZ 0b01010 +#define BMX055_ACCEL_BW_62_5HZ 0b01011 +#define BMX055_ACCEL_BW_125HZ 0b01100 +#define BMX055_ACCEL_BW_250HZ 0b01101 +#define BMX055_ACCEL_BW_500HZ 0b01110 +#define BMX055_ACCEL_BW_1000HZ 0b01111 + +class BMX055_Accel : public I2CSensor { + uint8_t get_device_address() {return BMX055_ACCEL_I2C_ADDR;} +public: + BMX055_Accel(I2CBus *bus); + int init(); + void get_event(cereal::SensorEventData::Builder &event); +}; diff --git a/selfdrive/sensord/sensors/bmx055_gyro.cc b/selfdrive/sensord/sensors/bmx055_gyro.cc new file mode 100644 index 00000000000000..61e3d9e4054918 --- /dev/null +++ b/selfdrive/sensord/sensors/bmx055_gyro.cc @@ -0,0 +1,81 @@ +#include +#include +#include "common/swaglog.h" + +#include "bmx055_gyro.hpp" + +#define DEG2RAD(x) ((x) * M_PI / 180.0) + + +BMX055_Gyro::BMX055_Gyro(I2CBus *bus) : I2CSensor(bus) {} + +int BMX055_Gyro::init(){ + int ret = 0; + uint8_t buffer[1]; + + ret =read_register(BMX055_GYRO_I2C_REG_ID, buffer, 1); + if(ret < 0){ + LOGE("Reading chip ID failed: %d", ret); + goto fail; + } + + if(buffer[0] != BMX055_GYRO_CHIP_ID){ + LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_GYRO_CHIP_ID); + ret = -1; + goto fail; + } + + // High bandwidth + // ret = set_register(BMX055_GYRO_I2C_REG_HBW, BMX055_GYRO_HBW_ENABLE); + // if (ret < 0){ + // goto fail; + // } + + // Low bandwidth + ret = set_register(BMX055_GYRO_I2C_REG_HBW, BMX055_GYRO_HBW_DISABLE); + if (ret < 0){ + goto fail; + } + + // 116 Hz filter + ret = set_register(BMX055_GYRO_I2C_REG_BW, BMX055_GYRO_BW_116HZ); + if (ret < 0){ + goto fail; + } + + // +- 125 deg/s range + ret = set_register(BMX055_GYRO_I2C_REG_RANGE, BMX055_GYRO_RANGE_125); + if (ret < 0){ + goto fail; + } + +fail: + return ret; +} + +void BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event){ + uint64_t start_time = nanos_since_boot(); + uint8_t buffer[6]; + int len = read_register(BMX055_GYRO_I2C_REG_FIFO, buffer, sizeof(buffer)); + assert(len == 6); + + // 16 bit = +- 125 deg/s + float scale = 125.0f / (1 << 15); + float x = -DEG2RAD(read_16_bit(buffer[0], buffer[1]) * scale); + float y = -DEG2RAD(read_16_bit(buffer[2], buffer[3]) * scale); + float z = DEG2RAD(read_16_bit(buffer[4], buffer[5]) * scale); + + event.setSource(cereal::SensorEventData::SensorSource::BMX055); + event.setVersion(1); + event.setSensor(SENSOR_GYRO_UNCALIBRATED); + event.setType(SENSOR_TYPE_GYROSCOPE_UNCALIBRATED); + event.setTimestamp(start_time); + + float xyz[] = {x, y, z}; + kj::ArrayPtr vs(&xyz[0], 3); + + auto svec = event.initGyroUncalibrated(); + svec.setV(vs); + svec.setStatus(true); + +} diff --git a/selfdrive/sensord/sensors/bmx055_gyro.hpp b/selfdrive/sensord/sensors/bmx055_gyro.hpp new file mode 100644 index 00000000000000..407ee1608eebd7 --- /dev/null +++ b/selfdrive/sensord/sensors/bmx055_gyro.hpp @@ -0,0 +1,36 @@ +#pragma once + +#include "sensors/i2c_sensor.hpp" + +// Address of the chip on the bus +#define BMX055_GYRO_I2C_ADDR 0x68 + +// Registers of the chip +#define BMX055_GYRO_I2C_REG_ID 0x00 +#define BMX055_GYRO_I2C_REG_RANGE 0x0F +#define BMX055_GYRO_I2C_REG_BW 0x10 +#define BMX055_GYRO_I2C_REG_HBW 0x13 +#define BMX055_GYRO_I2C_REG_FIFO 0x3F + +// Constants +#define BMX055_GYRO_CHIP_ID 0x0F + +#define BMX055_GYRO_HBW_ENABLE 0b10000000 +#define BMX055_GYRO_HBW_DISABLE 0b00000000 + +#define BMX055_GYRO_RANGE_2000 0b000 +#define BMX055_GYRO_RANGE_1000 0b001 +#define BMX055_GYRO_RANGE_500 0b010 +#define BMX055_GYRO_RANGE_250 0b011 +#define BMX055_GYRO_RANGE_125 0b100 + +#define BMX055_GYRO_BW_116HZ 0b0010 + + +class BMX055_Gyro : public I2CSensor { + uint8_t get_device_address() {return BMX055_GYRO_I2C_ADDR;} +public: + BMX055_Gyro(I2CBus *bus); + int init(); + void get_event(cereal::SensorEventData::Builder &event); +}; diff --git a/selfdrive/sensord/sensors/bmx055_magn.cc b/selfdrive/sensord/sensors/bmx055_magn.cc new file mode 100644 index 00000000000000..1c23ceb6a65822 --- /dev/null +++ b/selfdrive/sensord/sensors/bmx055_magn.cc @@ -0,0 +1,109 @@ +#include +#include +#include + +#include "common/swaglog.h" + +#include "bmx055_magn.hpp" + +int16_t parse_xy(uint8_t lsb, uint8_t msb){ + // 13 bit + uint16_t combined = (uint16_t(msb) << 5) | uint16_t(lsb >> 3); + return int16_t(combined << 3) / (1 << 3); +} + +int16_t parse_z(uint8_t lsb, uint8_t msb){ + // 15 bit + uint16_t combined = (uint16_t(msb) << 7) | uint16_t(lsb >> 1); + return int16_t(combined << 1) / (1 << 1); +} + +uint16_t parse_rhall(uint8_t lsb, uint8_t msb){ + // 14 bit + return (uint16_t(msb) << 6) | uint16_t(lsb >> 2); +} + +BMX055_Magn::BMX055_Magn(I2CBus *bus) : I2CSensor(bus) {} + +int BMX055_Magn::init(){ + int ret; + uint8_t buffer[1]; + + // suspend -> sleep + ret = set_register(BMX055_MAGN_I2C_REG_PWR_0, 0x01); + if(ret < 0){ + LOGE("Enabling power failed: %d", ret); + goto fail; + } + usleep(5 * 1000); // wait until the chip is powered on + + // read chip ID + ret = read_register(BMX055_MAGN_I2C_REG_ID, buffer, 1); + if(ret < 0){ + LOGE("Reading chip ID failed: %d", ret); + goto fail; + } + + if(buffer[0] != BMX055_MAGN_CHIP_ID){ + LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_MAGN_CHIP_ID); + return -1; + } + + // TODO: perform self-test + + // 9 REPXY and 15 REPZ for 100 Hz + // 3 REPXY and 3 REPZ for > 300 Hz + ret = set_register(BMX055_MAGN_I2C_REG_REPXY, (3 - 1) / 2); + if (ret < 0){ + goto fail; + } + + ret = set_register(BMX055_MAGN_I2C_REG_REPZ, 3 - 1); + if (ret < 0){ + goto fail; + } + + return 0; + + fail: + return ret; +} + + +void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event){ + uint64_t start_time = nanos_since_boot(); + uint8_t buffer[8]; + + int len = read_register(BMX055_MAGN_I2C_REG_DATAX_LSB, buffer, sizeof(buffer)); + assert(len == sizeof(buffer)); + + bool ready = buffer[6] & 0x1; + if (ready){ + float x = parse_xy(buffer[0], buffer[1]); + float y = parse_xy(buffer[2], buffer[3]); + float z = parse_z(buffer[4], buffer[5]); + //uint16_t rhall = parse_rhall(buffer[5], buffer[6]); + + // TODO: convert to micro tesla: + // https://github.com/BoschSensortec/BMM150-Sensor-API/blob/master/bmm150.c#L1614 + + event.setSource(cereal::SensorEventData::SensorSource::BMX055); + event.setVersion(1); + event.setSensor(SENSOR_MAGNETOMETER_UNCALIBRATED); + event.setType(SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED); + event.setTimestamp(start_time); + + float xyz[] = {x, y, z}; + kj::ArrayPtr vs(&xyz[0], 3); + + auto svec = event.initMagneticUncalibrated(); + svec.setV(vs); + svec.setStatus(true); + } + + // The BMX055 Magnetometer has no FIFO mode. Self running mode only goes + // up to 30 Hz. Therefore we put in forced mode, and request measurements + // at a 100 Hz. When reading the registers we have to check the ready bit + // To verify the measurement was comleted this cycle. + set_register(BMX055_MAGN_I2C_REG_MAG, BMX055_MAGN_FORCED); +} diff --git a/selfdrive/sensord/sensors/bmx055_magn.hpp b/selfdrive/sensord/sensors/bmx055_magn.hpp new file mode 100644 index 00000000000000..ba4942d72fc5ee --- /dev/null +++ b/selfdrive/sensord/sensors/bmx055_magn.hpp @@ -0,0 +1,27 @@ +#pragma once + +#include "sensors/i2c_sensor.hpp" + +// Address of the chip on the bus +#define BMX055_MAGN_I2C_ADDR 0x10 + +// Registers of the chip +#define BMX055_MAGN_I2C_REG_ID 0x40 +#define BMX055_MAGN_I2C_REG_PWR_0 0x4B +#define BMX055_MAGN_I2C_REG_MAG 0x4C +#define BMX055_MAGN_I2C_REG_DATAX_LSB 0x42 +#define BMX055_MAGN_I2C_REG_RHALL_LSB 0x48 +#define BMX055_MAGN_I2C_REG_REPXY 0x51 +#define BMX055_MAGN_I2C_REG_REPZ 0x52 + +// Constants +#define BMX055_MAGN_CHIP_ID 0x32 +#define BMX055_MAGN_FORCED (0b01 << 1) + +class BMX055_Magn : public I2CSensor{ + uint8_t get_device_address() {return BMX055_MAGN_I2C_ADDR;} +public: + BMX055_Magn(I2CBus *bus); + int init(); + void get_event(cereal::SensorEventData::Builder &event); +}; diff --git a/selfdrive/sensord/sensors/bmx055_temp.cc b/selfdrive/sensord/sensors/bmx055_temp.cc new file mode 100644 index 00000000000000..86f7d4f0c1ffee --- /dev/null +++ b/selfdrive/sensord/sensors/bmx055_temp.cc @@ -0,0 +1,44 @@ +#include +#include "common/swaglog.h" +#include "common/timing.h" + +#include "bmx055_temp.hpp" +#include "bmx055_accel.hpp" + + +BMX055_Temp::BMX055_Temp(I2CBus *bus) : I2CSensor(bus) {} + +int BMX055_Temp::init(){ + int ret = 0; + uint8_t buffer[1]; + + ret = read_register(BMX055_ACCEL_I2C_REG_ID, buffer, 1); + if(ret < 0){ + LOGE("Reading chip ID failed: %d", ret); + goto fail; + } + + if(buffer[0] != BMX055_ACCEL_CHIP_ID){ + LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_ACCEL_CHIP_ID); + ret = -1; + goto fail; + } + +fail: + return ret; +} + +void BMX055_Temp::get_event(cereal::SensorEventData::Builder &event){ + uint64_t start_time = nanos_since_boot(); + uint8_t buffer[1]; + int len = read_register(BMX055_ACCEL_I2C_REG_TEMP, buffer, sizeof(buffer)); + assert(len == sizeof(buffer)); + + float temp = 23.0f + int8_t(buffer[0]) / 2.0f; + + event.setSource(cereal::SensorEventData::SensorSource::BMX055); + event.setVersion(1); + event.setType(SENSOR_TYPE_AMBIENT_TEMPERATURE); + event.setTimestamp(start_time); + event.setTemperature(temp); +} diff --git a/selfdrive/sensord/sensors/bmx055_temp.hpp b/selfdrive/sensord/sensors/bmx055_temp.hpp new file mode 100644 index 00000000000000..8b7119a607d652 --- /dev/null +++ b/selfdrive/sensord/sensors/bmx055_temp.hpp @@ -0,0 +1,13 @@ +#pragma once + +#include "sensors/i2c_sensor.hpp" +#include "sensors/bmx055_accel.hpp" + + +class BMX055_Temp : public I2CSensor { + uint8_t get_device_address() {return BMX055_ACCEL_I2C_ADDR;} +public: + BMX055_Temp(I2CBus *bus); + int init(); + void get_event(cereal::SensorEventData::Builder &event); +}; diff --git a/selfdrive/sensord/sensors/constants.hpp b/selfdrive/sensord/sensors/constants.hpp new file mode 100644 index 00000000000000..c216f838a5ab0e --- /dev/null +++ b/selfdrive/sensord/sensors/constants.hpp @@ -0,0 +1,18 @@ +#pragma once + + +#define SENSOR_ACCELEROMETER 1 +#define SENSOR_MAGNETOMETER 2 +#define SENSOR_MAGNETOMETER_UNCALIBRATED 3 +#define SENSOR_GYRO 4 +#define SENSOR_GYRO_UNCALIBRATED 5 +#define SENSOR_LIGHT 7 + +#define SENSOR_TYPE_ACCELEROMETER 1 +#define SENSOR_TYPE_GEOMAGNETIC_FIELD 2 +#define SENSOR_TYPE_GYROSCOPE 4 +#define SENSOR_TYPE_LIGHT 5 +#define SENSOR_TYPE_AMBIENT_TEMPERATURE 13 +#define SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED 14 +#define SENSOR_TYPE_MAGNETIC_FIELD SENSOR_TYPE_GEOMAGNETIC_FIELD +#define SENSOR_TYPE_GYROSCOPE_UNCALIBRATED 16 diff --git a/selfdrive/sensord/sensors/file_sensor.cc b/selfdrive/sensord/sensors/file_sensor.cc new file mode 100644 index 00000000000000..6d03ef1b1f4a2b --- /dev/null +++ b/selfdrive/sensord/sensors/file_sensor.cc @@ -0,0 +1,15 @@ +#include +#include + +#include "file_sensor.hpp" + +FileSensor::FileSensor(std::string filename) : file(filename) { +} + +int FileSensor::init() { + return file.is_open() ? 0 : 1; +} + +FileSensor::~FileSensor(){ + file.close(); +} diff --git a/selfdrive/sensord/sensors/file_sensor.hpp b/selfdrive/sensord/sensors/file_sensor.hpp new file mode 100644 index 00000000000000..25a6f203c8cc3f --- /dev/null +++ b/selfdrive/sensord/sensors/file_sensor.hpp @@ -0,0 +1,19 @@ +#pragma once + +#include +#include + +#include "cereal/gen/cpp/log.capnp.h" +#include "sensors/sensor.hpp" + + +class FileSensor : public Sensor { +protected: + std::ifstream file; + +public: + FileSensor(std::string filename); + ~FileSensor(); + int init(); + virtual void get_event(cereal::SensorEventData::Builder &event) = 0; +}; diff --git a/selfdrive/sensord/sensors/i2c_sensor.cc b/selfdrive/sensord/sensors/i2c_sensor.cc new file mode 100644 index 00000000000000..e3000c8b02ac48 --- /dev/null +++ b/selfdrive/sensord/sensors/i2c_sensor.cc @@ -0,0 +1,24 @@ +#include +#include "i2c_sensor.hpp" + +int16_t read_12_bit(uint8_t lsb, uint8_t msb){ + uint16_t combined = (uint16_t(msb) << 8) | uint16_t(lsb & 0xF0); + return int16_t(combined) / (1 << 4); +} + +int16_t read_16_bit(uint8_t lsb, uint8_t msb){ + uint16_t combined = (uint16_t(msb) << 8) | uint16_t(lsb); + return int16_t(combined); +} + + +I2CSensor::I2CSensor(I2CBus *bus) : bus(bus){ +} + +int I2CSensor::read_register(uint register_address, uint8_t *buffer, uint8_t len){ + return bus->read_register(get_device_address(), register_address, buffer, len); +} + +int I2CSensor::set_register(uint register_address, uint8_t data){ + return bus->set_register(get_device_address(), register_address, data); +} diff --git a/selfdrive/sensord/sensors/i2c_sensor.hpp b/selfdrive/sensord/sensors/i2c_sensor.hpp new file mode 100644 index 00000000000000..39ef79cf836828 --- /dev/null +++ b/selfdrive/sensord/sensors/i2c_sensor.hpp @@ -0,0 +1,24 @@ +#pragma once + +#include +#include "cereal/gen/cpp/log.capnp.h" +#include "common/i2c.h" +#include "sensors/sensor.hpp" +#include "sensors/constants.hpp" + +int16_t read_12_bit(uint8_t lsb, uint8_t msb); +int16_t read_16_bit(uint8_t lsb, uint8_t msb); + + +class I2CSensor : public Sensor { +private: + I2CBus *bus; + virtual uint8_t get_device_address() = 0; + +public: + I2CSensor(I2CBus *bus); + int read_register(uint register_address, uint8_t *buffer, uint8_t len); + int set_register(uint register_address, uint8_t data); + virtual int init() = 0; + virtual void get_event(cereal::SensorEventData::Builder &event) = 0; +}; diff --git a/selfdrive/sensord/sensors/light_sensor.cc b/selfdrive/sensord/sensors/light_sensor.cc new file mode 100644 index 00000000000000..eb3eb05f17e30f --- /dev/null +++ b/selfdrive/sensord/sensors/light_sensor.cc @@ -0,0 +1,23 @@ +#include +#include + +#include "common/timing.h" + +#include "light_sensor.hpp" +#include "constants.hpp" + +void LightSensor::get_event(cereal::SensorEventData::Builder &event){ + uint64_t start_time = nanos_since_boot(); + file.clear(); + file.seekg(0); + + int value; + file >> value; + + event.setSource(cereal::SensorEventData::SensorSource::RPR0521); + event.setVersion(1); + event.setSensor(SENSOR_LIGHT); + event.setType(SENSOR_TYPE_LIGHT); + event.setTimestamp(start_time); + event.setLight(value); +} diff --git a/selfdrive/sensord/sensors/light_sensor.hpp b/selfdrive/sensord/sensors/light_sensor.hpp new file mode 100644 index 00000000000000..7c98cb29cf3d03 --- /dev/null +++ b/selfdrive/sensord/sensors/light_sensor.hpp @@ -0,0 +1,8 @@ +#pragma once +#include "file_sensor.hpp" + +class LightSensor : public FileSensor { +public: + LightSensor(std::string filename) : FileSensor(filename){}; + void get_event(cereal::SensorEventData::Builder &event); +}; diff --git a/selfdrive/sensord/sensors/sensor.hpp b/selfdrive/sensord/sensors/sensor.hpp new file mode 100644 index 00000000000000..91f41790815d8c --- /dev/null +++ b/selfdrive/sensord/sensors/sensor.hpp @@ -0,0 +1,9 @@ +#pragma once + +#include "cereal/gen/cpp/log.capnp.h" + +class Sensor { +public: + virtual int init() = 0; + virtual void get_event(cereal::SensorEventData::Builder &event) = 0; +}; diff --git a/selfdrive/sensord/sensors.cc b/selfdrive/sensord/sensors_qcom.cc similarity index 67% rename from selfdrive/sensord/sensors.cc rename to selfdrive/sensord/sensors_qcom.cc index b42482d8531f67..4119d8ede65da5 100644 --- a/selfdrive/sensord/sensors.cc +++ b/selfdrive/sensord/sensors_qcom.cc @@ -10,7 +10,8 @@ #include #include -#include +#include +#include #include #include @@ -20,15 +21,14 @@ #include "common/timing.h" #include "common/swaglog.h" +// ACCELEROMETER_UNCALIBRATED is only in Android O +// https://developer.android.com/reference/android/hardware/Sensor.html#STRING_TYPE_ACCELEROMETER_UNCALIBRATED + #define SENSOR_ACCELEROMETER 1 #define SENSOR_MAGNETOMETER 2 #define SENSOR_GYRO 4 - -// ACCELEROMETER_UNCALIBRATED is only in Android O -// https://developer.android.com/reference/android/hardware/Sensor.html#STRING_TYPE_ACCELEROMETER_UNCALIBRATED #define SENSOR_MAGNETOMETER_UNCALIBRATED 3 #define SENSOR_GYRO_UNCALIBRATED 5 - #define SENSOR_PROXIMITY 6 #define SENSOR_LIGHT 7 @@ -70,30 +70,33 @@ void sensor_loop() { LOGD("sensor %4d: %4d %60s %d-%ld us", i, list[i].handle, list[i].name, list[i].minDelay, list[i].maxDelay); } - device->activate(device, SENSOR_MAGNETOMETER_UNCALIBRATED, 0); - device->activate(device, SENSOR_GYRO_UNCALIBRATED, 0); - device->activate(device, SENSOR_ACCELEROMETER, 0); - device->activate(device, SENSOR_MAGNETOMETER, 0); - device->activate(device, SENSOR_GYRO, 0); - device->activate(device, SENSOR_PROXIMITY, 0); - device->activate(device, SENSOR_LIGHT, 0); - - device->activate(device, SENSOR_MAGNETOMETER_UNCALIBRATED, 1); - device->activate(device, SENSOR_GYRO_UNCALIBRATED, 1); - device->activate(device, SENSOR_ACCELEROMETER, 1); - device->activate(device, SENSOR_MAGNETOMETER, 1); - device->activate(device, SENSOR_GYRO, 1); - device->activate(device, SENSOR_PROXIMITY, 1); - device->activate(device, SENSOR_LIGHT, 1); - - device->setDelay(device, SENSOR_GYRO_UNCALIBRATED, ms2ns(10)); - device->setDelay(device, SENSOR_MAGNETOMETER_UNCALIBRATED, ms2ns(100)); - device->setDelay(device, SENSOR_ACCELEROMETER, ms2ns(10)); - device->setDelay(device, SENSOR_GYRO, ms2ns(10)); - device->setDelay(device, SENSOR_MAGNETOMETER, ms2ns(100)); - device->setDelay(device, SENSOR_PROXIMITY, ms2ns(100)); - device->setDelay(device, SENSOR_LIGHT, ms2ns(100)); + std::set sensor_types = { + SENSOR_TYPE_ACCELEROMETER, + SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED, + SENSOR_TYPE_MAGNETIC_FIELD, + SENSOR_TYPE_GYROSCOPE_UNCALIBRATED, + SENSOR_TYPE_GYROSCOPE, + SENSOR_TYPE_PROXIMITY, + SENSOR_TYPE_LIGHT, + }; + + std::map sensors = { + {SENSOR_GYRO_UNCALIBRATED, ms2ns(10)}, + {SENSOR_MAGNETOMETER_UNCALIBRATED, ms2ns(100)}, + {SENSOR_ACCELEROMETER, ms2ns(10)}, + {SENSOR_GYRO, ms2ns(10)}, + {SENSOR_MAGNETOMETER, ms2ns(100)}, + {SENSOR_PROXIMITY, ms2ns(100)}, + {SENSOR_LIGHT, ms2ns(100)} + }; + + for (auto &s : sensors) { + device->activate(device, s.first, 0); + device->activate(device, s.first, 1); + device->setDelay(device, s.first, s.second); + } + // TODO: why is this 16? static const size_t numEvents = 16; sensors_event_t buffer[numEvents]; @@ -107,49 +110,24 @@ void sensor_loop() { int log_events = 0; for (int i=0; i < n; i++) { - switch (buffer[i].type) { - case SENSOR_TYPE_ACCELEROMETER: - case SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED: - case SENSOR_TYPE_MAGNETIC_FIELD: - case SENSOR_TYPE_GYROSCOPE_UNCALIBRATED: - case SENSOR_TYPE_GYROSCOPE: - case SENSOR_TYPE_PROXIMITY: - case SENSOR_TYPE_LIGHT: + if (sensor_types.find(buffer[i].type) != sensor_types.end()) { log_events++; - break; - default: - continue; } } - uint64_t log_time = nanos_since_boot(); - - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(log_time); - - auto sensor_events = event.initSensorEvents(log_events); + MessageBuilder msg; + auto sensor_events = msg.initEvent().initSensorEvents(log_events); int log_i = 0; for (int i = 0; i < n; i++) { const sensors_event_t& data = buffer[i]; - switch (data.type) { - case SENSOR_TYPE_ACCELEROMETER: - case SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED: - case SENSOR_TYPE_MAGNETIC_FIELD: - case SENSOR_TYPE_GYROSCOPE_UNCALIBRATED: - case SENSOR_TYPE_GYROSCOPE: - case SENSOR_TYPE_PROXIMITY: - case SENSOR_TYPE_LIGHT: - break; - default: + if (sensor_types.find(data.type) == sensor_types.end()) { continue; } auto log_event = sensor_events[log_i]; - log_event.setSource(cereal::SensorEventData::SensorSource::ANDROID); log_event.setVersion(data.version); log_event.setSensor(data.sensor); diff --git a/selfdrive/sensord/sensors_qcom2.cc b/selfdrive/sensord/sensors_qcom2.cc new file mode 100644 index 00000000000000..d9da486054015a --- /dev/null +++ b/selfdrive/sensord/sensors_qcom2.cc @@ -0,0 +1,90 @@ +#include +#include +#include +#include +#include + +#include "messaging.hpp" +#include "common/i2c.h" +#include "common/timing.h" +#include "common/swaglog.h" + +#include "sensors/sensor.hpp" +#include "sensors/constants.hpp" +#include "sensors/bmx055_accel.hpp" +#include "sensors/bmx055_gyro.hpp" +#include "sensors/bmx055_magn.hpp" +#include "sensors/bmx055_temp.hpp" +#include "sensors/light_sensor.hpp" + +volatile sig_atomic_t do_exit = 0; + +#define I2C_BUS_IMU 1 + + +void set_do_exit(int sig) { + do_exit = 1; +} + +int sensor_loop() { + I2CBus *i2c_bus_imu; + + try { + i2c_bus_imu = new I2CBus(I2C_BUS_IMU); + } catch (std::exception &e) { + LOGE("I2CBus init failed"); + return -1; + } + + BMX055_Accel accel(i2c_bus_imu); + BMX055_Gyro gyro(i2c_bus_imu); + BMX055_Magn magn(i2c_bus_imu); + BMX055_Temp temp(i2c_bus_imu); + LightSensor light("/sys/class/i2c-adapter/i2c-2/2-0038/iio:device1/in_intensity_both_raw"); + + // Sensor init + std::vector sensors; + sensors.push_back(&accel); + sensors.push_back(&gyro); + sensors.push_back(&magn); + sensors.push_back(&temp); + sensors.push_back(&light); + + + for (Sensor * sensor : sensors){ + int err = sensor->init(); + if (err < 0){ + LOGE("Error initializing sensors"); + return -1; + } + } + + PubMaster pm({"sensorEvents"}); + + while (!do_exit){ + std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now(); + + const int num_events = sensors.size(); + MessageBuilder msg; + auto sensor_events = msg.initEvent().initSensorEvents(num_events); + + for (int i = 0; i < num_events; i++){ + auto event = sensor_events[i]; + sensors[i]->get_event(event); + } + + pm.send("sensorEvents", msg); + + std::chrono::steady_clock::time_point end = std::chrono::steady_clock::now(); + std::this_thread::sleep_for(std::chrono::milliseconds(10) - (end - begin)); + } + return 0; +} + +int main(int argc, char *argv[]) { + setpriority(PRIO_PROCESS, 0, -13); + signal(SIGINT, set_do_exit); + signal(SIGTERM, set_do_exit); + + return sensor_loop(); +} diff --git a/selfdrive/test/helpers.py b/selfdrive/test/helpers.py index 1e53ef4245037c..6ee6caf08e83b2 100644 --- a/selfdrive/test/helpers.py +++ b/selfdrive/test/helpers.py @@ -1,8 +1,9 @@ +import time import subprocess from functools import wraps from nose.tools import nottest -from common.android import ANDROID +from common.hardware import PC from common.apk import update_apks, start_offroad, pm_apply_packages, android_packages from common.params import Params from selfdrive.version import training_version, terms_version @@ -18,27 +19,31 @@ def set_params_enabled(): params.put("CompletedTrainingVersion", training_version) def phone_only(x): - if ANDROID: - return x - else: + if PC: return nottest(x) + else: + return x -def with_processes(processes): +def with_processes(processes, init_time=0): def wrapper(func): @wraps(func) - def wrap(): + def wrap(*args, **kwargs): # start and assert started - [start_managed_process(p) for p in processes] + for n, p in enumerate(processes): + start_managed_process(p) + if n < len(processes)-1: + time.sleep(init_time) assert all(get_running()[name].exitcode is None for name in processes) # call the function try: - func() + func(*args, **kwargs) # assert processes are still started assert all(get_running()[name].exitcode is None for name in processes) finally: # kill and assert all stopped - [kill_managed_process(p) for p in processes] + for p in processes: + kill_managed_process(p) assert len(get_running()) == 0 return wrap return wrapper @@ -64,4 +69,3 @@ def wrap(): assert apk_is_not_running, package return wrap return wrapper - diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index e8228ce7d47982..f1801e72db803d 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -15,7 +15,7 @@ fi # TODO: never clear qcom_replay cache # clear scons cache dirs that haven't been written to in one day -cd /tmp && find -name 'scons_cache_*' -type d -maxdepth 1 -mtime 1 -exec rm -rf '{}' \; +cd /tmp && find -name 'scons_cache_*' -type d -maxdepth 1 -mtime +1 -exec rm -rf '{}' \; # set up environment cd $SOURCE_DIR diff --git a/selfdrive/test/test_cpu_usage.py b/selfdrive/test/test_cpu_usage.py index 2f260ec8a34d86..0e06e0ab4dabb1 100755 --- a/selfdrive/test/test_cpu_usage.py +++ b/selfdrive/test/test_cpu_usage.py @@ -15,22 +15,22 @@ def cputime_total(ct): def print_cpu_usage(first_proc, last_proc): procs = [ - ("selfdrive.controls.controlsd", 66.15), - ("selfdrive.locationd.locationd", 34.38), + ("selfdrive.controls.controlsd", 45.0), ("./loggerd", 33.90), - ("selfdrive.controls.plannerd", 19.77), - ("./_modeld", 12.74), - ("selfdrive.locationd.paramsd", 11.53), + ("selfdrive.locationd.locationd", 29.5), + ("selfdrive.controls.plannerd", 11.84), + ("selfdrive.locationd.paramsd", 10.5), + ("./_modeld", 7.12), ("selfdrive.controls.radard", 9.54), - ("./_ui", 9.54), ("./camerad", 7.07), - ("selfdrive.locationd.calibrationd", 6.81), ("./_sensord", 6.17), - ("selfdrive.monitoring.dmonitoringd", 5.48), + ("./_ui", 5.82), ("./boardd", 3.63), ("./_dmonitoringmodeld", 2.67), ("selfdrive.logmessaged", 2.71), ("selfdrive.thermald.thermald", 2.41), + ("selfdrive.locationd.calibrationd", 2.0), + ("selfdrive.monitoring.dmonitoringd", 1.90), ("./proclogd", 1.54), ("./_gpsd", 0.09), ("./clocksd", 0.02), @@ -51,7 +51,7 @@ def print_cpu_usage(first_proc, last_proc): if cpu_usage > max(normal_cpu_usage * 1.1, normal_cpu_usage + 5.0): result += f"Warning {proc_name} using more CPU than normal\n" r = False - elif cpu_usage < min(normal_cpu_usage * 0.3, max(normal_cpu_usage - 1.0, 0.0)): + elif cpu_usage < min(normal_cpu_usage * 0.65, max(normal_cpu_usage - 1.0, 0.0)): result += f"Warning {proc_name} using less CPU than normal\n" r = False result += f"{proc_name.ljust(35)} {cpu_usage:.2f}%\n" @@ -71,12 +71,15 @@ def test_cpu_usage(): try: proc_sock = messaging.sub_sock('procLog', conflate=True, timeout=2000) - # wait until everything's started and get first sample + # wait until everything's started start_time = time.monotonic() - while time.monotonic() - start_time < 120: + while time.monotonic() - start_time < 210: if Params().get("CarParams") is not None: break time.sleep(2) + + # take first sample + time.sleep(5) first_proc = messaging.recv_sock(proc_sock, wait=True) if first_proc is None: raise Exception("\n\nTEST FAILED: progLog recv timed out\n\n") diff --git a/selfdrive/thermald/power_monitoring.py b/selfdrive/thermald/power_monitoring.py index 6bf26ee0eae6f4..76b9ad3b26b4af 100644 --- a/selfdrive/thermald/power_monitoring.py +++ b/selfdrive/thermald/power_monitoring.py @@ -1,4 +1,3 @@ -import datetime import random import threading import time @@ -6,10 +5,20 @@ from cereal import log from common.realtime import sec_since_boot +from common.params import Params, put_nonblocking +from common.hardware import TICI from selfdrive.swaglog import cloudlog PANDA_OUTPUT_VOLTAGE = 5.28 +CAR_VOLTAGE_LOW_PASS_K = 0.091 # LPF gain for 5s tau (dt/tau / (dt/tau + 1)) +# A C2 uses about 1W while idling, and 30h seens like a good shutoff for most cars +# While driving, a battery charges completely in about 30-60 minutes +CAR_BATTERY_CAPACITY_uWh = 30e6 +CAR_CHARGING_RATE_W = 45 + +VBATT_PAUSE_CHARGING = 11.0 +MAX_TIME_OFFROAD_S = 30*3600 # Parameters def get_battery_capacity(): @@ -36,7 +45,7 @@ def get_usb_present(): def get_battery_charging(): # This does correspond with actually charging - return _read_param("/sys/class/power_supply/battery/charge_type", lambda x: x.strip() != "N/A", False) + return _read_param("/sys/class/power_supply/battery/charge_type", lambda x: x.strip() != "N/A", True) def set_battery_charging(on): @@ -60,91 +69,120 @@ def panda_current_to_actual_current(panda_current): class PowerMonitoring: def __init__(self): + self.params = Params() self.last_measurement_time = None # Used for integration delta + self.last_save_time = 0 # Used for saving current value in a param self.power_used_uWh = 0 # Integrated power usage in uWh since going into offroad self.next_pulsed_measurement_time = None + self.car_voltage_mV = 12e3 # Low-passed version of health voltage self.integration_lock = threading.Lock() + car_battery_capacity_uWh = self.params.get("CarBatteryCapacity") + if car_battery_capacity_uWh is None: + car_battery_capacity_uWh = 0 + + # Reset capacity if it's low + self.car_battery_capacity_uWh = max((CAR_BATTERY_CAPACITY_uWh / 10), int(car_battery_capacity_uWh)) + + # Calculation tick def calculate(self, health): try: now = sec_since_boot() - # Check that time is valid - if datetime.datetime.fromtimestamp(now).year < 2019: - return - - # Only integrate when there is no ignition # If health is None, we're probably not in a car, so we don't care - if health is None or (health.health.ignitionLine or health.health.ignitionCan) or \ - health.health.hwType == log.HealthData.HwType.unknown: + if health is None or health.health.hwType == log.HealthData.HwType.unknown: with self.integration_lock: self.last_measurement_time = None self.next_pulsed_measurement_time = None self.power_used_uWh = 0 return + # Low-pass battery voltage + self.car_voltage_mV = ((health.health.voltage * CAR_VOLTAGE_LOW_PASS_K) + (self.car_voltage_mV * (1 - CAR_VOLTAGE_LOW_PASS_K))) + + # Cap the car battery power and save it in a param every 10-ish seconds + self.car_battery_capacity_uWh = max(self.car_battery_capacity_uWh, 0) + self.car_battery_capacity_uWh = min(self.car_battery_capacity_uWh, CAR_BATTERY_CAPACITY_uWh) + if now - self.last_save_time >= 10: + put_nonblocking("CarBatteryCapacity", str(int(self.car_battery_capacity_uWh))) + self.last_save_time = now + # First measurement, set integration time with self.integration_lock: if self.last_measurement_time is None: self.last_measurement_time = now return - is_uno = health.health.hwType == log.HealthData.HwType.uno - # Get current power draw somehow - current_power = 0 - if get_battery_status() == 'Discharging': - # If the battery is discharging, we can use this measurement - # On C2: this is low by about 10-15%, probably mostly due to UNO draw not being factored in - current_power = ((get_battery_voltage() / 1000000) * (get_battery_current() / 1000000)) - elif (health.health.hwType in [log.HealthData.HwType.whitePanda, log.HealthData.HwType.greyPanda]) and (health.health.current > 1): - # If white/grey panda, use the integrated current measurements if the measurement is not 0 - # If the measurement is 0, the current is 400mA or greater, and out of the measurement range of the panda - # This seems to be accurate to about 5% - current_power = (PANDA_OUTPUT_VOLTAGE * panda_current_to_actual_current(health.health.current)) - elif (self.next_pulsed_measurement_time is not None) and (self.next_pulsed_measurement_time <= now): - # TODO: Figure out why this is off by a factor of 3/4??? - FUDGE_FACTOR = 1.33 - - # Turn off charging for about 10 sec in a thread that does not get killed on SIGINT, and perform measurement here to avoid blocking thermal - def perform_pulse_measurement(now): - try: - set_battery_charging(False) - time.sleep(5) - - # Measure for a few sec to get a good average - voltages = [] - currents = [] - for _ in range(6): - voltages.append(get_battery_voltage()) - currents.append(get_battery_current()) - time.sleep(1) - current_power = ((mean(voltages) / 1000000) * (mean(currents) / 1000000)) - - self._perform_integration(now, current_power * FUDGE_FACTOR) - - # Enable charging again - set_battery_charging(True) - except Exception: - cloudlog.exception("Pulsed power measurement failed") - - # Start pulsed measurement and return - threading.Thread(target=perform_pulse_measurement, args=(now,)).start() - self.next_pulsed_measurement_time = None - return - - elif self.next_pulsed_measurement_time is None and not is_uno: - # On a charging EON with black panda, or drawing more than 400mA out of a white/grey one - # Only way to get the power draw is to turn off charging for a few sec and check what the discharging rate is - # We shouldn't do this very often, so make sure it has been some long-ish random time interval - self.next_pulsed_measurement_time = now + random.randint(120, 180) - return + if (health.health.ignitionLine or health.health.ignitionCan): + # If there is ignition, we integrate the charging rate of the car + with self.integration_lock: + self.power_used_uWh = 0 + integration_time_h = (now - self.last_measurement_time) / 3600 + if integration_time_h < 0: + raise ValueError(f"Negative integration time: {integration_time_h}h") + self.car_battery_capacity_uWh += (CAR_CHARGING_RATE_W * 1e6 * integration_time_h) + self.last_measurement_time = now else: - # Do nothing - return + # No ignition, we integrate the offroad power used by the device + is_uno = health.health.hwType == log.HealthData.HwType.uno + # Get current power draw somehow + current_power = 0 + if TICI: + with open("/sys/class/hwmon/hwmon1/power1_input") as f: + current_power = int(f.read()) / 1e6 + elif get_battery_status() == 'Discharging': + # If the battery is discharging, we can use this measurement + # On C2: this is low by about 10-15%, probably mostly due to UNO draw not being factored in + current_power = ((get_battery_voltage() / 1000000) * (get_battery_current() / 1000000)) + elif (health.health.hwType in [log.HealthData.HwType.whitePanda, log.HealthData.HwType.greyPanda]) and (health.health.current > 1): + # If white/grey panda, use the integrated current measurements if the measurement is not 0 + # If the measurement is 0, the current is 400mA or greater, and out of the measurement range of the panda + # This seems to be accurate to about 5% + current_power = (PANDA_OUTPUT_VOLTAGE * panda_current_to_actual_current(health.health.current)) + elif (self.next_pulsed_measurement_time is not None) and (self.next_pulsed_measurement_time <= now): + # TODO: Figure out why this is off by a factor of 3/4??? + FUDGE_FACTOR = 1.33 + + # Turn off charging for about 10 sec in a thread that does not get killed on SIGINT, and perform measurement here to avoid blocking thermal + def perform_pulse_measurement(now): + try: + set_battery_charging(False) + time.sleep(5) + + # Measure for a few sec to get a good average + voltages = [] + currents = [] + for _ in range(6): + voltages.append(get_battery_voltage()) + currents.append(get_battery_current()) + time.sleep(1) + current_power = ((mean(voltages) / 1000000) * (mean(currents) / 1000000)) + + self._perform_integration(now, current_power * FUDGE_FACTOR) + + # Enable charging again + set_battery_charging(True) + except Exception: + cloudlog.exception("Pulsed power measurement failed") + + # Start pulsed measurement and return + threading.Thread(target=perform_pulse_measurement, args=(now,)).start() + self.next_pulsed_measurement_time = None + return - # Do the integration - self._perform_integration(now, current_power) + elif self.next_pulsed_measurement_time is None and not is_uno: + # On a charging EON with black panda, or drawing more than 400mA out of a white/grey one + # Only way to get the power draw is to turn off charging for a few sec and check what the discharging rate is + # We shouldn't do this very often, so make sure it has been some long-ish random time interval + self.next_pulsed_measurement_time = now + random.randint(120, 180) + return + else: + # Do nothing + return + + # Do the integration + self._perform_integration(now, current_power) except Exception: cloudlog.exception("Power monitoring calculation failed") @@ -157,6 +195,7 @@ def _perform_integration(self, t, current_power): if power_used < 0: raise ValueError(f"Negative power used! Integration time: {integration_time_h} h Current Power: {power_used} uWh") self.power_used_uWh += power_used + self.car_battery_capacity_uWh -= power_used self.last_measurement_time = t except Exception: cloudlog.exception("Integration failed") @@ -164,3 +203,36 @@ def _perform_integration(self, t, current_power): # Get the power usage def get_power_used(self): return int(self.power_used_uWh) + + def get_car_battery_capacity(self): + return int(self.car_battery_capacity_uWh) + + # See if we need to disable charging + def should_disable_charging(self, health, offroad_timestamp): + if health is None or offroad_timestamp is None: + return False + + now = sec_since_boot() + disable_charging = False + disable_charging |= (now - offroad_timestamp) > MAX_TIME_OFFROAD_S + disable_charging |= (self.car_voltage_mV < (VBATT_PAUSE_CHARGING * 1e3)) + disable_charging |= (self.car_battery_capacity_uWh <= 0) + disable_charging &= (not health.health.ignitionLine and not health.health.ignitionCan) + disable_charging &= (self.params.get("DisablePowerDown") != b"1") + return disable_charging + + # See if we need to shutdown + def should_shutdown(self, health, offroad_timestamp, started_seen, LEON): + if health is None or offroad_timestamp is None: + return False + + now = sec_since_boot() + panda_charging = (health.health.usbPowerMode != log.HealthData.UsbPowerMode.client) + BATT_PERC_OFF = 10 if LEON else 3 + + should_shutdown = False + # Wait until we have shut down charging before powering down + should_shutdown |= (not panda_charging and self.should_disable_charging(health, offroad_timestamp)) + should_shutdown |= ((get_battery_capacity() < BATT_PERC_OFF) and (not get_battery_charging()) and ((now - offroad_timestamp) > 60)) + should_shutdown &= started_seen + return should_shutdown diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 093b832da0827f..10b8a454786c11 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -1,22 +1,32 @@ #!/usr/bin/env python3 -import os import datetime +import os +import time +from collections import namedtuple + import psutil from smbus2 import SMBus + +import cereal.messaging as messaging from cereal import log -from common.android import ANDROID, get_network_type, get_network_strength -from common.params import Params, put_nonblocking -from common.realtime import sec_since_boot, DT_TRML -from common.numpy_fast import clip, interp from common.filter_simple import FirstOrderFilter -from selfdrive.version import terms_version, training_version, get_git_branch -from selfdrive.swaglog import cloudlog -import cereal.messaging as messaging +from common.hardware import EON, HARDWARE, TICI +from common.numpy_fast import clip, interp +from common.params import Params, put_nonblocking +from common.realtime import DT_TRML, sec_since_boot from selfdrive.controls.lib.alertmanager import set_offroad_alert from selfdrive.loggerd.config import get_available_percent from selfdrive.pandad import get_expected_signature -from selfdrive.thermald.power_monitoring import PowerMonitoring, get_battery_capacity, get_battery_status, \ - get_battery_current, get_battery_voltage, get_usb_present +from selfdrive.swaglog import cloudlog +from selfdrive.thermald.power_monitoring import (PowerMonitoring, + get_battery_capacity, + get_battery_current, + get_battery_status, + get_battery_voltage, + get_usb_present) +from selfdrive.version import get_git_branch, terms_version, training_version + +ThermalConfig = namedtuple('ThermalConfig', ['cpu', 'gpu', 'mem', 'bat', 'ambient']) FW_SIGNATURE = get_expected_signature() @@ -33,31 +43,34 @@ last_eon_fan_val = None -def read_tz(x, clip=True): - if not ANDROID: - # we don't monitor thermal on PC +def get_thermal_config(): + # (tz, scale) + if EON: + return ThermalConfig(cpu=((5, 7, 10, 12), 10), gpu=((16,), 10), mem=(2, 10), bat=(29, 1000), ambient=(25, 1)) + elif TICI: + return ThermalConfig(cpu=((1, 2, 3, 4, 5, 6, 7, 8), 1000), gpu=((48,49), 1000), mem=(15, 1000), bat=(None, 1), ambient=(70, 1000)) + else: + return ThermalConfig(cpu=((None,), 1), gpu=((None,), 1), mem=(None, 1), bat=(None, 1), ambient=(None, 1)) + + +def read_tz(x): + if x is None: return 0 + try: with open("/sys/devices/virtual/thermal/thermal_zone%d/temp" % x) as f: - ret = int(f.read()) - if clip: - ret = max(0, ret) + return int(f.read()) except FileNotFoundError: return 0 - return ret - -def read_thermal(): +def read_thermal(thermal_config): dat = messaging.new_message('thermal') - dat.thermal.cpu0 = read_tz(5) - dat.thermal.cpu1 = read_tz(7) - dat.thermal.cpu2 = read_tz(10) - dat.thermal.cpu3 = read_tz(12) - dat.thermal.mem = read_tz(2) - dat.thermal.gpu = read_tz(16) - dat.thermal.bat = read_tz(29) - dat.thermal.pa0 = read_tz(25) + dat.thermal.cpu = [read_tz(z) / thermal_config.cpu[1] for z in thermal_config.cpu[0]] + dat.thermal.gpu = [read_tz(z) / thermal_config.gpu[1] for z in thermal_config.gpu[0]] + dat.thermal.mem = read_tz(thermal_config.mem[0]) / thermal_config.mem[1] + dat.thermal.ambient = read_tz(thermal_config.ambient[0]) / thermal_config.ambient[1] + dat.thermal.bat = read_tz(thermal_config.bat[0]) / thermal_config.bat[1] return dat @@ -111,7 +124,7 @@ def set_eon_fan(val): # fan speed options _FAN_SPEEDS = [0, 16384, 32768, 65535] # max fan speed only allowed if battery is hot -_BAT_TEMP_THERSHOLD = 45. +_BAT_TEMP_THRESHOLD = 45. def handle_fan_eon(max_cpu_temp, bat_temp, fan_speed, ignition): @@ -125,7 +138,7 @@ def handle_fan_eon(max_cpu_temp, bat_temp, fan_speed, ignition): # update speed if using the low thresholds results in fan speed decrement fan_speed = new_speed_l - if bat_temp < _BAT_TEMP_THERSHOLD: + if bat_temp < _BAT_TEMP_THRESHOLD: # no max fan speed unless battery is hot fan_speed = min(fan_speed, _FAN_SPEEDS[-2]) @@ -144,9 +157,6 @@ def handle_fan_uno(max_cpu_temp, bat_temp, fan_speed, ignition): def thermald_thread(): - # prevent LEECO from undervoltage - BATT_PERC_OFF = 10 if LEON else 3 - health_timeout = int(1000 * 2.5 * DT_TRML) # 2.5x the expected health frequency # now loop @@ -185,11 +195,13 @@ def thermald_thread(): pm = PowerMonitoring() no_panda_cnt = 0 + thermal_config = get_thermal_config() + while 1: health = messaging.recv_sock(health_sock, wait=True) location = messaging.recv_sock(location_sock) location = location.gpsLocation if location else None - msg = read_thermal() + msg = read_thermal(thermal_config) if health is not None: usb_power = health.health.usbPowerMode != log.HealthData.UsbPowerMode.client @@ -210,7 +222,7 @@ def thermald_thread(): is_uno = health.health.hwType == log.HealthData.HwType.uno has_relay = health.health.hwType in [log.HealthData.HwType.blackPanda, log.HealthData.HwType.uno, log.HealthData.HwType.dos] - if is_uno or not ANDROID: + if (not EON) or is_uno: cloudlog.info("Setting up UNO fan handler") handle_fan = handle_fan_uno else: @@ -228,8 +240,8 @@ def thermald_thread(): # get_network_type is an expensive call. update every 10s if (count % int(10. / DT_TRML)) == 0: try: - network_type = get_network_type() - network_strength = get_network_strength(network_type) + network_type = HARDWARE.get_network_type() + network_strength = HARDWARE.get_network_strength(network_type) except Exception: cloudlog.exception("Error getting network status") @@ -245,7 +257,7 @@ def thermald_thread(): msg.thermal.usbOnline = get_usb_present() # Fake battery levels on uno for frame - if is_uno: + if (not EON) or is_uno: msg.thermal.batteryPercent = 100 msg.thermal.batteryStatus = "Charging" msg.thermal.bat = 0 @@ -253,14 +265,9 @@ def thermald_thread(): current_filter.update(msg.thermal.batteryCurrent / 1e6) # TODO: add car battery voltage check - max_cpu_temp = cpu_temp_filter.update( - max(msg.thermal.cpu0, - msg.thermal.cpu1, - msg.thermal.cpu2, - msg.thermal.cpu3) / 10.0) - - max_comp_temp = max(max_cpu_temp, msg.thermal.mem / 10., msg.thermal.gpu / 10.) - bat_temp = msg.thermal.bat / 1000. + max_cpu_temp = cpu_temp_filter.update(max(msg.thermal.cpu)) + max_comp_temp = max(max_cpu_temp, msg.thermal.mem, max(msg.thermal.gpu)) + bat_temp = msg.thermal.bat if handle_fan is not None: fan_speed = handle_fan(max_cpu_temp, bat_temp, fan_speed, ignition) @@ -269,7 +276,8 @@ def thermald_thread(): # If device is offroad we want to cool down before going onroad # since going onroad increases load and can make temps go over 107 # We only do this if there is a relay that prevents the car from faulting - if max_cpu_temp > 107. or bat_temp >= 63. or (has_relay and (started_ts is None) and max_cpu_temp > 70.0): + is_offroad_for_5_min = (started_ts is None) and ((not started_seen) or (off_ts is None) or (sec_since_boot() - off_ts > 60 * 5)) + if max_cpu_temp > 107. or bat_temp >= 63. or (has_relay and is_offroad_for_5_min and max_cpu_temp > 70.0): # onroad not allowed thermal_status = ThermalStatus.danger elif max_comp_temp > 96.0 or bat_temp > 60.: @@ -402,15 +410,20 @@ def thermald_thread(): off_ts = sec_since_boot() os.system('echo powersave > /sys/class/devfreq/soc:qcom,cpubw/governor') - # shutdown if the battery gets lower than 3%, it's discharging, we aren't running for - # more than a minute but we were running - if msg.thermal.batteryPercent < BATT_PERC_OFF and msg.thermal.batteryStatus == "Discharging" and \ - started_seen and (sec_since_boot() - off_ts) > 60: - os.system('LD_LIBRARY_PATH="" svc power shutdown') - # Offroad power monitoring pm.calculate(health) msg.thermal.offroadPowerUsage = pm.get_power_used() + msg.thermal.carBatteryCapacity = max(0, pm.get_car_battery_capacity()) + + # Check if we need to disable charging (handled by boardd) + msg.thermal.chargingDisabled = pm.should_disable_charging(health, off_ts) + + # Check if we need to shut down + if pm.should_shutdown(health, off_ts, started_seen, LEON): + cloudlog.info(f"shutting device down, offroad since {off_ts}") + # TODO: add function for blocking cloudlog instead of sleep + time.sleep(10) + os.system('LD_LIBRARY_PATH="" svc power shutdown') msg.thermal.chargingError = current_filter.x > 0. and msg.thermal.batteryPercent < 90 # if current is positive, then battery is being discharged msg.thermal.started = started_ts is not None diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py index 4dc969b5c780ec..fbebddbd72e4ca 100755 --- a/selfdrive/tombstoned.py +++ b/selfdrive/tombstoned.py @@ -12,10 +12,16 @@ def get_tombstones(): - """Returns list of (filename, ctime) for all tombstones in /data/tombstones""" - DIR_DATA = "/data/tombstones/" - return [(DIR_DATA + fn, int(os.stat(DIR_DATA + fn).st_ctime)) - for fn in os.listdir(DIR_DATA) if fn.startswith("tombstone")] + """Returns list of (filename, ctime) for all tombstones in /data/tombstones + and apport crashlogs in /var/crash""" + files = [] + for folder in ["/data/tombstones/", "/var/crash/"]: + if os.path.exists(folder): + for fn in os.listdir(folder): + if fn.startswith("tombstone") or fn.endswith(".crash"): + path = os.path.join(folder, fn) + files.append((path, int(os.stat(path).st_ctime))) + return files def report_tombstone(fn, client): @@ -28,17 +34,27 @@ def report_tombstone(fn, client): contents = f.read() # Get summary for sentry title - message = " ".join(contents.split('\n')[5:7]) + if fn.endswith(".crash"): + lines = contents.split('\n') + message = lines[6] - # Cut off pid/tid, since that varies per run - name_idx = message.find('name') - if name_idx >= 0: - message = message[name_idx:] + status_idx = contents.find('ProcStatus') + if status_idx >= 0: + lines = contents[status_idx:].split('\n') + message += " " + lines[1] + else: + message = " ".join(contents.split('\n')[5:7]) + + # Cut off pid/tid, since that varies per run + name_idx = message.find('name') + if name_idx >= 0: + message = message[name_idx:] + + # Cut off fault addr + fault_idx = message.find(', fault addr') + if fault_idx >= 0: + message = message[:fault_idx] - # Cut off fault addr - fault_idx = message.find(', fault addr') - if fault_idx >= 0: - message = message[:fault_idx] cloudlog.error({'tombstone': message}) client.captureMessage( @@ -53,7 +69,6 @@ def report_tombstone(fn, client): def main(): initial_tombstones = set(get_tombstones()) - client = Client('https://d3b175702f62402c91ade04d1c547e68:b20d68c813c74f63a7cdf9c4039d8f56@sentry.io/157615', install_sys_hook=False, transport=HTTPTransport, release=version, tags={'dirty': dirty}, string_max_length=10000) diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 8f22824fbb5baa..2207123a9777a7 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -1,17 +1,30 @@ -Import('env', 'arch', 'common', 'messaging', 'gpucommon', 'visionipc', 'cereal') +Import('env', 'qt_env', 'arch', 'common', 'messaging', 'gpucommon', 'visionipc', 'cereal') src = ['ui.cc', 'paint.cc', 'sidebar.cc', '#phonelibs/nanovg/nanovg.c'] libs = [common, 'zmq', 'czmq', 'capnp', 'kj', 'm', cereal, messaging, gpucommon, visionipc] -if arch == "aarch64": - src += ['sound.cc'] + +if qt_env is None: libs += ['EGL', 'GLESv3', 'gnustl_shared', 'log', 'utils', 'gui', 'hardware', 'ui', 'CB', 'gsl', 'adreno_utils', 'OpenSLES', 'cutils', 'uuid', 'OpenCL'] linkflags = ['-Wl,-rpath=/system/lib64,-rpath=/system/comma/usr/lib'] + + src += ["android/ui.cc", "android/sl_sound.cc"] + env.Program('_ui', src, + LINKFLAGS=linkflags, + LIBS=libs) + else: - src += ['linux.cc'] - libs += ['pthread', 'glfw'] - linkflags = [] + qt_libs = ["pthread"] + + if arch == "Darwin": + qt_env["FRAMEWORKS"] += ["QtWidgets", "QtGui", "QtCore", "QtDBus", "QtMultimedia"] + else: + qt_libs += ["Qt5Widgets", "Qt5Gui", "Qt5Core", "Qt5DBus", "Qt5Multimedia"] + + if arch == "larch64": + qt_libs += ["GLESv2", "wayland-client"] + else: + qt_libs += ["GL"] -env.Program('_ui', src, - LINKFLAGS=linkflags, - LIBS=libs) + qt_src = ["qt/ui.cc", "qt/window.cc", "qt/settings.cc", "qt/qt_sound.cc"] + src + qt_env.Program("_ui", qt_src, LIBS=qt_libs + libs) diff --git a/selfdrive/ui/sound.cc b/selfdrive/ui/android/sl_sound.cc similarity index 79% rename from selfdrive/ui/sound.cc rename to selfdrive/ui/android/sl_sound.cc index 79a8fd6e261d59..95cebab9c4d4a3 100644 --- a/selfdrive/ui/sound.cc +++ b/selfdrive/ui/android/sl_sound.cc @@ -1,35 +1,31 @@ - -#include "sound.hpp" #include #include #include #include "common/swaglog.h" #include "common/timing.h" +#include "android/sl_sound.hpp" + #define LogOnError(func, msg) \ if ((func) != SL_RESULT_SUCCESS) { LOGW(msg); } #define ReturnOnError(func, msg) \ if ((func) != SL_RESULT_SUCCESS) { LOGW(msg); return false; } -static std::map> sound_map { - {AudibleAlert::CHIME_DISENGAGE, {"../assets/sounds/disengaged.wav", 0}}, - {AudibleAlert::CHIME_ENGAGE, {"../assets/sounds/engaged.wav", 0}}, - {AudibleAlert::CHIME_WARNING1, {"../assets/sounds/warning_1.wav", 0}}, - {AudibleAlert::CHIME_WARNING2, {"../assets/sounds/warning_2.wav", 0}}, - {AudibleAlert::CHIME_WARNING2_REPEAT, {"../assets/sounds/warning_2.wav", 3}}, - {AudibleAlert::CHIME_WARNING_REPEAT, {"../assets/sounds/warning_repeat.wav", 3}}, - {AudibleAlert::CHIME_ERROR, {"../assets/sounds/error.wav", 0}}, - {AudibleAlert::CHIME_PROMPT, {"../assets/sounds/error.wav", 0}}}; - -struct Sound::Player { +struct SLSound::Player { SLObjectItf player; SLPlayItf playItf; // slplay_callback runs on a background thread,use atomic to ensure thread safe. std::atomic repeat; }; -bool Sound::init(int volume) { +SLSound::SLSound() { + if (!init()){ + throw std::runtime_error("Failed to initialize sound"); + } +} + +bool SLSound::init() { SLEngineOption engineOptions[] = {{SL_ENGINEOPTION_THREADSAFE, SL_BOOLEAN_TRUE}}; const SLInterfaceID ids[1] = {SL_IID_VOLUME}; const SLboolean req[1] = {SL_BOOLEAN_FALSE}; @@ -54,15 +50,13 @@ bool Sound::init(int volume) { ReturnOnError((*player)->GetInterface(player, SL_IID_PLAY, &playItf), "Failed to get player interface"); ReturnOnError((*playItf)->SetPlayState(playItf, SL_PLAYSTATE_PAUSED), "Failed to initialize playstate to SL_PLAYSTATE_PAUSED"); - player_[kv.first] = new Sound::Player{player, playItf}; + player_[kv.first] = new SLSound::Player{player, playItf}; } - - setVolume(volume); return true; } void SLAPIENTRY slplay_callback(SLPlayItf playItf, void *context, SLuint32 event) { - Sound::Player *s = reinterpret_cast(context); + SLSound::Player *s = reinterpret_cast(context); if (event == SL_PLAYEVENT_HEADATEND && s->repeat > 1) { --s->repeat; (*playItf)->SetPlayState(playItf, SL_PLAYSTATE_STOPPED); @@ -71,7 +65,7 @@ void SLAPIENTRY slplay_callback(SLPlayItf playItf, void *context, SLuint32 event } } -bool Sound::play(AudibleAlert alert) { +bool SLSound::play(AudibleAlert alert) { if (currentSound_ != AudibleAlert::NONE) { stop(); } @@ -93,7 +87,7 @@ bool Sound::play(AudibleAlert alert) { return true; } -void Sound::stop() { +void SLSound::stop() { if (currentSound_ != AudibleAlert::NONE) { auto player = player_.at(currentSound_); player->repeat = 0; @@ -102,9 +96,9 @@ void Sound::stop() { } } -void Sound::setVolume(int volume) { +void SLSound::setVolume(int volume) { if (last_volume_ == volume) return; - + double current_time = nanos_since_boot(); if ((current_time - last_set_volume_time_) > (5 * (1e+9))) { // 5s timeout on updating the volume char volume_change_cmd[64]; @@ -115,11 +109,15 @@ void Sound::setVolume(int volume) { } } -Sound::~Sound() { +SLSound::~SLSound() { for (auto &kv : player_) { (*(kv.second->player))->Destroy(kv.second->player); delete kv.second; } - if (outputMix_) (*outputMix_)->Destroy(outputMix_); - if (engine_) (*engine_)->Destroy(engine_); + if (outputMix_) { + (*outputMix_)->Destroy(outputMix_); + } + if (engine_) { + (*engine_)->Destroy(engine_); + } } diff --git a/selfdrive/ui/android/sl_sound.hpp b/selfdrive/ui/android/sl_sound.hpp new file mode 100644 index 00000000000000..7925277b9d80d3 --- /dev/null +++ b/selfdrive/ui/android/sl_sound.hpp @@ -0,0 +1,26 @@ +#pragma once +#include +#include + +#include "sound.hpp" + + +class SLSound : public Sound { +public: + SLSound(); + ~SLSound(); + bool play(AudibleAlert alert); + void stop(); + void setVolume(int volume); + +private: + bool init(); + SLObjectItf engine_ = nullptr; + SLObjectItf outputMix_ = nullptr; + int last_volume_ = 0; + double last_set_volume_time_ = 0.; + AudibleAlert currentSound_ = AudibleAlert::NONE; + struct Player; + std::map player_; + friend void SLAPIENTRY slplay_callback(SLPlayItf playItf, void *context, SLuint32 event); +}; diff --git a/selfdrive/ui/android/ui.cc b/selfdrive/ui/android/ui.cc new file mode 100644 index 00000000000000..e64ab6cded3541 --- /dev/null +++ b/selfdrive/ui/android/ui.cc @@ -0,0 +1,265 @@ +#include +#include +#include +#include + +#include "common/util.h" +#include "common/utilpp.h" +#include "common/params.h" +#include "common/touch.h" +#include "common/swaglog.h" + +#include "ui.hpp" +#include "paint.hpp" +#include "android/sl_sound.hpp" + +// Includes for light sensor +#include +#include +#include + +volatile sig_atomic_t do_exit = 0; +static void set_do_exit(int sig) { + do_exit = 1; +} + + +static void* light_sensor_thread(void *args) { + set_thread_name("light_sensor"); + + int err; + UIState *s = (UIState*)args; + s->light_sensor = 0.0; + + struct sensors_poll_device_t* device; + struct sensors_module_t* module; + + hw_get_module(SENSORS_HARDWARE_MODULE_ID, (hw_module_t const**)&module); + sensors_open(&module->common, &device); + + // need to do this + struct sensor_t const* list; + module->get_sensors_list(module, &list); + + int SENSOR_LIGHT = 7; + + err = device->activate(device, SENSOR_LIGHT, 0); + if (err != 0) goto fail; + err = device->activate(device, SENSOR_LIGHT, 1); + if (err != 0) goto fail; + + device->setDelay(device, SENSOR_LIGHT, ms2ns(100)); + + while (!do_exit) { + static const size_t numEvents = 1; + sensors_event_t buffer[numEvents]; + + int n = device->poll(device, buffer, numEvents); + if (n < 0) { + LOG_100("light_sensor_poll failed: %d", n); + } + if (n > 0) { + s->light_sensor = buffer[0].light; + } + } + sensors_close(device); + return NULL; + +fail: + LOGE("LIGHT SENSOR IS MISSING"); + s->light_sensor = 255; + + return NULL; +} + +static void ui_set_brightness(UIState *s, int brightness) { + static int last_brightness = -1; + if (last_brightness != brightness && (s->awake || brightness == 0)) { + if (set_brightness(brightness)) { + last_brightness = brightness; + } + } +} + +int event_processing_enabled = -1; +static void enable_event_processing(bool yes) { + if (event_processing_enabled != 1 && yes) { + system("service call window 18 i32 1"); // enable event processing + event_processing_enabled = 1; + } else if (event_processing_enabled != 0 && !yes) { + system("service call window 18 i32 0"); // disable event processing + event_processing_enabled = 0; + } +} + +static void set_awake(UIState *s, bool awake) { + if (awake) { + // 30 second timeout + s->awake_timeout = 30*UI_FREQ; + } + if (s->awake != awake) { + s->awake = awake; + + // TODO: replace command_awake and command_sleep with direct calls to android + if (awake) { + LOGW("awake normal"); + framebuffer_set_power(s->fb, HWC_POWER_MODE_NORMAL); + enable_event_processing(true); + } else { + LOGW("awake off"); + ui_set_brightness(s, 0); + framebuffer_set_power(s->fb, HWC_POWER_MODE_OFF); + enable_event_processing(false); + } + } +} + +static void handle_vision_touch(UIState *s, int touch_x, int touch_y) { + if (s->started && (touch_x >= s->scene.viz_rect.x - bdr_s) + && (s->active_app != cereal::UiLayoutState::App::SETTINGS)) { + if (!s->scene.frontview) { + s->scene.uilayout_sidebarcollapsed = !s->scene.uilayout_sidebarcollapsed; + } else { + write_db_value("IsDriverViewEnabled", "0", 1); + } + } +} + +static void handle_sidebar_touch(UIState *s, int touch_x, int touch_y) { + if (!s->scene.uilayout_sidebarcollapsed && touch_x <= sbr_w) { + if (settings_btn.ptInRect(touch_x, touch_y)) { + s->active_app = cereal::UiLayoutState::App::SETTINGS; + } else if (home_btn.ptInRect(touch_x, touch_y)) { + if (s->started) { + s->active_app = cereal::UiLayoutState::App::NONE; + s->scene.uilayout_sidebarcollapsed = true; + } else { + s->active_app = cereal::UiLayoutState::App::HOME; + } + } + } +} + +static void update_offroad_layout_state(UIState *s, PubMaster *pm) { + static int timeout = 0; + static bool prev_collapsed = false; + static cereal::UiLayoutState::App prev_app = cereal::UiLayoutState::App::NONE; + if (timeout > 0) { + timeout--; + } + if (prev_collapsed != s->scene.uilayout_sidebarcollapsed || prev_app != s->active_app || timeout == 0) { + MessageBuilder msg; + auto layout = msg.initEvent().initUiLayoutState(); + layout.setActiveApp(s->active_app); + layout.setSidebarCollapsed(s->scene.uilayout_sidebarcollapsed); + pm->send("offroadLayout", msg); + LOGD("setting active app to %d with sidebar %d", (int)s->active_app, s->scene.uilayout_sidebarcollapsed); + prev_collapsed = s->scene.uilayout_sidebarcollapsed; + prev_app = s->active_app; + timeout = 2 * UI_FREQ; + } +} + +int main(int argc, char* argv[]) { + int err; + setpriority(PRIO_PROCESS, 0, -14); + + signal(SIGINT, (sighandler_t)set_do_exit); + SLSound sound; + + UIState uistate = {}; + UIState *s = &uistate; + ui_init(s); + s->sound = &sound; + + set_awake(s, true); + enable_event_processing(true); + + PubMaster *pm = new PubMaster({"offroadLayout"}); + pthread_t light_sensor_thread_handle; + err = pthread_create(&light_sensor_thread_handle, NULL, + light_sensor_thread, s); + assert(err == 0); + + TouchState touch = {0}; + touch_init(&touch); + + // light sensor scaling and volume params + const bool LEON = util::read_file("/proc/cmdline").find("letv") != std::string::npos; + + float brightness_b = 0, brightness_m = 0; + int result = read_param(&brightness_b, "BRIGHTNESS_B", true); + result += read_param(&brightness_m, "BRIGHTNESS_M", true); + if(result != 0) { + brightness_b = LEON ? 10.0 : 5.0; + brightness_m = LEON ? 2.6 : 1.3; + write_param_float(brightness_b, "BRIGHTNESS_B", true); + write_param_float(brightness_m, "BRIGHTNESS_M", true); + } + float smooth_brightness = brightness_b; + + const int MIN_VOLUME = LEON ? 12 : 9; + const int MAX_VOLUME = LEON ? 15 : 12; + s->sound->setVolume(MIN_VOLUME); + + while (!do_exit) { + if (!s->started || !s->vision_connected) { + // Delay a while to avoid 9% cpu usage while car is not started and user is keeping touching on the screen. + usleep(30 * 1000); + } + double u1 = millis_since_boot(); + + ui_update(s); + + // poll for touch events + int touch_x = -1, touch_y = -1; + int touched = touch_poll(&touch, &touch_x, &touch_y, 0); + if (touched == 1) { + set_awake(s, true); + handle_sidebar_touch(s, touch_x, touch_y); + handle_vision_touch(s, touch_x, touch_y); + } + + // manage wakefulness + if (s->started || s->ignition) { + set_awake(s, true); + } + + if (s->awake_timeout > 0) { + s->awake_timeout--; + } else { + set_awake(s, false); + } + + // Don't waste resources on drawing in case screen is off + if (!s->awake) { + continue; + } + + // up one notch every 5 m/s + s->sound->setVolume(fmin(MAX_VOLUME, MIN_VOLUME + s->scene.controls_state.getVEgo() / 5)); + + // set brightness + float clipped_brightness = fmin(512, (s->light_sensor*brightness_m) + brightness_b); + smooth_brightness = fmin(255, clipped_brightness * 0.01 + smooth_brightness * 0.99); + ui_set_brightness(s, (int)smooth_brightness); + + update_offroad_layout_state(s, pm); + + ui_draw(s); + double u2 = millis_since_boot(); + if (!s->scene.frontview && (u2-u1 > 66)) { + // warn on sub 15fps + LOGW("slow frame(%llu) time: %.2f", (s->sm)->frame, u2-u1); + } + framebuffer_swap(s->fb); + } + + set_awake(s, true); + + err = pthread_join(light_sensor_thread_handle, NULL); + assert(err == 0); + delete s->sm; + delete pm; + return 0; +} diff --git a/selfdrive/ui/linux.cc b/selfdrive/ui/linux.cc deleted file mode 100644 index 5b370cc29f0612..00000000000000 --- a/selfdrive/ui/linux.cc +++ /dev/null @@ -1,107 +0,0 @@ -#include -#include -#include -#include -#include - -#include "ui.hpp" - -#ifndef __APPLE__ -#define GLFW_INCLUDE_ES2 -#else -#define GLFW_INCLUDE_GLCOREARB -#endif - -#define GLFW_INCLUDE_GLEXT -#include - -typedef struct FramebufferState FramebufferState; -typedef struct TouchState TouchState; - -extern "C" { - -FramebufferState* framebuffer_init( - const char* name, int32_t layer, int alpha, - int *out_w, int *out_h) { - glfwInit(); - -#ifndef __APPLE__ - glfwWindowHint(GLFW_CLIENT_API, GLFW_OPENGL_ES_API); - glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 3); - glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 0); -#else - glfwWindowHint(GLFW_OPENGL_FORWARD_COMPAT, GL_TRUE); - glfwWindowHint(GLFW_OPENGL_PROFILE, GLFW_OPENGL_CORE_PROFILE); - glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 3); - glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 2); -#endif - glfwWindowHint(GLFW_RESIZABLE, 0); - GLFWwindow* window; - window = glfwCreateWindow(1920, 1080, "ui", NULL, NULL); - if (!window) { - printf("glfwCreateWindow failed\n"); - } - - glfwMakeContextCurrent(window); - glfwSwapInterval(1); - - // clear screen - glClearColor(0.2f, 0.2f, 0.2f, 1.0f); - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - framebuffer_swap((FramebufferState*)window); - - if (out_w) *out_w = 1920; - if (out_h) *out_h = 1080; - - return (FramebufferState*)window; -} - -void framebuffer_set_power(FramebufferState *s, int mode) { -} - -void framebuffer_swap(FramebufferState *s) { - glfwSwapBuffers((GLFWwindow*)s); - glfwPollEvents(); -} - -bool set_brightness(int brightness) { return true; } - -void touch_init(TouchState *s) { - printf("touch_init\n"); -} - -int touch_poll(TouchState *s, int* out_x, int* out_y, int timeout) { - return -1; -} - -int touch_read(TouchState *s, int* out_x, int* out_y) { - return -1; -} - -} - -#include "sound.hpp" - -bool Sound::init(int volume) { return true; } -bool Sound::play(AudibleAlert alert) { printf("play sound: %d\n", (int)alert); return true; } -void Sound::stop() {} -void Sound::setVolume(int volume) {} -Sound::~Sound() {} - -#include "common/visionimg.h" -#include - -GLuint visionimg_to_gl(const VisionImg *img, EGLImageKHR *pkhr, void **pph) { - unsigned int texture; - glGenTextures(1, &texture); - glBindTexture(GL_TEXTURE_2D, texture); - glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, img->width, img->height, 0, GL_RGB, GL_UNSIGNED_BYTE, *pph); - glGenerateMipmap(GL_TEXTURE_2D); - *pkhr = (EGLImageKHR)1; // not NULL - return texture; -} - -void visionimg_destroy_gl(EGLImageKHR khr, void *ph) { - // empty -} - diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 8802526cb8d05d..881074d8f3fb16 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -2,10 +2,10 @@ #include #include #include +#include #include "common/util.h" #define NANOVG_GLES3_IMPLEMENTATION - #include "nanovg_gl.h" #include "nanovg_gl_utils.h" @@ -13,15 +13,27 @@ extern "C"{ #include "common/glutil.h" } +#include "paint.hpp" +#include "sidebar.hpp" + // TODO: this is also hardcoded in common/transformations/camera.py +// TODO: choose based on frame input size +#ifdef QCOM2 +const mat3 intrinsic_matrix = (mat3){{ + 2648.0, 0.0, 1928.0/2, + 0.0, 2648.0, 1208.0/2, + 0.0, 0.0, 1.0 +}}; +#else const mat3 intrinsic_matrix = (mat3){{ 910., 0., 582., 0., 910., 437., 0., 0., 1. }}; +#endif const uint8_t alert_colors[][4] = { - [STATUS_STOPPED] = {0x07, 0x23, 0x39, 0xf1}, + [STATUS_OFFROAD] = {0x07, 0x23, 0x39, 0xf1}, [STATUS_DISENGAGED] = {0x17, 0x33, 0x49, 0xc8}, [STATUS_ENGAGED] = {0x17, 0x86, 0x44, 0xf1}, [STATUS_WARNING] = {0xDA, 0x6F, 0x25, 0xf1}, @@ -142,7 +154,7 @@ static void ui_draw_lane_line(UIState *s, const model_path_vertices_data *pvd, N static void update_track_data(UIState *s, bool is_mpc, track_vertices_data *pvd) { const UIScene *scene = &s->scene; - const PathData path = scene->model.path; + const float *points = scene->path_points; const float *mpc_x_coords = &scene->mpc_x[0]; const float *mpc_y_coords = &scene->mpc_y[0]; @@ -150,6 +162,7 @@ static void update_track_data(UIState *s, bool is_mpc, track_vertices_data *pvd) float lead_d = scene->lead_data[0].getDRel()*2.; float path_height = is_mpc?(lead_d>5.)?fmin(lead_d, 25.)-fmin(lead_d*0.35, 10.):20. :(lead_d>0.)?fmin(lead_d, 50.)-fmin(lead_d*0.35, 10.):49.; + path_height = fmin(path_height, scene->model.getPath().getValidLen()); pvd->cnt = 0; // left side up for (int i=0; i<=path_height; i++) { @@ -160,7 +173,7 @@ static void update_track_data(UIState *s, bool is_mpc, track_vertices_data *pvd) py = mpc_y_coords[i] - off; } else { px = lerp(i+1.0, i, i/100.0); - py = path.points[i] - off; + py = points[i] - off; } vec4 p_car_space = (vec4){{px, py, 0., 1.}}; @@ -182,11 +195,14 @@ static void update_track_data(UIState *s, bool is_mpc, track_vertices_data *pvd) py = mpc_y_coords[i] + off; } else { px = lerp(i+1.0, i, i/100.0); - py = path.points[i] + off; + py = points[i] + off; } vec4 p_car_space = (vec4){{px, py, 0., 1.}}; vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); + if (p_full_frame.v[0] < 0. || p_full_frame.v[1] < 0.) { + continue; + } pvd->v[pvd->cnt].x = p_full_frame.v[0]; pvd->v[pvd->cnt].y = p_full_frame.v[1]; pvd->cnt += 1; @@ -204,7 +220,6 @@ static void update_all_track_data(UIState *s) { } } - static void ui_draw_track(UIState *s, bool is_mpc, track_vertices_data *pvd) { if (pvd->cnt == 0) return; @@ -218,12 +233,12 @@ static void ui_draw_track(UIState *s, bool is_mpc, track_vertices_data *pvd) { NVGpaint track_bg; if (is_mpc) { // Draw colored MPC track - const uint8_t *clr = bg_colors[s->status]; - track_bg = nvgLinearGradient(s->vg, vwp_w, vwp_h, vwp_w, vwp_h*.4, - nvgRGBA(clr[0], clr[1], clr[2], 255), nvgRGBA(clr[0], clr[1], clr[2], 255/2)); + const Color clr = bg_colors[s->status]; + track_bg = nvgLinearGradient(s->vg, s->fb_w, s->fb_h, s->fb_w, s->fb_h*.4, + nvgRGBA(clr.r, clr.g, clr.b, 255), nvgRGBA(clr.r, clr.g, clr.b, 255/2)); } else { // Draw white vision track - track_bg = nvgLinearGradient(s->vg, vwp_w, vwp_h, vwp_w, vwp_h*.4, + track_bg = nvgLinearGradient(s->vg, s->fb_w, s->fb_h, s->fb_w, s->fb_h*.4, COLOR_WHITE, COLOR_WHITE_ALPHA(0)); } nvgFillPaint(s->vg, track_bg); @@ -231,30 +246,23 @@ static void ui_draw_track(UIState *s, bool is_mpc, track_vertices_data *pvd) { } static void draw_frame(UIState *s) { - const UIScene *scene = &s->scene; - + mat4 *out_mat; if (s->scene.frontview) { glBindVertexArray(s->frame_vao[1]); - } else { - glBindVertexArray(s->frame_vao[0]); - } - - mat4 *out_mat; - if (s->scene.frontview || s->scene.fullview) { out_mat = &s->front_frame_mat; } else { + glBindVertexArray(s->frame_vao[0]); out_mat = &s->rear_frame_mat; } glActiveTexture(GL_TEXTURE0); - if (s->scene.frontview && s->cur_vision_front_idx >= 0) { - glBindTexture(GL_TEXTURE_2D, s->frame_front_texs[s->cur_vision_front_idx]); - } else if (!scene->frontview && s->cur_vision_idx >= 0) { - glBindTexture(GL_TEXTURE_2D, s->frame_texs[s->cur_vision_idx]); - #ifndef QCOM - // TODO: a better way to do this? - //printf("%d\n", ((int*)s->priv_hnds[s->cur_vision_idx])[0]); - glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, 1164, 874, 0, GL_RGB, GL_UNSIGNED_BYTE, s->priv_hnds[s->cur_vision_idx]); - #endif + + if (s->stream.last_idx >= 0) { + glBindTexture(GL_TEXTURE_2D, s->frame_texs[s->stream.last_idx]); +#ifndef QCOM + // this is handled in ion on QCOM + glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, s->stream.bufs_info.width, s->stream.bufs_info.height, + 0, GL_RGB, GL_UNSIGNED_BYTE, s->priv_hnds[s->stream.last_idx]); +#endif } glUseProgram(s->frame_program); @@ -269,9 +277,9 @@ static void draw_frame(UIState *s) { } static inline bool valid_frame_pt(UIState *s, float x, float y) { - return x >= 0 && x <= s->rgb_width && y >= 0 && y <= s->rgb_height; - + return x >= 0 && x <= s->stream.bufs_info.width && y >= 0 && y <= s->stream.bufs_info.height; } + static void update_lane_line_data(UIState *s, const float *points, float off, model_path_vertices_data *pvd, float valid_len) { pvd->cnt = 0; int rcount = fmin(MODEL_PATH_MAX_VERTICES_CNT / 2, valid_len); @@ -286,7 +294,7 @@ static void update_lane_line_data(UIState *s, const float *points, float off, mo pvd->v[pvd->cnt].y = p_full_frame.v[1]; pvd->cnt += 1; } - for (int i = rcount; i > 0; i--) { + for (int i = rcount - 1; i > 0; i--) { float px = (float)i; float py = points[i] + off; const vec4 p_car_space = (vec4){{px, py, 0., 1.}}; @@ -299,42 +307,35 @@ static void update_lane_line_data(UIState *s, const float *points, float off, mo } } -static void update_all_lane_lines_data(UIState *s, const PathData &path, model_path_vertices_data *pstart) { - update_lane_line_data(s, path.points, 0.025*path.prob, pstart, path.validLen); - float var = fmin(path.std, 0.7); - update_lane_line_data(s, path.points, -var, pstart + 1, path.validLen); - update_lane_line_data(s, path.points, var, pstart + 2, path.validLen); +static void update_all_lane_lines_data(UIState *s, const cereal::ModelData::PathData::Reader &path, const float *points, model_path_vertices_data *pstart) { + update_lane_line_data(s, points, 0.025*path.getProb(), pstart, path.getValidLen()); + update_lane_line_data(s, points, fmin(path.getStd(), 0.7), pstart + 1, path.getValidLen()); } -static void ui_draw_lane(UIState *s, const PathData *path, model_path_vertices_data *pstart, NVGcolor color) { +static void ui_draw_lane(UIState *s, model_path_vertices_data *pstart, NVGcolor color) { ui_draw_lane_line(s, pstart, color); color.a /= 25; ui_draw_lane_line(s, pstart + 1, color); - ui_draw_lane_line(s, pstart + 2, color); } static void ui_draw_vision_lanes(UIState *s) { const UIScene *scene = &s->scene; model_path_vertices_data *pvd = &s->model_path_vertices[0]; if(s->sm->updated("model")) { - update_all_lane_lines_data(s, scene->model.left_lane, pvd); - update_all_lane_lines_data(s, scene->model.right_lane, pvd + MODEL_LANE_PATH_CNT); + update_all_lane_lines_data(s, scene->model.getLeftLane(), scene->left_lane_points, pvd); + update_all_lane_lines_data(s, scene->model.getRightLane(), scene->right_lane_points, pvd + MODEL_LANE_PATH_CNT); } + // Draw left lane edge - ui_draw_lane( - s, &scene->model.left_lane, - pvd, - nvgRGBAf(1.0, 1.0, 1.0, scene->model.left_lane.prob)); + ui_draw_lane(s, pvd, nvgRGBAf(1.0, 1.0, 1.0, scene->model.getLeftLane().getProb())); // Draw right lane edge - ui_draw_lane( - s, &scene->model.right_lane, - pvd + MODEL_LANE_PATH_CNT, - nvgRGBAf(1.0, 1.0, 1.0, scene->model.right_lane.prob)); + ui_draw_lane(s, pvd + MODEL_LANE_PATH_CNT, nvgRGBAf(1.0, 1.0, 1.0, scene->model.getRightLane().getProb())); if(s->sm->updated("radarState")) { update_all_track_data(s); } + // Draw vision path ui_draw_track(s, false, &s->track_vertices[0]); if (scene->controls_state.getEnabled()) { @@ -346,24 +347,21 @@ static void ui_draw_vision_lanes(UIState *s) { // Draw all world space objects. static void ui_draw_world(UIState *s) { const UIScene *scene = &s->scene; - if (!scene->world_objects_visible) { - return; - } - - const int inner_height = viz_w*9/16; - const int ui_viz_rx = scene->ui_viz_rx; - const int ui_viz_rw = scene->ui_viz_rw; - const int ui_viz_ro = scene->ui_viz_ro; - + const Rect &viz_rect = scene->viz_rect; + const int viz_w = s->fb_w - bdr_s * 2; + const int inner_height = float(viz_w) * s->fb_h / s->fb_w; nvgSave(s->vg); - nvgScissor(s->vg, ui_viz_rx, box_y, ui_viz_rw, box_h); + nvgScissor(s->vg, viz_rect.x, viz_rect.y, viz_rect.w, viz_rect.h); - nvgTranslate(s->vg, ui_viz_rx+ui_viz_ro, box_y + (box_h-inner_height)/2.0); + nvgTranslate(s->vg, viz_rect.x+scene->ui_viz_ro, viz_rect.y + (viz_rect.h-inner_height)/2.0); nvgScale(s->vg, (float)viz_w / s->fb_w, (float)inner_height / s->fb_h); - nvgTranslate(s->vg, 240.0f, 0.0); - nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); + + float w = 1440.0f; // Why 1440? + nvgTranslate(s->vg, (s->fb_w - w) / 2.0f, 0.0); + + nvgTranslate(s->vg, -w / 2, -1080.0f / 2); nvgScale(s->vg, 2.0, 2.0); - nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + nvgScale(s->vg, w / s->stream.bufs_info.width, 1080.0f / s->stream.bufs_info.height); // Draw lane edges and vision/mpc tracks ui_draw_vision_lanes(s); @@ -381,51 +379,28 @@ static void ui_draw_world(UIState *s) { } static void ui_draw_vision_maxspeed(UIState *s) { - /*if (!s->longitudinal_control){ - return; - }*/ char maxspeed_str[32]; float maxspeed = s->scene.controls_state.getVCruise(); int maxspeed_calc = maxspeed * 0.6225 + 0.5; - float speedlimit = s->scene.speedlimit; - int speedlim_calc = speedlimit * 2.2369363 + 0.5; - int speed_lim_off = s->speed_lim_off * 2.2369363 + 0.5; if (s->is_metric) { maxspeed_calc = maxspeed + 0.5; - speedlim_calc = speedlimit * 3.6 + 0.5; - speed_lim_off = s->speed_lim_off * 3.6 + 0.5; } bool is_cruise_set = (maxspeed != 0 && maxspeed != SET_SPEED_NA); - bool is_speedlim_valid = s->scene.speedlimit_valid; - bool is_set_over_limit = is_speedlim_valid && s->scene.controls_state.getEnabled() && - is_cruise_set && maxspeed_calc > (speedlim_calc + speed_lim_off); int viz_maxspeed_w = 184; int viz_maxspeed_h = 202; - int viz_maxspeed_x = (s->scene.ui_viz_rx + (bdr_s*2)); - int viz_maxspeed_y = (box_y + (bdr_s*1.5)); + int viz_maxspeed_x = s->scene.viz_rect.x + (bdr_s*2); + int viz_maxspeed_y = s->scene.viz_rect.y + (bdr_s*1.5); int viz_maxspeed_xo = 180; -#ifdef SHOW_SPEEDLIMIT - viz_maxspeed_w += viz_maxspeed_xo; - viz_maxspeed_x += viz_maxspeed_w - (viz_maxspeed_xo * 2); -#else viz_maxspeed_xo = 0; -#endif // Draw Background - ui_draw_rect(s->vg, viz_maxspeed_x, viz_maxspeed_y, viz_maxspeed_w, viz_maxspeed_h, - is_set_over_limit ? nvgRGBA(218, 111, 37, 180) : COLOR_BLACK_ALPHA(100), 30); + ui_draw_rect(s->vg, viz_maxspeed_x, viz_maxspeed_y, viz_maxspeed_w, viz_maxspeed_h, COLOR_BLACK_ALPHA(100), 30); // Draw Border NVGcolor color = COLOR_WHITE_ALPHA(100); - if (is_set_over_limit) { - color = COLOR_OCHRE; - } else if (is_speedlim_valid) { - color = s->is_ego_over_limit ? COLOR_WHITE_ALPHA(20) : COLOR_WHITE; - } - ui_draw_rect(s->vg, viz_maxspeed_x, viz_maxspeed_y, viz_maxspeed_w, viz_maxspeed_h, color, 20, 10); nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); @@ -440,89 +415,30 @@ static void ui_draw_vision_maxspeed(UIState *s) { } } -#ifdef SHOW_SPEEDLIMIT -static void ui_draw_vision_speedlimit(UIState *s) { - char speedlim_str[32]; - float speedlimit = s->scene.speedlimit; - int speedlim_calc = speedlimit * 2.2369363 + 0.5; - if (s->is_metric) { - speedlim_calc = speedlimit * 3.6 + 0.5; - } - - bool is_speedlim_valid = s->scene.speedlimit_valid; - float hysteresis_offset = 0.5; - if (s->is_ego_over_limit) { - hysteresis_offset = 0.0; - } - s->is_ego_over_limit = is_speedlim_valid && s->scene.controls_state.getVEgo() > (speedlimit + s->speed_lim_off + hysteresis_offset); - - int viz_speedlim_w = 180; - int viz_speedlim_h = 202; - int viz_speedlim_x = (s->scene.ui_viz_rx + (bdr_s*2)); - int viz_speedlim_y = (box_y + (bdr_s*1.5)); - if (!is_speedlim_valid) { - viz_speedlim_w -= 5; - viz_speedlim_h -= 10; - viz_speedlim_x += 9; - viz_speedlim_y += 5; - } - // Draw Background - NVGcolor color = COLOR_WHITE_ALPHA(100); - if (is_speedlim_valid && s->is_ego_over_limit) { - color = nvgRGBA(218, 111, 37, 180); - } else if (is_speedlim_valid) { - color = COLOR_WHITE; - } - ui_draw_rect(s->vg, viz_speedlim_x, viz_speedlim_y, viz_speedlim_w, viz_speedlim_h, color, is_speedlim_valid ? 30 : 15); - - // Draw Border - if (is_speedlim_valid) { - ui_draw_rect(s->vg, viz_speedlim_x, viz_speedlim_y, viz_speedlim_w, viz_speedlim_h, - s->is_ego_over_limit ? COLOR_OCHRE : COLOR_WHITE, 20, 10); - } - const float text_x = viz_speedlim_x + viz_speedlim_w / 2; - const float text_y = viz_speedlim_y + (is_speedlim_valid ? 50 : 45); - // Draw "Speed Limit" Text - nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); - color = is_speedlim_valid && s->is_ego_over_limit ? COLOR_WHITE : COLOR_BLACK; - ui_draw_text(s->vg, text_x + (is_speedlim_valid ? 6 : 0), text_y, "SMART", 50, color, s->font_sans_semibold); - ui_draw_text(s->vg, text_x + (is_speedlim_valid ? 6 : 0), text_y + 40, "SPEED", 50, color, s->font_sans_semibold); - - // Draw Speed Text - color = s->is_ego_over_limit ? COLOR_WHITE : COLOR_BLACK; - if (is_speedlim_valid) { - snprintf(speedlim_str, sizeof(speedlim_str), "%d", speedlim_calc); - ui_draw_text(s->vg, text_x, viz_speedlim_y + (is_speedlim_valid ? 170 : 165), speedlim_str, 48*2.5, color, s->font_sans_bold); - } else { - ui_draw_text(s->vg, text_x, viz_speedlim_y + (is_speedlim_valid ? 170 : 165), "N/A", 42*2.5, color, s->font_sans_semibold); - } -} -#endif - static void ui_draw_vision_speed(UIState *s) { - const UIScene *scene = &s->scene; + const Rect &viz_rect = s->scene.viz_rect; float v_ego = s->scene.controls_state.getVEgo(); float speed = v_ego * 2.2369363 + 0.5; if (s->is_metric){ speed = v_ego * 3.6 + 0.5; } const int viz_speed_w = 280; - const int viz_speed_x = scene->ui_viz_rx+((scene->ui_viz_rw/2)-(viz_speed_w/2)); + const int viz_speed_x = viz_rect.centerX() - viz_speed_w/2; char speed_str[32]; nvgBeginPath(s->vg); - nvgRect(s->vg, viz_speed_x, box_y, viz_speed_w, header_h); + nvgRect(s->vg, viz_speed_x, viz_rect.y, viz_speed_w, header_h); nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); snprintf(speed_str, sizeof(speed_str), "%d", (int)speed); - ui_draw_text(s->vg, viz_speed_x + viz_speed_w / 2, 240, speed_str, 96*2.5, COLOR_WHITE, s->font_sans_bold); - ui_draw_text(s->vg, viz_speed_x + viz_speed_w / 2, 320, s->is_metric?"kph":"mph", 36*2.5, COLOR_WHITE_ALPHA(200), s->font_sans_regular); + ui_draw_text(s->vg, viz_rect.centerX(), 240, speed_str, 96*2.5, COLOR_WHITE, s->font_sans_bold); + ui_draw_text(s->vg, viz_rect.centerX(), 320, s->is_metric?"km/h":"mph", 36*2.5, COLOR_WHITE_ALPHA(200), s->font_sans_regular); } static void ui_draw_vision_event(UIState *s) { const int viz_event_w = 220; - const int viz_event_x = ((s->scene.ui_viz_rx + s->scene.ui_viz_rw) - (viz_event_w + (bdr_s*2))); - const int viz_event_y = (box_y + (bdr_s*1.5)); + const int viz_event_x = s->scene.viz_rect.right() - (viz_event_w + bdr_s*2); + const int viz_event_y = s->scene.viz_rect.y + (bdr_s*1.5); if (s->scene.controls_state.getDecelForModel() && s->scene.controls_state.getEnabled()) { // draw winding road sign const int img_turn_size = 160*1.5; @@ -547,28 +463,23 @@ static void ui_draw_vision_event(UIState *s) { } } -#ifdef SHOW_SPEEDLIMIT -static void ui_draw_vision_map(UIState *s) { - const int map_size = 96; - const int map_x = (s->scene.ui_viz_rx + (map_size * 3) + (bdr_s * 3)); - const int map_y = (footer_y + ((footer_h - map_size) / 2)); - ui_draw_circle_image(s->vg, map_x, map_y, map_size, s->img_map, s->scene.map_valid); -} -#endif - static void ui_draw_vision_face(UIState *s) { const int face_size = 96; - const int face_x = (s->scene.ui_viz_rx + face_size + (bdr_s * 2)); - const int face_y = (footer_y + ((footer_h - face_size) / 2)); + const int face_x = (s->scene.viz_rect.x + face_size + (bdr_s * 2)); + const int face_y = (s->scene.viz_rect.bottom() - footer_h + ((footer_h - face_size) / 2)); ui_draw_circle_image(s->vg, face_x, face_y, face_size, s->img_face, s->scene.dmonitoring_state.getFaceDetected()); } static void ui_draw_driver_view(UIState *s) { const UIScene *scene = &s->scene; s->scene.uilayout_sidebarcollapsed = true; - const int frame_x = scene->ui_viz_rx; - const int frame_w = scene->ui_viz_rw; - const int valid_frame_w = 4 * box_h / 3; + const Rect &viz_rect = s->scene.viz_rect; + const int ff_xoffset = 32; + const int frame_x = viz_rect.x; + const int frame_w = viz_rect.w; + const int valid_frame_w = 4 * viz_rect.h / 3; + const int box_y = viz_rect.y; + const int box_h = viz_rect.h; const int valid_frame_x = frame_x + (frame_w - valid_frame_w) / 2 + ff_xoffset; // blackout @@ -613,34 +524,21 @@ static void ui_draw_driver_view(UIState *s) { } static void ui_draw_vision_header(UIState *s) { - const UIScene *scene = &s->scene; - int ui_viz_rx = scene->ui_viz_rx; - int ui_viz_rw = scene->ui_viz_rw; - - NVGpaint gradient = nvgLinearGradient(s->vg, ui_viz_rx, - (box_y+(header_h-(header_h/2.5))), - ui_viz_rx, box_y+header_h, + const Rect &viz_rect = s->scene.viz_rect; + NVGpaint gradient = nvgLinearGradient(s->vg, viz_rect.x, + viz_rect.y+(header_h-(header_h/2.5)), + viz_rect.x, viz_rect.y+header_h, nvgRGBAf(0,0,0,0.45), nvgRGBAf(0,0,0,0)); - ui_draw_rect(s->vg, ui_viz_rx, box_y, ui_viz_rw, header_h, gradient); - ui_draw_vision_maxspeed(s); + ui_draw_rect(s->vg, viz_rect.x, viz_rect.y, viz_rect.w, header_h, gradient); -#ifdef SHOW_SPEEDLIMIT - ui_draw_vision_speedlimit(s); -#endif + ui_draw_vision_maxspeed(s); ui_draw_vision_speed(s); ui_draw_vision_event(s); } static void ui_draw_vision_footer(UIState *s) { - nvgBeginPath(s->vg); - nvgRect(s->vg, s->scene.ui_viz_rx, footer_y, s->scene.ui_viz_rw, footer_h); - ui_draw_vision_face(s); - -#ifdef SHOW_SPEEDLIMIT - // ui_draw_vision_map(s); -#endif } void ui_draw_vision_alert(UIState *s, cereal::ControlsState::AlertSize va_size, int va_color, @@ -649,20 +547,18 @@ void ui_draw_vision_alert(UIState *s, cereal::ControlsState::AlertSize va_size, {cereal::ControlsState::AlertSize::NONE, 0}, {cereal::ControlsState::AlertSize::SMALL, 241}, {cereal::ControlsState::AlertSize::MID, 390}, - {cereal::ControlsState::AlertSize::FULL, vwp_h}}; + {cereal::ControlsState::AlertSize::FULL, s->fb_h}}; const UIScene *scene = &s->scene; - const bool hasSidebar = !scene->uilayout_sidebarcollapsed; - const bool mapEnabled = scene->uilayout_mapenabled; bool longAlert1 = strlen(va_text1) > 15; const uint8_t *color = alert_colors[va_color]; int alr_s = alert_size_map[va_size]; - const int alr_x = scene->ui_viz_rx-(mapEnabled?(hasSidebar?nav_w:(nav_ww)):0)-bdr_s; - const int alr_w = scene->ui_viz_rw+(mapEnabled?(hasSidebar?nav_w:(nav_ww)):0)+(bdr_s*2); + const int alr_x = scene->viz_rect.x - bdr_s; + const int alr_w = scene->viz_rect.w + (bdr_s*2); const int alr_h = alr_s+(va_size==cereal::ControlsState::AlertSize::NONE?0:bdr_s); - const int alr_y = vwp_h-alr_h; + const int alr_y = s->fb_h-alr_h; ui_draw_rect(s->vg, alr_x, alr_y, alr_w, alr_h, nvgRGBA(color[0],color[1],color[2],(color[3]*s->alert_blinking_alpha))); @@ -692,21 +588,20 @@ void ui_draw_vision_alert(UIState *s, cereal::ControlsState::AlertSize va_size, static void ui_draw_vision(UIState *s) { const UIScene *scene = &s->scene; - + const Rect &viz_rect = scene->viz_rect; // Draw video frames glEnable(GL_SCISSOR_TEST); - glViewport(scene->ui_viz_rx+scene->ui_viz_ro, s->fb_h-(box_y+box_h), viz_w, box_h); - glScissor(scene->ui_viz_rx, s->fb_h-(box_y+box_h), scene->ui_viz_rw, box_h); + glViewport(viz_rect.x+scene->ui_viz_ro, viz_rect.y, s->fb_w - bdr_s*2, viz_rect.h); + glScissor(viz_rect.x, viz_rect.y, viz_rect.w, viz_rect.h); draw_frame(s); glDisable(GL_SCISSOR_TEST); glViewport(0, 0, s->fb_w, s->fb_h); // Draw augmented elements - if (!scene->frontview && !scene->fullview) { + if (!scene->frontview && scene->world_objects_visible) { ui_draw_world(s); } - // Set Speed, Current Speed, Status/Events if (!scene->frontview) { ui_draw_vision_header(s); @@ -715,31 +610,36 @@ static void ui_draw_vision(UIState *s) { } if (scene->alert_size != cereal::ControlsState::AlertSize::NONE) { - // Controls Alerts ui_draw_vision_alert(s, scene->alert_size, s->status, - scene->alert_text1.c_str(), scene->alert_text2.c_str()); - } else { - if (!scene->frontview){ui_draw_vision_footer(s);} + scene->alert_text1.c_str(), scene->alert_text2.c_str()); + } else if (!scene->frontview) { + ui_draw_vision_footer(s); } } static void ui_draw_background(UIState *s) { - int bg_status = s->status; - assert(bg_status < ARRAYSIZE(bg_colors)); - const uint8_t *color = bg_colors[bg_status]; - - glClearColor(color[0]/256.0, color[1]/256.0, color[2]/256.0, 1.0); + const Color color = bg_colors[s->status]; + glClearColor(color.r/256.0, color.g/256.0, color.b/256.0, 1.0); glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); } void ui_draw(UIState *s) { + s->scene.viz_rect = Rect{bdr_s * 3, bdr_s, s->fb_w - 4 * bdr_s, s->fb_h - 2 * bdr_s}; + s->scene.ui_viz_ro = 0; + if (!s->scene.uilayout_sidebarcollapsed) { + s->scene.viz_rect.x = sbr_w + bdr_s; + s->scene.viz_rect.w = s->fb_w - s->scene.viz_rect.x - bdr_s; + s->scene.ui_viz_ro = -(sbr_w - 6 * bdr_s); + } + ui_draw_background(s); glEnable(GL_BLEND); glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); glViewport(0, 0, s->fb_w, s->fb_h); nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); ui_draw_sidebar(s); - if (s->started && s->active_app == cereal::UiLayoutState::App::NONE && s->status != STATUS_STOPPED && s->vision_seen) { + if (s->started && s->active_app == cereal::UiLayoutState::App::NONE && + s->status != STATUS_OFFROAD && s->vision_connected) { ui_draw_vision(s); } nvgEndFrame(s->vg); @@ -774,9 +674,12 @@ void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint & nvgFill(vg); } -#ifdef NANOVG_GL3_IMPLEMENTATION static const char frame_vertex_shader[] = +#ifdef NANOVG_GL3_IMPLEMENTATION "#version 150 core\n" +#else + "#version 300 es\n" +#endif "in vec4 aPosition;\n" "in vec4 aTexCoord;\n" "uniform mat4 uTransform;\n" @@ -787,7 +690,11 @@ static const char frame_vertex_shader[] = "}\n"; static const char frame_fragment_shader[] = +#ifdef NANOVG_GL3_IMPLEMENTATION "#version 150 core\n" +#else + "#version 300 es\n" +#endif "precision mediump float;\n" "uniform sampler2D uTexture;\n" "in vec4 vTexCoord;\n" @@ -795,25 +702,6 @@ static const char frame_fragment_shader[] = "void main() {\n" " colorOut = texture(uTexture, vTexCoord.xy);\n" "}\n"; -#else -static const char frame_vertex_shader[] = - "attribute vec4 aPosition;\n" - "attribute vec4 aTexCoord;\n" - "uniform mat4 uTransform;\n" - "varying vec4 vTexCoord;\n" - "void main() {\n" - " gl_Position = uTransform * aPosition;\n" - " vTexCoord = aTexCoord;\n" - "}\n"; - -static const char frame_fragment_shader[] = - "precision mediump float;\n" - "uniform sampler2D uTexture;\n" - "varying vec4 vTexCoord;\n" - "void main() {\n" - " gl_FragColor = texture2D(uTexture, vTexCoord.xy);\n" - "}\n"; -#endif static const mat4 device_transform = {{ 1.0, 0.0, 0.0, 0.0, @@ -822,14 +710,6 @@ static const mat4 device_transform = {{ 0.0, 0.0, 0.0, 1.0, }}; -// frame from 4/3 to box size with a 2x zoom -static const mat4 frame_transform = {{ - 2*(4./3.)/((float)viz_w/box_h), 0.0, 0.0, 0.0, - 0.0, 2.0, 0.0, 0.0, - 0.0, 0.0, 1.0, 0.0, - 0.0, 0.0, 0.0, 1.0, -}}; - // frame from 4/3 to 16/9 display static const mat4 full_to_wide_frame_transform = {{ .75, 0.0, 0.0, 0.0, @@ -862,8 +742,6 @@ void ui_nvg_init(UIState *s) { assert(s->img_turn != 0); s->img_face = nvgCreateImage(s->vg, "../assets/img_driver_face.png", 1); assert(s->img_face != 0); - s->img_map = nvgCreateImage(s->vg, "../assets/img_map.png", 1); - assert(s->img_map != 0); s->img_button_settings = nvgCreateImage(s->vg, "../assets/images/button_settings.png", 1); assert(s->img_button_settings != 0); s->img_button_home = nvgCreateImage(s->vg, "../assets/images/button_home.png", 1); @@ -918,7 +796,7 @@ void ui_nvg_init(UIState *s) { { 1.0, -1.0, x1, y1}, //br }; - glGenVertexArrays(1,&s->frame_vao[i]); + glGenVertexArrays(1, &s->frame_vao[i]); glBindVertexArray(s->frame_vao[i]); glGenBuffers(1, &s->frame_vbo[i]); glBindBuffer(GL_ARRAY_BUFFER, s->frame_vbo[i]); @@ -936,13 +814,19 @@ void ui_nvg_init(UIState *s) { glBindVertexArray(0); } + // frame from 4/3 to box size with a 2x zoom + const mat4 frame_transform = {{ + (float)(2*(4./3.)/((float)(s->fb_w-(bdr_s*2))/(s->fb_h-(bdr_s*2)))), 0.0, 0.0, 0.0, + 0.0, 2.0, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, + }}; + s->front_frame_mat = matmul(device_transform, full_to_wide_frame_transform); s->rear_frame_mat = matmul(device_transform, frame_transform); - for(int i = 0;i < UI_BUF_COUNT; i++) { + for(int i = 0; i < UI_BUF_COUNT; i++) { s->khr[i] = 0; s->priv_hnds[i] = NULL; - s->khr_front[i] = 0; - s->priv_hnds_front[i] = NULL; } } diff --git a/selfdrive/ui/paint.hpp b/selfdrive/ui/paint.hpp new file mode 100644 index 00000000000000..e71a2a43ec87f0 --- /dev/null +++ b/selfdrive/ui/paint.hpp @@ -0,0 +1,11 @@ +#pragma once +#include "ui.hpp" + + +void ui_draw_vision_alert(UIState *s, cereal::ControlsState::AlertSize va_size, int va_color, + const char* va_text1, const char* va_text2); +void ui_draw(UIState *s); +void ui_draw_image(NVGcontext *vg, float x, float y, float w, float h, int image, float alpha); +void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGcolor color, float r = 0, int width = 0); +void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint &paint, float r = 0); +void ui_nvg_init(UIState *s); diff --git a/selfdrive/ui/qt/qt_sound.cc b/selfdrive/ui/qt/qt_sound.cc new file mode 100644 index 00000000000000..76842c67efccee --- /dev/null +++ b/selfdrive/ui/qt/qt_sound.cc @@ -0,0 +1,30 @@ +#include +#include "qt/qt_sound.hpp" + +QtSound::QtSound() { + for (auto &kv : sound_map) { + auto path = QUrl::fromLocalFile(kv.second.first); + sounds[kv.first].setSource(path); + } +} + +bool QtSound::play(AudibleAlert alert) { + sounds[alert].setLoopCount(sound_map[alert].second); + sounds[alert].setVolume(0.9); + sounds[alert].play(); + return true; +} + +void QtSound::stop() { + for (auto &kv : sounds) { + kv.second.stop(); + } +} + +void QtSound::setVolume(int volume) { + // TODO: implement this +} + +QtSound::~QtSound() { + +} diff --git a/selfdrive/ui/qt/qt_sound.hpp b/selfdrive/ui/qt/qt_sound.hpp new file mode 100644 index 00000000000000..c2aab2de446ff3 --- /dev/null +++ b/selfdrive/ui/qt/qt_sound.hpp @@ -0,0 +1,16 @@ +#pragma once + +#include +#include "sound.hpp" + +class QtSound : public Sound { +public: + QtSound(); + ~QtSound(); + bool play(AudibleAlert alert); + void stop(); + void setVolume(int volume); + +private: + std::map sounds; +}; diff --git a/selfdrive/ui/qt/settings.cc b/selfdrive/ui/qt/settings.cc new file mode 100644 index 00000000000000..612fe2af364588 --- /dev/null +++ b/selfdrive/ui/qt/settings.cc @@ -0,0 +1,140 @@ +#include +#include +#include +#include + +#include "qt/settings.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/params.h" + +ParamsToggle::ParamsToggle(QString param, QString title, QString description, QString icon_path, QWidget *parent): QFrame(parent) , param(param) { + QHBoxLayout *hlayout = new QHBoxLayout; + QVBoxLayout *vlayout = new QVBoxLayout; + + hlayout->addSpacing(25); + if (icon_path.length()){ + QPixmap pix(icon_path); + QLabel *icon = new QLabel(); + icon->setPixmap(pix.scaledToWidth(100, Qt::SmoothTransformation)); + icon->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); + hlayout->addWidget(icon); + } else{ + hlayout->addSpacing(100); + } + hlayout->addSpacing(25); + + checkbox = new QCheckBox(title); + QLabel *label = new QLabel(description); + label->setWordWrap(true); + + vlayout->addWidget(checkbox); + vlayout->addWidget(label); + hlayout->addLayout(vlayout); + + setLayout(hlayout); + + checkbox->setChecked(read_db_bool(param.toStdString().c_str())); + + setStyleSheet(R"( + QCheckBox { font-size: 70px } + QLabel { font-size: 40px } + * { + background-color: #114265; + } + )"); + + QObject::connect(checkbox, SIGNAL(stateChanged(int)), this, SLOT(checkboxClicked(int))); +} + +void ParamsToggle::checkboxClicked(int state){ + char value = state ? '1': '0'; + write_db_value(param.toStdString().c_str(), &value, 1); +} + +SettingsWindow::SettingsWindow(QWidget *parent) : QWidget(parent) { + QWidget *container = new QWidget(this); + + QVBoxLayout *settings_list = new QVBoxLayout(); + settings_list->addWidget(new ParamsToggle("OpenpilotEnabledToggle", + "Enable Openpilot", + "Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off.", + "../assets/offroad/icon_openpilot.png" + )); + settings_list->addWidget(new ParamsToggle("LaneChangeEnabled", + "Enable Lane Change Assist", + "Perform assisted lane changes with openpilot by checking your surroundings for safety, activating the turn signal and gently nudging the steering wheel towards your desired lane. openpilot is not capable of checking if a lane change is safe. You must continuously observe your surroundings to use this feature.", + "../assets/offroad/icon_road.png" + )); + settings_list->addWidget(new ParamsToggle("IsLdwEnabled", + "Enable Lane Departure Warnings", + "Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31mph (50kph).", + "../assets/offroad/icon_warning.png" + )); + settings_list->addWidget(new ParamsToggle("RecordFront", + "Record and Upload Driver Camera", + "Upload data from the driver facing camera and help improve the driver monitoring algorithm.", + "../assets/offroad/icon_network.png" + )); + settings_list->addWidget(new ParamsToggle("IsRHD", + "Enable Right-Hand Drive", + "Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat.", + "../assets/offroad/icon_openpilot_mirrored.png" + )); + settings_list->addWidget(new ParamsToggle("IsMetric", + "Use Metric System", + "Display speed in km/h instead of mp/h.", + "../assets/offroad/icon_metric.png" + )); + settings_list->addWidget(new ParamsToggle("CommunityFeaturesToggle", + "Enable Community Features", + "Use features from the open source community that are not maintained or supported by comma.ai and have not been confirmed to meet the standard safety model. These features include community supported cars and community supported hardware. Be extra cautious when using these features", + "../assets/offroad/icon_shell.png" + )); + + settings_list->setSpacing(25); + + container->setLayout(settings_list); + container->setFixedWidth(1650); + + QScrollArea *scrollArea = new QScrollArea; + scrollArea->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + scrollArea->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + scrollArea->setWidget(container); + + QScrollerProperties sp; + sp.setScrollMetric(QScrollerProperties::DecelerationFactor, 2.0); + + QScroller* qs = QScroller::scroller(scrollArea); + qs->setScrollerProperties(sp); + + QHBoxLayout *main_layout = new QHBoxLayout; + main_layout->addSpacing(50); + main_layout->addWidget(scrollArea); + + QPushButton * button = new QPushButton("Close"); + main_layout->addWidget(button); + main_layout->addSpacing(20); + + setLayout(main_layout); + + QScroller::grabGesture(scrollArea, QScroller::LeftMouseButtonGesture); + QObject::connect(button, SIGNAL(clicked()), this, SIGNAL(closeSettings())); + + setStyleSheet(R"( + QPushButton { font-size: 40px } + * { + color: white; + background-color: #072339; + } + )"); +} diff --git a/selfdrive/ui/qt/settings.hpp b/selfdrive/ui/qt/settings.hpp new file mode 100644 index 00000000000000..e65e75bc76e2ae --- /dev/null +++ b/selfdrive/ui/qt/settings.hpp @@ -0,0 +1,28 @@ +#pragma once + +#include +#include +#include +#include + +class ParamsToggle : public QFrame { + Q_OBJECT + +private: + QCheckBox *checkbox; + QString param; +public: + explicit ParamsToggle(QString param, QString title, QString description, QString icon, QWidget *parent = 0); +public slots: + void checkboxClicked(int state); +}; + + + +class SettingsWindow : public QWidget { + Q_OBJECT +public: + explicit SettingsWindow(QWidget *parent = 0); +signals: + void closeSettings(); +}; diff --git a/selfdrive/ui/qt/ui.cc b/selfdrive/ui/qt/ui.cc new file mode 100644 index 00000000000000..aece1742abfe51 --- /dev/null +++ b/selfdrive/ui/qt/ui.cc @@ -0,0 +1,37 @@ +#include + +#ifdef QCOM2 +#include +#include +#include +#endif + +#include "window.hpp" + +int main(int argc, char *argv[]) { + QSurfaceFormat fmt; +#ifdef __APPLE__ + fmt.setVersion(3, 2); + fmt.setProfile(QSurfaceFormat::OpenGLContextProfile::CoreProfile); + fmt.setRenderableType(QSurfaceFormat::OpenGL); +#else + fmt.setRenderableType(QSurfaceFormat::OpenGLES); +#endif + QSurfaceFormat::setDefaultFormat(fmt); + + QApplication a(argc, argv); + + MainWindow w; + w.setFixedSize(vwp_w, vwp_h); + w.show(); + +#ifdef QCOM2 + QPlatformNativeInterface *native = QGuiApplication::platformNativeInterface(); + wl_surface *s = reinterpret_cast(native->nativeResourceForWindow("surface", w.windowHandle())); + wl_surface_set_buffer_transform(s, WL_OUTPUT_TRANSFORM_270); + wl_surface_commit(s); + w.showFullScreen(); +#endif + + return a.exec(); +} diff --git a/selfdrive/ui/qt/wifi.cc b/selfdrive/ui/qt/wifi.cc new file mode 100644 index 00000000000000..1d66c2c8623241 --- /dev/null +++ b/selfdrive/ui/qt/wifi.cc @@ -0,0 +1,69 @@ +#include +#include + +typedef QMap > Connection; +Q_DECLARE_METATYPE(Connection) + +void wifi_stuff(){ + qDBusRegisterMetaType(); + + QString nm_path = "/org/freedesktop/NetworkManager"; + QString nm_settings_path = "/org/freedesktop/NetworkManager/Settings"; + + QString nm_iface = "org.freedesktop.NetworkManager"; + QString props_iface = "org.freedesktop.DBus.Properties"; + QString nm_settings_iface = "org.freedesktop.NetworkManager.Settings"; + + QString nm_service = "org.freedesktop.NetworkManager"; + QString device_service = "org.freedesktop.NetworkManager.Device"; + + QDBusConnection bus = QDBusConnection::systemBus(); + + // Get devices + QDBusInterface nm(nm_service, nm_path, nm_iface, bus); + QDBusMessage response = nm.call("GetDevices"); + QVariant first = response.arguments().at(0); + + const QDBusArgument &args = first.value(); + args.beginArray(); + while (!args.atEnd()) { + QDBusObjectPath path; + args >> path; + + // Get device type + QDBusInterface device_props(nm_service, path.path(), props_iface, bus); + QDBusMessage response = device_props.call("Get", device_service, "DeviceType"); + QVariant first = response.arguments().at(0); + QDBusVariant dbvFirst = first.value(); + QVariant vFirst = dbvFirst.variant(); + uint device_type = vFirst.value(); + qDebug() << path.path() << device_type; + } + args.endArray(); + + + // Add connection + Connection connection; + connection["connection"]["type"] = "802-11-wireless"; + connection["connection"]["uuid"] = QUuid::createUuid().toString().remove('{').remove('}'); + connection["connection"]["id"] = "Connection 1"; + + connection["802-11-wireless"]["ssid"] = QByteArray(""); + connection["802-11-wireless"]["mode"] = "infrastructure"; + + connection["802-11-wireless-security"]["key-mgmt"] = "wpa-psk"; + connection["802-11-wireless-security"]["auth-alg"] = "open"; + connection["802-11-wireless-security"]["psk"] = ""; + + connection["ipv4"]["method"] = "auto"; + connection["ipv6"]["method"] = "ignore"; + + + QDBusInterface nm_settings(nm_service, nm_settings_path, nm_settings_iface, bus); + QDBusReply result = nm_settings.call("AddConnection", QVariant::fromValue(connection)); + if (!result.isValid()) { + qDebug() << result.error().name() << result.error().message(); + } else { + qDebug() << result.value().path(); + } +} diff --git a/selfdrive/ui/qt/window.cc b/selfdrive/ui/qt/window.cc new file mode 100644 index 00000000000000..60a8e28cd40f20 --- /dev/null +++ b/selfdrive/ui/qt/window.cc @@ -0,0 +1,159 @@ +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "window.hpp" +#include "settings.hpp" + +#include "paint.hpp" +#include "common/util.h" + +volatile sig_atomic_t do_exit = 0; + +MainWindow::MainWindow(QWidget *parent) : QWidget(parent) { + main_layout = new QStackedLayout; + +#ifdef QCOM2 + set_core_affinity(7); +#endif + + GLWindow * glWindow = new GLWindow(this); + main_layout->addWidget(glWindow); + + SettingsWindow * settingsWindow = new SettingsWindow(this); + main_layout->addWidget(settingsWindow); + + + main_layout->setMargin(0); + setLayout(main_layout); + QObject::connect(glWindow, SIGNAL(openSettings()), this, SLOT(openSettings())); + QObject::connect(settingsWindow, SIGNAL(closeSettings()), this, SLOT(closeSettings())); + + setStyleSheet(R"( + * { + color: white; + background-color: #072339; + } + )"); +} + +void MainWindow::openSettings() { + main_layout->setCurrentIndex(1); +} + +void MainWindow::closeSettings() { + main_layout->setCurrentIndex(0); +} + + +GLWindow::GLWindow(QWidget *parent) : QOpenGLWidget(parent) { + timer = new QTimer(this); + QObject::connect(timer, SIGNAL(timeout()), this, SLOT(timerUpdate())); + + int result = read_param(&brightness_b, "BRIGHTNESS_B", true); + result += read_param(&brightness_m, "BRIGHTNESS_M", true); + if(result != 0) { + brightness_b = 0.0; + brightness_m = 5.0; + } + smooth_brightness = 512; +} + +GLWindow::~GLWindow() { + makeCurrent(); + doneCurrent(); +} + +void GLWindow::initializeGL() { + initializeOpenGLFunctions(); + std::cout << "OpenGL version: " << glGetString(GL_VERSION) << std::endl; + std::cout << "OpenGL vendor: " << glGetString(GL_VENDOR) << std::endl; + std::cout << "OpenGL renderer: " << glGetString(GL_RENDERER) << std::endl; + std::cout << "OpenGL language version: " << glGetString(GL_SHADING_LANGUAGE_VERSION) << std::endl; + + ui_state = new UIState(); + ui_state->sound = &sound; + ui_state->fb_w = vwp_w; + ui_state->fb_h = vwp_h; + ui_init(ui_state); + + timer->start(50); +} + +void GLWindow::timerUpdate(){ + // Update brightness + float clipped_brightness = std::min(1023.0f, (ui_state->light_sensor*brightness_m) + brightness_b); + smooth_brightness = clipped_brightness * 0.01f + smooth_brightness * 0.99f; + + std::ofstream brightness_control("/sys/class/backlight/panel0-backlight/brightness"); + if (brightness_control.is_open()){ + brightness_control << int(smooth_brightness) << "\n"; + brightness_control.close(); + } + + ui_update(ui_state); + +#ifdef QCOM2 + if (ui_state->started != onroad){ + onroad = ui_state->started; + timer->setInterval(onroad ? 50 : 1000); + + int brightness = onroad ? 1023 : 0; + std::ofstream brightness_control("/sys/class/backlight/panel0-backlight/brightness"); + if (brightness_control.is_open()){ + brightness_control << int(brightness) << "\n"; + brightness_control.close(); + } + } +#endif + + update(); +} + +void GLWindow::resizeGL(int w, int h) { + std::cout << "resize " << w << "x" << h << std::endl; +} + +void GLWindow::paintGL() { + ui_draw(ui_state); +} + +void GLWindow::mousePressEvent(QMouseEvent *e) { + // Settings button click + if (!ui_state->scene.uilayout_sidebarcollapsed && settings_btn.ptInRect(e->x(), e->y())) { + emit openSettings(); + } + + // Vision click + if (ui_state->started && (e->x() >= ui_state->scene.viz_rect.x - bdr_s)){ + ui_state->scene.uilayout_sidebarcollapsed = !ui_state->scene.uilayout_sidebarcollapsed; + } +} + + +GLuint visionimg_to_gl(const VisionImg *img, EGLImageKHR *pkhr, void **pph) { + unsigned int texture; + glGenTextures(1, &texture); + glBindTexture(GL_TEXTURE_2D, texture); + glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, img->width, img->height, 0, GL_RGB, GL_UNSIGNED_BYTE, *pph); + glGenerateMipmap(GL_TEXTURE_2D); + *pkhr = (EGLImageKHR)1; // not NULL + return texture; +} + +void visionimg_destroy_gl(EGLImageKHR khr, void *ph) { + // empty +} + +FramebufferState* framebuffer_init(const char* name, int32_t layer, int alpha, + int *out_w, int *out_h) { + return (FramebufferState*)1; // not null +} diff --git a/selfdrive/ui/qt/window.hpp b/selfdrive/ui/qt/window.hpp new file mode 100644 index 00000000000000..cc525a6e0d84ff --- /dev/null +++ b/selfdrive/ui/qt/window.hpp @@ -0,0 +1,68 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include + +#include "qt/qt_sound.hpp" +#include "ui/ui.hpp" + +class MainWindow : public QWidget +{ + Q_OBJECT + +public: + explicit MainWindow(QWidget *parent = 0); + +private: + QStackedLayout *main_layout; + +public slots: + void openSettings(); + void closeSettings(); + +}; + +#ifdef QCOM2 +const int vwp_w = 2160; +#else +const int vwp_w = 1920; +#endif +const int vwp_h = 1080; +class GLWindow : public QOpenGLWidget, protected QOpenGLFunctions +{ + Q_OBJECT + +public: + using QOpenGLWidget::QOpenGLWidget; + explicit GLWindow(QWidget *parent = 0); + ~GLWindow(); + +protected: + void mousePressEvent(QMouseEvent *e) override; + void initializeGL() override; + void resizeGL(int w, int h) override; + void paintGL() override; + + +private: + QTimer * timer; + UIState * ui_state; + QtSound sound; + + bool onroad = true; + QLabel * label = NULL; + float brightness_b = 0; + float brightness_m = 0; + float smooth_brightness = 0; + +public slots: + void timerUpdate(); + +signals: + void openSettings(); +}; diff --git a/selfdrive/ui/sidebar.cc b/selfdrive/ui/sidebar.cc index e8eb894cc9f151..679d347cbad18a 100644 --- a/selfdrive/ui/sidebar.cc +++ b/selfdrive/ui/sidebar.cc @@ -2,21 +2,23 @@ #include #include #include -#include "ui.hpp" + +#include "paint.hpp" +#include "sidebar.hpp" static void ui_draw_sidebar_background(UIState *s) { int sbr_x = !s->scene.uilayout_sidebarcollapsed ? 0 : -(sbr_w) + bdr_s * 2; - ui_draw_rect(s->vg, sbr_x, 0, sbr_w, vwp_h, COLOR_BLACK_ALPHA(85)); + ui_draw_rect(s->vg, sbr_x, 0, sbr_w, s->fb_h, COLOR_BLACK_ALPHA(85)); } static void ui_draw_sidebar_settings_button(UIState *s) { const float alpha = s->active_app == cereal::UiLayoutState::App::SETTINGS ? 1.0f : 0.65f; - ui_draw_image(s->vg, settings_btn_x, settings_btn_y, settings_btn_w, settings_btn_h, s->img_button_settings, alpha); + ui_draw_image(s->vg, settings_btn.x, settings_btn.y, settings_btn.w, settings_btn.h, s->img_button_settings, alpha); } static void ui_draw_sidebar_home_button(UIState *s) { const float alpha = s->active_app == cereal::UiLayoutState::App::HOME ? 1.0f : 0.65f;; - ui_draw_image(s->vg, home_btn_x, home_btn_y, home_btn_w, home_btn_h, s->img_button_home, alpha); + ui_draw_image(s->vg, home_btn.x, home_btn.y, home_btn.w, home_btn.h, s->img_button_home, alpha); } static void ui_draw_sidebar_network_strength(UIState *s) { @@ -118,57 +120,43 @@ static void ui_draw_sidebar_temp_metric(UIState *s) { {cereal::ThermalData::ThermalStatus::YELLOW, 1}, {cereal::ThermalData::ThermalStatus::RED, 2}, {cereal::ThermalData::ThermalStatus::DANGER, 3}}; - char temp_label_str[32]; - char temp_value_str[32]; - char temp_value_unit[32]; - const int temp_y_offset = 0; - snprintf(temp_value_str, sizeof(temp_value_str), "%d", s->scene.thermal.getPa0()); - snprintf(temp_value_unit, sizeof(temp_value_unit), "%s", "°C"); - snprintf(temp_label_str, sizeof(temp_label_str), "%s", "TEMP"); - strcat(temp_value_str, temp_value_unit); - - ui_draw_sidebar_metric(s, temp_label_str, temp_value_str, temp_severity_map[s->scene.thermal.getThermalStatus()], temp_y_offset, NULL); + std::string temp_val = std::to_string((int)s->scene.thermal.getAmbient()) + "°C"; + ui_draw_sidebar_metric(s, "TEMP", temp_val.c_str(), temp_severity_map[s->scene.thermal.getThermalStatus()], 0, NULL); } static void ui_draw_sidebar_panda_metric(UIState *s) { - int panda_severity = 2; - char panda_message_str[32]; const int panda_y_offset = 32 + 148; + int panda_severity = 0; + std::string panda_message = "VEHICLE\nONLINE"; if (s->scene.hwType == cereal::HealthData::HwType::UNKNOWN) { panda_severity = 2; - snprintf(panda_message_str, sizeof(panda_message_str), "%s", "NO\nVEHICLE"); - } else { - if (s->started){ - if (s->scene.satelliteCount < 6) { - panda_severity = 1; - snprintf(panda_message_str, sizeof(panda_message_str), "%s", "VEHICLE\nNO GPS"); - } else if (s->scene.satelliteCount >= 6) { - panda_severity = 0; - snprintf(panda_message_str, sizeof(panda_message_str), "%s", "VEHICLE\nGOOD GPS"); - } + panda_message = "NO\nVEHICLE"; + } else if (s->started) { + if (s->scene.satelliteCount < 6) { + panda_severity = 1; + panda_message = "VEHICLE\nNO GPS"; } else { panda_severity = 0; - snprintf(panda_message_str, sizeof(panda_message_str), "%s", "VEHICLE\nONLINE"); + panda_message = "VEHICLE\nGOOD GPS"; } } - - ui_draw_sidebar_metric(s, NULL, NULL, panda_severity, panda_y_offset, panda_message_str); + ui_draw_sidebar_metric(s, NULL, NULL, panda_severity, panda_y_offset, panda_message.c_str()); } static void ui_draw_sidebar_connectivity(UIState *s) { - if (s->scene.athenaStatus == NET_DISCONNECTED) { - ui_draw_sidebar_metric(s, NULL, NULL, 1, 180+158, "CONNECT\nOFFLINE"); - } else if (s->scene.athenaStatus == NET_CONNECTED) { - ui_draw_sidebar_metric(s, NULL, NULL, 0, 180+158, "CONNECT\nONLINE"); - } else { - ui_draw_sidebar_metric(s, NULL, NULL, 2, 180+158, "CONNECT\nERROR"); - } + static std::map> connectivity_map = { + {NET_ERROR, {"CONNECT\nERROR", 2}}, + {NET_CONNECTED, {"CONNECT\nONLINE", 0}}, + {NET_DISCONNECTED, {"CONNECT\nOFFLINE", 1}}, + }; + auto net_params = connectivity_map[s->scene.athenaStatus]; + ui_draw_sidebar_metric(s, NULL, NULL, net_params.second, 180+158, net_params.first); } void ui_draw_sidebar(UIState *s) { ui_draw_sidebar_background(s); - if (s->scene.uilayout_sidebarcollapsed){ + if (s->scene.uilayout_sidebarcollapsed) { return; } ui_draw_sidebar_settings_button(s); diff --git a/selfdrive/ui/sidebar.hpp b/selfdrive/ui/sidebar.hpp new file mode 100644 index 00000000000000..f273e16f8bff70 --- /dev/null +++ b/selfdrive/ui/sidebar.hpp @@ -0,0 +1,4 @@ +#pragma once +#include "ui.hpp" + +void ui_draw_sidebar(UIState *s); diff --git a/selfdrive/ui/sound.hpp b/selfdrive/ui/sound.hpp index d565f846ffcf46..93157830661376 100644 --- a/selfdrive/ui/sound.hpp +++ b/selfdrive/ui/sound.hpp @@ -2,31 +2,23 @@ #include #include "cereal/gen/cpp/log.capnp.h" -#if defined(QCOM) -#include -#include -#endif - typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert; -class Sound { - public: - Sound() = default; - bool init(int volume); - bool play(AudibleAlert alert); - void stop(); - void setVolume(int volume); - ~Sound(); +static std::map> sound_map { + // AudibleAlert, (file path, loop count) + {AudibleAlert::CHIME_DISENGAGE, {"../assets/sounds/disengaged.wav", 0}}, + {AudibleAlert::CHIME_ENGAGE, {"../assets/sounds/engaged.wav", 0}}, + {AudibleAlert::CHIME_WARNING1, {"../assets/sounds/warning_1.wav", 0}}, + {AudibleAlert::CHIME_WARNING2, {"../assets/sounds/warning_2.wav", 0}}, + {AudibleAlert::CHIME_WARNING2_REPEAT, {"../assets/sounds/warning_2.wav", 3}}, + {AudibleAlert::CHIME_WARNING_REPEAT, {"../assets/sounds/warning_repeat.wav", 3}}, + {AudibleAlert::CHIME_ERROR, {"../assets/sounds/error.wav", 0}}, + {AudibleAlert::CHIME_PROMPT, {"../assets/sounds/error.wav", 0}} +}; -#if defined(QCOM) - private: - SLObjectItf engine_ = nullptr; - SLObjectItf outputMix_ = nullptr; - int last_volume_ = 0; - double last_set_volume_time_ = 0.; - AudibleAlert currentSound_ = AudibleAlert::NONE; - struct Player; - std::map player_; - friend void SLAPIENTRY slplay_callback(SLPlayItf playItf, void *context, SLuint32 event); -#endif +class Sound { +public: + virtual bool play(AudibleAlert alert) = 0; + virtual void stop() = 0; + virtual void setVolume(int volume) = 0; }; diff --git a/selfdrive/ui/spinner/Makefile b/selfdrive/ui/spinner/Makefile index 93871bb0090d27..8d80f69a854420 100644 --- a/selfdrive/ui/spinner/Makefile +++ b/selfdrive/ui/spinner/Makefile @@ -20,6 +20,7 @@ FRAMEBUFFER_LIBS = -lutils -lgui -lEGL OBJS = spinner.o \ ../../common/framebuffer.o \ + ../../common/util.o \ $(PHONELIBS)/nanovg/nanovg.o \ ../../common/spinner.o \ opensans_semibold.o \ diff --git a/selfdrive/ui/spinner/spinner b/selfdrive/ui/spinner/spinner index c8f8e68ecf4ae37be04f60dbc6551c73366cbe2d..2acc7e7854aeb06c7ae6ef1468a2309891c51942 100755 GIT binary patch delta 59878 zcmbrn33wD$)<1l!I!iBE$x0Hcm$0Ne3lIWHSSyVSBoH*jWzaDpxFl&n0xlpzCEyYW zI<&=ziX#cQB#kH*mc!u<$lgqskm5a>6^`(QPAHX*F>!DH}z7~wjEQ3&G^rXbvmFdtzB!e0>R_bkF= z2*U~RH|7PrJ>-GCe;)C@m-(Lae9uTcUqN`v2h(FZ!V?J52+I*F5!NHDLr^392_XxC zeoMWN{=ZK$J!7K*K92A_!YYJW2)7~7@70ZapHofUD1NC5kj20p?rC{h;1up9`4|@^ ze;k;`ZNXcd91#=}xD}}<$;O}w+*p8A~V%aV@5xkD^%`F2-G_NZwp?i z|I`zj7Y^B|elyX(yn*QdsaPDQNPyg}p2WQ(bJ{pgBj;%z=4R5nd{i?^o~DhL z`JUJ{@?32RcTwJ}y^%X4H-yB=23`8qS-kw8zTywR~z;Qq5 zP@P<|2R;}X&#ji*B1`1k2gP$1Pci#F@rUJxK@W2Y9!$7AI;w>GLAK-XMfsgO2(tKJMvp9J`is>wV?4ZuX}4ckJ)Jaz4h8 zd04OLE9gdF#Exqk^fzBYLw#dRD~^5-`qH2DHI(^=@=JgEYs$Ik8ydyj^3>0k_=aGS zuV?xrAHKe!d0+g|VEHLSY4E*^7FR5M;9mKx;aE~h$qm<)OrJgb`r?v# zm#<9QG$!96pr$PQGWj zUiupIJi=G&ywE_r@hsFg6Iy*Dgv!^yMLxP5yar$I!yml{zr%;GAL%W?Urx>_FWfjX zz&kGfh@tC=#WS|!nhd*rYxUqYcz^n%*Wmq9%gJl-JA4gv_2a$uv)eMg%e|vN!qW~` z@5^xh8oWP!&o%hxe1hF>AD%-;{jvj<*s8#jtk5r#U~3?dahQ1|kobR#QoVQ{58nWK zqLwP~-W1*()e1ZfrvF!~z>_TL|4Hi=5nkeZqn=aX{j88;>J@mbj{aYx0*_VD|J$L! zV^a73c6;#>qn`OW55=}BGKBUgXY8N?AEv+`Rp3cN^#4vO@cs!-aV`Zua)ADfbtodD z{H5S|UV-=TMikwnz{e=kv$TOBi&fy&3Or;1?~mqRgd!r|AAx7Q0zX)RHz@E43VezJ zPa>B8H%fs|@+0xg0p2tJX$XcWB1A<7kL2Wwo2J0)73ptM;0+4=?Fzh6fiE4vON<0D z|F3)?f+hQrcrH@lhbr((75HHae6<4a6SqCFwF>+Q55~9t*DE6YOq=4LQ{c^>4BkKW z3cN*uZ&ct@75E(re3}BkTT(=%DD*;|44acRV&{v1UF=?eazsK8J0Bk`Q3z>5m}O$vOT0)M*#Z&lz+ z2~Yi}A(*O&C|6{-PJv&fz?0hI|1DMEZ}21WtXAM}RN!kBcxjp=th@W@-cPk=DQTP8^6?jrk{l9|>{7rr&o<|kyZyfmdpuJqrA-iu5dFp#0kuc(or-_50;zijVL|0RIO?hIj>j zjskB`;O|i2Qxy0+75GsKJSoXu`r{=>5pkCygQ&olDDcx1_)-P_CIx=30)M*#Up9c3 zSg9gn-arH^SK#kf;1?eRxm( zE=9x=MTQOq{s9I4yaNBA0^g&+Kcv7jpVUi~eprE5`{jR%SgMGKP-GxukN+31!22y_ z6lYN2m-`drnWDfys=$xx$D{u%6cIW75nfA^KT1^Kl|wd7fv@%_#`7ixzD9w+U4dUk zczYk ze+Ilt0sjJcivs=?@ID3nFTm{zn7;uH7-cs|{tAPDFahC*wScV(I1F%^0v-f-l>&|h zyhQ;g0N$s71;FhJ*aVm#ZI}8h91etO^gshFfUOER18|uF&IG(l0gnT`MFEcoyiWm7 z2HdWIt$_JVX`sRzfG}ka!1;i!3b+t(nF1~Xyh;Jz3V4eGo&$KF0=^4yy8;Y*oMu0hcM@#ei2S;D-QjQNWJ?-lu?90&Z8ps{l)U)<6TE0K%kz*8;XG z;HLqXDd1-SuTsFz0^Xv4UjV#M0lx&eT>)>op;wCF#||{$RU|MeU3pOW2!8xP18x9pQo#9utqQmh zaG3%w0=!BA-wJq(0-ghSp8~!MaJwItu#=Sm!A}@yz`cM?3b+!mRRJ#qT&92*174+o z9|F8Z0Y3tGp8{S9xZMX!w3V&`f}c3hfF}T(6!2QWRt5Yt;4%gL4B%A?_*uYP6z~gx z_bK3)0JnQ#$+P`#0fL`2(12F~n-s7EuvG!S0k}*7zYTbm0)7YZ76trQ!21;N-vGCJ zV3T+I-3J6ed7uFw0yg@@+^MLM^8 zqhAWTIO}gseapF~zNyT9LB%Yde7j@pdy(FFXRLib(i%9n(*u{s+S^r8mWybZ7I>E` z+7aM(kH!nj>|37KbaB=`PpkZe(~}vPebc|(aekb8wd$B$`bLsmKPjI3P{i$3in_!-3gif0E1M+CUzN!D|&PY#=$z%7)`lM^{f zzJ9X)o`;d_4wcw@M*`c~V5Ou9j(31-O<-fU1X;~qvc%gPw7mHs@b4|Qn%|4<$$mes zCwt3k?$}lY$^+VG?olQ5ytibm`AanAuV{)3Bx+L)c7(}?CMQZqkh?cZ?0p^$bOGC@ zig%1hN`~6KjgEH|B8>}a2CJAChsIAQ97>vsv}&ZC7Rz>~07v=SRB@I|c)yH+piVx7 z_uFFG*!tmOFLnH1fO}BhyH-xHKj*199u>zql2DkdpIUK_QF6_cC@Gba1A8)>?L5e_ z9c=90Nz($J_)N{U{@jtsdI{&!RZn8Mdnc)bpD60EF(=`;8f)KSJln>wzPw3$Cwzf+JiM^UUX4iA*3!O`DKP#kaHtF10N_Fm14XZdi3u<9~@ahF2HW|6csg!S=Q&A@jN4i=Us8V4oXNU9|r95>NvotBYz8 z4_o^N*x@(8M!x~<(19bdXnGP`YP>?@9Oby>Yi}H_Y!?sqgxNd^d83gwPR^Se6*CSH zt?^O59M>a9s9Z5spJ}ETlrbI{9(52`{8zZXClx8Rm_G#jdA&9Ot06}Y%TEaY7$d!I zZ&LHf{A2uG80Mp_KG4hB4MASkzC&kkc)z;n&nV~j;%g367d`cR@jXFyBu zaZ$xtE`d_z0dVCx&F=5O+HO~=z=31HqM|MC<*e7G3fkVWpE=!k;C({%Bv&%R>VWO_ zv)P7fE%5-cxBG(VoTrIgTXa^Z&(v_5x^v+y(>69F(ZW?bZ3~hHm2p~Ks<^qRgz0Rl zL9AGlThR->eAPkYO0dXp}LE>3&Yf(@3!F>jKdEsDb z8}h5o%x+#G$vV_EzpW&v@~4uVwL_LRr*SOvY1H*P8WoE6oJV{9#D&)Vg!X)TeMI7? zXv;aYX&)D=%kZ=(%yuMz71yFY>RD`OwXZ!4?fC`F9Cb&l^U8Zo9CNBUZC$&Hm-?ww zj)ryI#(Mt%O4M^K>z8KH*#Sy?%d2gMLRNg$m`?L;=ksIi#-y4eHOACeLGQh&q6$LFVxn@|*pN+;NlTk;Tx6Y1!|We( zA$30@^LYgOXl4&#)z9b!wiw%5aYPWiSp&+tR60j^w3zcJ7N1S&x-s-B;1{8ADq~$B zvzKro-6OwaImUmvi-~%pRzz%y;6v+(MR+Q!qRRNh#iL^F zbHe#>-KXf)n{)L`x93u2VV=sqL*YLloI|*bfKAJC8i6WpN9aa4i*N?vdjz7yPgoqT zU?yeKggwb=bTP9>ZE|Lcx$p3;%XS5|E_3r?HlvCazoBDU2ZC7Elb90+ZW^`eNfx5} z{!woBYw#_*kLf(`9|o|<`cW+Rbv0YIErcz5Er2Z}KJpRLyMRA{_B8Bvv#MCMJ;pLPm@O*-;ZIIxgWf^- z0>%9giu(}7e>sZTN2u7?JQd45iQ09e%i32)Y+A+hb+eFuhMGxem(GHt=;-f3Ab$fyz~VI(5Fx3OkI|PS=<|1IC=TzU z=PC-Of$D?j`ald&uH_8J2K^6X|aRnDe(^MIcSrfS* zR0uebUbh|ZRTvbUEG)ZU-di+6`j*q$D246^cQGy9Gbt?Vdkl9c=E3XT99wn}!F6MGW;>S#j5_7M}2WDSCRJHw1EIiuL1=C)IWD^9+(I5jp7NjQ_h)D}UJT;5nbKGYXAEnHmI z7A}8N95)=ItHGDhzte=#9vZ-^3gTI@d%1P{*^zm2;w?i`d*_M0J&>w@vx(cWGgjbDY~kW@VGDb#aSJcT zY8UQ$H6pwxNV~8I&kaMu3S*OFGj@GxEIeU~%_ze2IPgpG+(7YP8l^&8B>QRUSD6d{ z@YUFbUm*O9_nd#^6yEyPn1#m?9{wt8;YEbEPh=MU`SYB@L3r*$x)Ud|3zwY8D%|9-Nm%!({3N9iq&;v zXYI~NlsDftSUQZI)W2IsbJ}e#z-7pPMg5J!{t#ji$Y8!*8BRYfb}Ah;M-l>J6Pe7k<44n=^WXBG@3y(*xq={b1vmBW z=X^3(AY`rp2bdLBCUabd40ceZl)Xs%jdi%8=($vkX1x>2o;2y*o7jeTNli%x)dD960ykm+2ay@lK&%5!8yl(vd$O~kA{~U>rQU0( z(`dw8b*PwY{$u=X^CT9P!bPerRN2^pMDpglV#ZKqSp&E_&0u64qRgnaP~~F=(#SvF z6$_cliO#|JaAVWuWU=?+tQ#PpUf%@5*~vUYN^~zYCn6>V5>}@Lu(9fBw4dW_pI`=Q zCW_7}fvjpf-rhsdZDp>{;aIIaG;X&cAv_gnDPhl~8-$ z!RjJ*&5XDlp49WpZ5(C;kJ+G-!{-dv4nVrI?7QG;}7F{vdd|h50x%eYg&iR zQLl)Y4aL36g~YrkA&txRO&2gOXpm<-Wc3|iNour01HytHb(%nNnHe-RBl8+;dYZ@q zm5ZMIm$=tJdMMKnN=PsO8p2d)~dPS zE9I!50u^Xb!4!_SiLGlAXcOt?Sutr68sZZX%x?Q5v(JC4Bxk|ilANcIcIICF?)k?6 zLu>HB5US@xdsuLfn6nNuejR2!_#Dg`n(lR6sAUG2L;h$1I}2pg|I`DTuJWSw(bARs zRZzGBpl}6ZJ_ljAvGA9xp>Xkb^{8rRkBWzA&skCu6{O^@CS98V(kaMWA+WI;qnN85 zCgxh8-$X(ONrB*P4x*kfZSD+bz0-%VEQq9%BSp*XzXt0wJEB-Ggw@^-=(_4au1%T(%zZ~G3rUyG%aB8Rb@P+ zQr8{Uin&L^uy&B|Ft4kd!AahQbO@~jC&{e?ttAv#3V~R{nC(qu#k9x@u*fK`I}-dG zq_YLGn`cDA`~!{bFyydLSBUbbz0xyJb76IVN5elw!+${fZ@FmO0<87|q$iz)_L`ZH z!1i!DTRL==;cVMR-1XtUHuew*UzjBH3EkN(h=ovMrV(h(G=Ctxh?cPErj?pRGxm!^`^EAy%3_t-s@|M zf(H^@9sd=~eN$_S+`se}aCQ83@%9?TU;e%L@;Lk6$u&hkBHp{}$}im+d*?+kEV83v zHH=9kxWDR^qn3phm}m>E#Ej_#SsRkdNTo&xRnv|xeIJH}woAy#ETntZTl zTb^gWcB?RORJM{cuQ7_bYlngML)5d)U?8GM9Vh^a}d*kK#ZB17_0 z>z=~OC5rS@=MM_%4B-Z-Q^TrS!ECRk4zwhTCW|?#BP8ui1BIs%{~*DFR45VbLd(Ql zU4V~~LB{$RB-g5e3mL#21`ce+j;o0FDI69VNH4pd8!8b!HCNnOM9X}mxSN*ibl6A! z>630Qg%9buI19&B%OU^3?y5%b8&P=-gh!tngR`fHRzBl5W6`ca^I&@ev;Tn8$v5-v%GqHo$#G*_dJA)+K3B}$ z-X@#oWl3?}227$(Rf;2yW8=C}P!}{YZMt@oniJp7A1&r$f2*1k_X32>xNQ)Fi~VUj zdG!%BrK`YvLgBgtc{!9eA894Z6SFqKtYJSH-R|Nq2V;__dbLPQmAX{eWT!nW%vQ@^ z%!|5}bi`?}$Tr5YU9ITOG#EmoINi2Rh{qix`6lRlPB9LWf4or$Q5%GFFnaW$dsh%h zaCr|0x68jxvg?DfmykSY6P;bja{k@=k|^{I^_o$l6{X~I>TL$>%fFzX4MVmU)+1cR z*<1{C3L^7C>|&4xZ`Oyhs%ctQyaqnBmA3L6vqoEI;PfZ{%zCn^bTyY$Q2yoE-SVP) z;s;*=VpkB0tPN(7bUfD^%y!noEHyzk-;*Y7VZsZxin+Nr@l*okJs6>?`vxVnx7vh))$%x(z6SY5*Iitfat zD|#KP^7nJ~PwwKLe@tyURU$h7fbNy%83hPnRV*o0=ujnCN~W@^Ef~dfW2{ZYV`u^n z_DoD`6NiHa6Q+4`QiB|PZ#Wks$K5+AfMF)dcix+p)x=jjO^{qH9`n4`R!0MfAydB3<@*7Tcx$jjUNp)|2X0Bd|L4|uktazTcBs&%4xPS@F{A;uV@3=d@b^!dlR_~ z`OLjX)Q^KIy+|+bzRw)EggMV<%irBs5ST6Yo?9Z1D;HwbDri-KTvY*D(WMeHwN*pL zH1Tp}d4@z$upK*s(67rF0eG24Tc&#Jy$y3(6O37xEjlgej0pP}ndMlDS;)U5Ytt00 z2QiSfbf0w>cNK`xRZT+IVTcXbuC8b`bxoMThNf99-I&>3BUmp9v0ae$yG(cnicAbO8GYW?EB{;w6j1zmyVM9uZQP)w2)p@;b3a zr4n1LImyD%9D`tuA1Vao8idExCShL6P+?wb!Atf`ey8;6fI@hEL~)u$Bs3G3Q|PRO8(Mf^=uI;wIItJw$*;RcsGS6kFQndD|U3 zo7t%!(|g^;CJ+jI=AlYK!v40?FvWYgMTbeAZU&1jG)~lfQc*j4+`Am;q8XEhm=SdA zZ7$HBy4r!Ur0P26RTo`=!T25QrT)Arm)*NwL_Q~))NA$_dwSzJ(aBUM!BxUqlJ%n0 zQi^ulMzUhdh`jU^qd_oY0=r7Y77_0UV!>bW?85UD`azRI9O5XXK3nmmiO~-J#9?*h zVl1BTbMJ!jCweIQ?Lzu$kg|3ZD>g*Ydy3%CM`~0}PKsdE$SZB(+&uYdn`u%i2DT9y zx}mUvU9^aXWZ`k&dp+KV;e9&G5gZ6)X=wn9u1N36)~htOborbujSH6(=38P76)Ep~ z8gt3L>k8;F1O5|z}s(@f1NMzYi^bk7Tmx;e6w7(;8tnw z&E$haYa+qZwbmhT6t)d{vyi%9He_4j9}urs#n|AkVll$%Nj2qmxOc5ZO>?*$p%dwp zBuXaRILae3QJK@J{A4p@8V9>A@GnW1u@Cjmg*fb&` zfktlTH8$HGckzrqw-i?oZbs(QE#y!YAlSF!Id6yFzPF~P=)!q8bSUFX6TI9P@RFqtKy;xyzWzj9j9UPu7vcvM~lUU)l5G;$?C|~MKKe?$bP1<|uYeHKa5zBSrmmIa zoyef#f(rZuBGM4iEdNXQ4s*ZTJx}j4uI^pl|L^X}^{>Utt_QE6ZU|P^e=OtV1;S1!g#wxN0JdZ(K^jWc7VVaL0~$xfu;f1B9EqF zX;0>wuoK#Kfz?GFkjvDPZj)FpuUfHCO4R8#9ULw?E5h@3lekwtmF2>M<}AOF>{ULuI`FB2L<1@_-=iY?~ss zbg0w?;{O;kOkW!^xFI2h9TP;S;iNIFZKV9t%8VE_>N;p5wPvuT<2QE}j%<2EZ3%NjlFNl8SIV=#a%>@UV3Au=1`iUIy1SqUW|0Viyv4Wu!RAm~-xpCE={95n>Cr z@E!T*lI*q65~o)@lB3pW>KL@d4s4t$a8{*Zu8o5VL&6_skR?!h<_HX_^Pz%UR9Z(q zo@+U6!8A^-v%o4d6Y=S)P{->yxD0{EzsLoh=1>-S7C@RtY}O#f zQ%G46$Z|KUwB4O3vF3`q_%9etYC+>5Zwu5hY$q9*s0A}n!y#S^{aegUQ-wIz;W?iR zDX2vYW}xhIC>v(D=4~ifw_@ieTi@K{sdz6yBM>Lq7a%eX7Nu>-SjXuK%8{`k5;6dq zZ$sg!a5HuS3~sDk;QK=P8_@t!UL%jiMg( zH!Q~6Flw}J1wWe_L$sv^5v52jBTAKPe3Xh97^^f?co<_!vE|@#LtqAauCG`JBma`bgs~Vv>p5Uhn zO_+rmQEE=dSRFwZw)w`Y4g*OOXg-ky8ED*yEHsh)WSNNuVai%)!c5^}Y&INjR02n1 z)r|$-3ICruEsRAdrvT+pd50=1b8M(5)juaREONd^5}UCl<r9`6wg(N7CSgroTZL0_s&K$VvrT zP++G@W1#{)oT8#KX9j$?(r^ywAM4jaW;G^a2=dOau;h>d81cHz$X^HB2c3?bfcdmz zgc#~Is|-l7OKJ=pI|^25MxEC!RIT+k^kCG#H&CKh5Q(Uzv#=J3R78<; zzSjO7t;J!khdUFw|AY#=`y0*ArUrkEMy7(C{%vL((hxKDa2_qh}DHn+yOTI1ls23invql8R!`7h^f8i)N(jTW)vTc8Uuav%A%90C<+Sk5Ia)+z z$BB2-+PLbEEGRtvz(8+YP0SG#t`ebS5(Rju5myO$P$8 z1FjPe^3Q1B>eX;!aUv29Er*o74jt>QT@emVr~G|2Ond3rr5bU5)+F0kObGP89b1to z)oQ{wkrJCtSW@NA!OLM*yg>-V_{U=X)&}9E8^Z+B_o`vp>eLCD zhfHQ1eWER4Ro^#oRF_UelwmOBP6jm0R>xQ*eYzdgU6#!GDkPI60597vtEC9k_fk&R!3R zp*7Z$E5^s_!)mPhD>b~>XLzhWqZ&F`ljFJyqP+%Z4|G>SEB~cNpELMS#nK9BZKNu; z&*tr?;Mj0_3~xV^%tJ$@YaY-L3s~<0ubC^WqYfJ4MzKZisY#Pu@ZVkISXoh?Aokv! zQ0;67Jt-5Nch(rRn=0S9&MacEL>$7+#WPQhffz2DabyH0R=~#NAMwbESyc|4Rl>dRVJB z)>=z;Pgf<@rNA?E?W&U9X;WAfO@?aBBnzBF>p*V<8r>GxI*C-46gZ30z#DKdkTx+S zOiKq)*zcEF*l?i+nIK?!4sqZbpxdf32&Lv^kL}Z?F$#HzuQnTmt#~(tvKD;k)Eghe zS}304T=$DkQkY{^&n6fKvzA&Y%%lu&fWo{Se#@j3AAu{&Ik>&FgM-lWJe!&*_HO6m zb+qotnQI+b)n*uK+rIT{&sdA#edSiZXXAAx+^FV=KUHxF`&Gw!XS3d(5*>8u5a`sQ zuxW(BrlD%ywEhM@4QlOeu;F=KHb~ftbu57&C{DjUGol@KgHtf$orZaPW^<_gC~PH(|0HVC?T4qVX?1UarGMMtt?UhGT;Kj#{`7j>=|j4 zDd6xCMRudeI+O@ag1pzjf@3XDThl$RaPGf&OZ+=ZbfYV6Fwp)TJ~Hkz-sb-uJ~Hm- zxvF}&+R;?mjymA2=BWd%vq&}*bDl#bXHm)PsN{820v_-90hRp8no&n?ar!OZO3tGa zdZ$XxqZ0kI-b%e3eAPQE+4t;`Zg6XD52ufnJis4*XrRNTOV89p^DaNV~k17htF)Oj{Z%=-;_g zo40auwWQ?%p5$@dkxrn8bkIXiQyo)SCX^7T8vA5 z6(yTk18V#mdkFPX#N$Oa*h>*;Qn`EZUPI&WaU+AHR4MKdLZ09RC0 z*O^z89{1p*>R#xKTJu7sG+fj49P1gUCE*PP#KY5G&&Au0fOJ$r4=VV=Q$b);FvbjW z`+DDz=z8l1;Uu@OpLchJo%>UD(TMK`4n2Y-<9Tm@Tn_OxS5Lbpy%Wd72GNFbCTT~FNvN+8t4h&GeV*uX+$V9? zgXf}bbe>;(cubu-6wU=mOZy)KzfgWQ!mZ+t(WQouHW;OEAgT2&pNbXZy*WTKfJY8k ztvc2*oAv#2n-0=Q2&556BvV!Rc0~XjSX8(U!#mVCC?xYx3y$Y7)C7rX^?=0G+_NEt zyUDEzI`-p)um$JFgfHk$jlel@B#x>E;Y1_~GFCKl#UOVq=!h%b`vdKygVC7MrN7Q( zy0{eW=uW)}`DZQoaYEsOjnSpJ#MG+_gb$SG@)2B6c*~ak{4opsu(mGYkG;H_Kek5| zv-=g9KXySC?AS9kb~ha`UiKZ0xKgVpy$nN~h;>x2y5)TakFxgE)=AW_HfW9vnp@NU zTXw@%S)gX4gl$uA-A%{1D#Vu}PQyk?LcQu%Pe#f_8M;-v0xe4sN)-upfXV-WY+@vG zk!(b=3w2G;X>B47mZoqz8^hDgB^E#{E9lfS=X5SnSBWrzQx}lsurrx&nuC+GJ5wTOY!W0ny$t>q+idCDQvJ#q6*!NBE4v7hkN58I6kRy*UiGI z>$-8*tu7-mk#4k4<3#ue>vY+0Q-j26DPeIom;j1X;id-D!A`%6S}6`!J!MF~LafM0 zy-}l=sc=(M!#?l;3MUUBI^&}_I+ZPdNSN&ciQ#n~siq2PY zr5EWG7wK{1(?PCiV?&xCtWM^A^zUJ2fj7gF_ZJs&46_aU<=SM2arR``z&K zJPYU0r{UxIEp~PnRvdiv3cn?Oiv99wu65adZiMhOZqL%H-fm3Yv>#`OZvej?xDOBq z&&Dv-SIHSK0}t=Uuz;_IW~}~vYuLQ6lBJA!Cr7Qk8}~QK5s)(bGg6^jk>M##>#~>e z{#0n|GG#$ep@LTkk4j!q6b!e?u*W_h8W#A~u#A^Ke>rR(-ceD;-KeJ)OM)6Nf`v_m zN7(*HB=h^{U`Z#d%R1a;Ea5cWdohW;lf%0k{Fca^3(f!sYLE$MI)(;2LvN$N20aMh zGqOv#-i1Q~>>r)j3C1IS4SZJ&Z_R3{#q(GCG=h$`uw7o*6^wVM?_Gj3CTsBm+dzIe z^EeYh{w|fapdyzYgMyyf6%NH>BnpSkqH8m>$0^9OcUFsQ7Aj4)Hqn;V16k;)VmQCT z+lzyQw@Xto2cS3E z=D)Qzfv##j4&LEP9ws~mQ;-M0cWr_ncLpj-n(^DE8JItxa8iiv>Ag=U96$zU7$$@w z@_M{uSGV1O=a~t^gxBzVC4RW@1U=OwgjZ6A3-}~z^hiw1bQI#|LT#P`F+r&z)S&Zk zJ(Zy6Lu~8!u21+DjOo~0bqTF|>k>*DM%!+F%bpMn$Ci=?gKe~g&lC&;AnvVBh@|f$ z7)A)g0iXV8nBe+oxbQfsA(Pl31W&JiLL=%8qXlZ*X9%qUnQ*LR#m#s(n8pYX;3)=W z2?pTCX(tM=sV53IjUOj`kuyTL4{)qylZFc7*T+@Qo&e@CkTB2PV(E`;0{m z3oqX=RH*-OnDD`kCgGfk72j<}fw@D41LmQ^Y4b?oF}%;qH4E*zX~IY7IW6BH#NDkP zCfuwZEcA$%;)e-j*j|LRHzQ*NCg8P&1x1VoeiSP9mbnU!)~cJpj8JwB$iE8t zjNqgU@iaNXO(o$;AZXkg!2fB2s1}V7?n&BONQna?(CYVCi#0x3NXBGhDJH>$wAZ1q z$Iu{}ROHQFj>cNRs8oxxg)$r!SX(K~6&RjV)uo8^n6-qruU4~A~MLaD#_wrfk{#|rqj!}3H>%U9Fc1l|&ZMEe5z(-_y z$kc#wqVXZpsnNUBgIF<#mezVUQPTXeH_?caPXdq*~oZBtfqc;orLnPw|iX;-*3Ca^2@GK*WBo z%)jJ6*hj0(fr4@G!j3%>i@DnJgHQ zhp8pZaun16u0(eet_L>^Z8ZwSjOJlCR3{q*8!BYU-ik{nd-6DA^HVsq^ZrFedJHW@OVi&ei>T&6WY~d8P z-ruYEls5bStzuujlE257agMlr0<*jMnC`k`?&8~<-B~1jl6HR%zJc``i_rEiW<5w) zjomPXCME41aKhwqCxx!586aB2EvQ(;6*M(m%h#v|>*$c0h_gb%WV+ zZwT%tM;z|a#dEH>w=Aj6x_rm zb@U=sQTX}7{W8EoH{|>-&KejEdSNt3gRG0=3m6RsLwAaYt8yHUFJc`ezMjE()pt;c z>FYJ$tD+qAd4r3yu502Tef)CUR4CNAqLlpMd_7v{uU+9U+H8C7K~8e-4?NbjoSa4@ zpovF96CZ?(QP9MrQCJK#acJYK1MOtVz-J0AXbgNrIs0Wao-7;CrQu>2XmLZZCx;kv z*!>N+4-NQ;V)@Ewa*dU}r*Tkqq0WBb0x598!4`=LGD1}McHUR*gw;WIKb$VnF)f3P zqsE;we1EK|16FU`$IXQK#B(%DmJZK%fN;`D*WrG}rJ*Z`y8!jZ6<$4wPC_|uFuX`P z`_fbHja{$JsG!qMvWSpnqhJlpDo=^Im9Q`B9uQ_ve^8ihj>IK6rnObPwPtieJkAv9 zJdq06BI5&`Te)K|U*L|tqT-K{-n?h^;GS{cn(Kf1X-z|46ou79a`c4Xt){>!w zH}bp=w%|xT7hvmv@Aiw$&nCz!m2Np)(s#bIIYGjdsf76WXQbQ12iV$RysVV%%Tn$@ zjT|nr(m~=ZoLIK$a3BjcP>u6FB1s3FxFkN-MssoYDgDwDZ*NMNf}^!O73*sYZ^fsF z3_|g0{n9(P>X+WKU%!;D>50(T=FEmeWym9f_NE10%gLiT)*`$9X^^g(u6GajPFFF- zZv3B`qFZTD;IIO91pJi??Ht2GnWsakFpJlEA47%KB znaiX10n6O5e$!kH78^43o8jo(fXr|gf~`Fpt2r)BzVdv;APyhUfrZc_!rO?Z(*c(( zybzo4Pis~keGKsyw9JM3RP^x&*etTjMY=(8i#1I2p#Lf-MBfv>$RfA-=xd{3MF_FsMudAE~3z(`*v z+1n_eUlJej@rF?W@A_wlf%K%EGwqF!yio z`&#~Hvqk#(YeehVPBNtG)vP!6PKIxy#$}!*d=NhQs%1N|m>evg*{yr3i^vtN2}RQG z#}?4kNX*;=JJCB@whW&??0aAw>-`#eOEclRriNoZZZ~>%$|~%%jBRh_M+hzI5&fjXXKIj9NP?ee9B#Y>M zxc7Yly<5vY#Z`LJ5{DePzkkoy@*7(dg}IMAr_98qBg{e^pGRuv2Es_J!KA{r5gFM0 z{ni{#I%?dl!!a@M2m`rF;f{l@ff?#EiJVPeQL|zk66zo`uaDVLyk!gGPQtw6f`8H` zyovLW;c;L7jh;4=V|x_hVzCCMHsNxL1|c6RGG5-0=(ukFUeoN zx=0k#OW~v9`jxei37Rr3L!sny;_{89xT>i!Da5Hhz5;Bw&*u5ZmG6$2I&cA8yiT{vx*gOy^7Z zQlmOBagZJdV0*!68hrQ$?Oh%rjgOcpkmV4toaneG_*uBKpIDV5Kk4|IyU={kwo(-; z{qPNmYGdj&Pi-WXQf*66o9k!!t~d4EFY?Ma;}U#jyHGaC^8T^`%WuA!&OiT8`I|TI z3Vse%#IH_~r|ww6z1X~W$9m2fndkf!yJIgb)IIPNAa8(oVLHJTiqQ;QQ@vVV{PuWx z$J=Rx&cYKFCfVN3DX{StFz1P{Ruwavpht^8JV6qh6)Xik&nU5`t=utZ&U z7vqk&BXMf9y?pumyDP9DjLXV<=uQeQ=|OBrAg>3D4QCM5SYPS@(MglFV=TTtHSclf zi`Z2*V>iJ!nv1uApkyzgJLmnzYBU6!XhH3-((zJ!7WpD}`{=!vI;k@bw`sVfg0XNl zIkkkdpPq;BDdX!YSooGM*z=%V;9!F}ub+UeBNV5+Fg_l{M^UbzR}=FB>>)UF(1hnX z)w(>-u@xQ2vDNT1%)Zfl3NB*d7y*Jc_yUQZF50SwWU9F}3EYb1^4V0DhK!su=u0eu z)!;g#@RZAojC;ynw->Pqv1Cc&dJHU(z&zp&AXxl8_c@34RYnK;hEdGkb)!Q z*s^ZiRkqRlc=*t$MCTDLT~cAryWvk$4wkZJs5X)I=jomD-*)|V(5K_s2Jt8NSQm~- z&&G+)AA;qz@7#|Ioxi@5N&3Wk?h}tebUlNJ&K;Z8!ctN^2QY7+Y|el8@2V(8Gs&*K z66MHW%}tU>AiNBLkWP^NA5+8ikI|)=A&uBSA(?i!j)z8!fHN=vM1#6haqfIEv3`U1mc1Gv5c_kF6k#F5Vn8$!p(F;8*eT ztM8knRj4{JAmlD8^)YBMk3sJ{U=sUGSV0Y688cq_%8(&K-&-BTTB--}>5m7ozM3%B zSD)!M$8hUWJB$=$^|-csmm&307fC?@nOgdmUkA~3DnwY4e-F^bI_`ulwp4Ld^4l%@ z_^2!LLx0ORu`6J7xK3R$2m&HTyc`rbV!|;SzNeWV5I@fFlidEdk%NB{TS&HI@fJaY zJMMpGY!~f9?f;N1dkV&15?knFAZx*Z^1*;gz<|hHVFcd$Q5}=;E#eJ<#4M=kUPc61 zesj-*!D}&7@@rD$)Yg0O|Euk-shqR9rFDWTcpW01z|?i`Ul303I!wjt%JlcEYsBW| zAH1PLS1bopsc~c@GU8;<$XLrhENvPG?vlLlU>w&gKXGt2Qhs@G3ip$oa7d58B zJm*lN7ESyKP2)rFk|iMTk~bf+!~i)D1WqMC_bW$Qf4UCc z)Fu&M-lBAGAD7pDY~^qMT>kXqSbo!S`MZxz+GmiNw)K?b@}N&{;I*GO&-o-w6?=mR zjhp-UOatY`4(8bPnY{97awIs5e^1kga?Zxj9ZS$o>z0pc5+QnYv3fQ3T&bj7xpvzgY9rPqwkJBF3L}Sc2C5mEc(6_WCpmTHzIfQ zmCrWt>K#X^>=*~h>GJL`N<%D2*6L5P=zrGp^3Ib})aU&r{dTe<nar1c~}O!sUOR zOqPe7c_POnf+@!#_)~ll3gQ%6aP%s2ujYx|{xal$p2_ib>3~j7{4S4Q@riubcX>(w zHPd_Fy&rJ?#PCpg`S+*OJXPO;rv6{5tLrEZI8S6h)$td8=g0D@&guWXs_#3e1)RT( zs_yT8OFrF|rBgOOxw}7drx}E1E&e%+Zl7oH$n?V;tV?vhPk4F8Sv_}No_|*4&m5ND zIC}#>@`zk{MZfVcb5y}{(z$m%1UYZk1k3+CH;p?g5B;Gh_(O=&e`Q}el`VQ6nDr07bcFQ z7j@MX%zn0=*kl7>bN zi|PD5&&Y)r3;)03-UKe{s{0@R-1`}1*cTBM6^2EGK@dh{QPBa+1Wk0pCG8OqHDC}$ z(Q?Td)XcT`%_(;mSkT5P08Qd>-|4BH;tT&u^mXfr8ke(&>{8AGe*`~SYa|JN&g zjpu&O-S0W~-0j?RdHV6yn|{=X!KWtoWN+pEIVJmJyK7Ej(*9ixw%oz3HL-{Ltp3lB z)p4OuAcO8O1PPq>`BcRNmvpqB6zJHo5!JfFUL^-st6v16+zTsQEFn`HRy>J@tBGshS{-q7FgLvg9<1YUA6XsTI+%BOYxRWIg=)2>kNj?3W2R?z^eHqDw_kEpBG`rG>bduqS0cgl{{XYA=-w;K9QueFiv zF3(@ybO`MmN7l|@<02dW=VaD?%PRSSH^oH8D)`v(;(cg9^D8CdI%9MBlgq>m&ie9} z`L?~BagSiN%i#4`EO7$p^*W5EjfM4~ZioEFtvXgWxi}p<={_#1N8W zv@XSJv~YmbI_#hb?7|`}*$87r=fiQXBg`^mt2$D8bv9r#qqQITdrB=jY&588tTMJb zR^LGeE9Q;8$v+V5WS9q5{S{-YH5i*3o&hZw2@N!MS9wM>V5@hH>fZsQb@pOYVcE|9 z*o_h|c40}}{hau^3mY6*gv6*#3se|X_m6{OKv!1A#~l)NU0Hg!=J3vkGN=I}y5Uwv z7mpXD%nkiL4tKplxOLrF^@MQ3=e*$I1EZ!?asyMG>DbPg2rVTVjV!KL#bmJwfHc!NbvkWh2?leUJQ4GY)aCVnFnzTuSkAvZ? zmJfebltnO8dm!sIm^w-y+VNB;p1XL zV{nuZa4t{080ie|h7dnTvLrRcrDu#&vxdPq5^_w9VzE6Ctw{n+Xd6tDtQoFRl4f`G zBY)ocka#qTjpUaPh)<(HWkNz_sg)#*R+3uJHVQ*`mg4t*qg{|+A(kdm_#xYa-B}Kc zBTQymQ7GSvlQrGMP+Tj{SCif0_;$lLNY$k4e8_esn)PA5;aktXa#USi#$3Xx5UWF1 z;Z%R%2&(>H<=J4RIfuDB(-F_avWNMT{}K^;Hk&UwAfDE<1$@c@8!kf!vq%aR7A`et zl!1G~szYyR+^iW<4n}FxREOP+LWS?`$r^hQ87Z(P^XdL!ncenlGS~MHJKXt(23$J` z5j2NG)WE6n?2R5xm(g2j?x=^DUWUn9CSsCc)_>xM#i$kwRj$8^G9|ERzVKfnH-YKf zzxN83Rv3tuB0S|3`=*z8G=VApm%BM8ys!}V5_yW4UhF8J{)+g%7kkzVLF)st%b0R4 zPdt;z`ltv^tkf9wU7om*$Q~v{lZrrH%t`D%2O=CHfOs#7t>uq4*rpiR*R0EMBEVE1Oe!Eatq#&gy+;m2v2589>qCdNf zpL|)I?#~kVn=cFB42Z#lFN^35_Uss;Fxb;=_cO08zW8N0#P=EZR6ec3EvzxG1dC8w1$qi_hGpL z6Kf3z@qUf@dnkg07)g%S=wcxwuzhCrwPviqjSM|xYt~PBwtwcZ4zh!aosEqix`~ZJ z+L17#8ET*-FA@+F9=3ftj4fpR*o$Jqa5jM$vBm?Z=JB;g+grm~E8`!`w;dV5Mlx+P z?H`19GupyT>>l1e{sp^;0Ut})t_a7`o#!P8yL=YT%jem)<+D#2Km5E{Fq%zHZ1T7+ z`~8YGyF4BmbNwKGe#&b^)aJ8Y;D)Fow=a4uK|f^Nehll*`1QG>?^rgs%V*Ew6(^MU zEKZ~k!z$Rn@l7GYVB)>8Xs#pAiL(3H>@GF%@Ik;#oQ0G5u$7L0O~g&V-p4lbxzE|2 z9tT;&Kiz8!`3HNN@tJ$Y%M;j%fO#i>Upq@dBU^TfwFPX5YeV;$z1Yz0D|Cgd`~R@f zE{Y4;Xh*aTb>(}-YlUp6E0r;O1*Rw2t`vr0kMho~`k(+e+k-_ckU8Q6)!o=5o|wp9 z;h*dk!;6{0J(fDp^LgUYV%Es>_SyzdV!`h2pm%*Xu*GI}oK=d1a@HjY`y5%?C>Yy= zCWLcKB??PlJ%2vW_UKerED#4H8D2}KY&$e^I3OIZCM3w8{({i)Ie`ukQF*7{rNKvBb8Fi zvPcPLwV-$WfmFK;HxDksjyknSuW(}{y`w@81w9lfDR}nKfOijS*6>ipf`|r~LujB) zXj=Q6h1QfFE2Ck}x-AVM)!#C7zDw9wApB))@h%=;YB_KT{q5|p zMp$86{`5j~>48h`p@tl`?CC{tKQg}L0Q1p>{)%ZC&E*QFNtKzsrF<)_#%}MrW4Ig6 zz@LIb)Rlpb+liM^5WV|yFAMgN)8*wM`Ylh4l9J0pjSW!gHD8yz)VXLwqTdr+mbp08gdzQgvSCg zCj?huA{?s0g!e#NIY_Gn*XYV%4;!b|4VH(|e6;^ht4KTcey%}_8n?#`=JC`_pjnQT zk8RzcGw|Cr4kxT&zF?TfxQHVFY0mZjv^{kf{Lxa5G(da(7%Bg4YE4*K`v&RZYMbHh zvCsqn!xFzq%-CAwi2?h=aEq@OnxYT~krMWe%h4pB_+E*_-Ey=DZvUCp0T3l0hLW4n z3gu{p&Cr-^i!Vb9l%oYGJk`|O6&@{MMhmE#wZMA;KNRVdp#{p-76AQejXgEk*ivqA zT-;sN$9Mg6NicGSySLc+n{zNzx)BRA0?TP19XGQFQmf#~+Z9;MB;ILx}XLM1TJ{L<(3lQBuzEj%GZY zs%CN>?}J{ZL}+^sZ?i3ZJ9Py+TyTKiHmX7e2>2n@A($=#@lQLGx+9Gh&1xDDx^XU#@}h~>-{^)Efc1K=EMW5 zK=Y}fIWA+WwDke4ux{&94w_E|%?~A_keUHKFG~N z7sb9)?i}jtWd}Sx5DspHKUqEA3;|YpU?JhLi>d{F(fG0hi|3W7u9;But zgMTe>UD z$jEc)??#^Op;Dz+1{vbXY&`2#5dWonW+U+iNl(jVFCf7zWbE@w`^?6xewmH#C|M+C z350hU4PDr6_wY&3o~KCf<3OQpe?Q(w%0Gz$7A%q~Ur&d+u3fIQVj_MnlP-}l^R7&& zhe7k@912~Cw6&x@j?vcss${9$gYCV;&e|;p9X(O2Sk#aPBRZg@3sO{b^7A?hKahp| z=vED>ZU1llwQb^4mmR_^T0ND7DWZRVZfW`-s|CbQ9?e~B1Z3ah| zL5R`wibLbQ*W)@fbgCTTU1Lf)n7kBBUIHe!fXOXG(43S|3Ah|j5Cz#&AV|=+&$<`H zUjU<=C#FG(zXD%;30}F>F|+Y9_~c3$c%@5b! zdt`JKHS*WTLHRfqKRxh0Ljzyag?@KP7y317=${oH`X6Mji!i7Kc=w$ip}r@gLo=K; zCk4GC6oxDiFGAs{KyRX8S`_LE^tyJ%-blTSeZDXZUiU!l+XAL8vtTJ0QEE<0L(>yS zUj}VSyn20P&!_9?GGX*Gh1TUYhA#1vB+Pe9}dU2Bgd1gue$pi_*Yr zlxn=o2p4hecM<+JzAY4(c9tnJCB7U3PJ%Pg33NRbhk(7DIO=*B&-EvmpZ;6a<{UR*Fx-*GDCUKWEoZqvB`xi z8iQ-STMIvUC-g?@ZYUCYU>jABg40BUdX(!H9*r>rF;|-Pm#; ztEu20?JK9QvYK`uUKuiVRgI|tHM%AT80dQ;^NJe;(*y-jBlHB+K3w<&!?ot~*j%J3 zI!(`GU;+?!ZUSJDq=8gXsAmOXF-BAEbCEf*G>zZ2!(lqm`dP_=B8z91dSsl51AVh| z_EU&CVJu3!0wbasBO=XS%qX>&YxaT>(Tow%g85!sd?`jmGe*Qe%yuv$mSIHv!~75< zqQ%^1NGyi{F*|2Lqj!eTRoMJbJl_?1Fd(A*HuoaL*vKqbOa0h--X zCG;qK5$EwV%l#iJVfp{17XRByPz9(WVa(Fe?D>N|e-rvBEvsUD9P{@wY#%K5@>r4S zVT{kl$tR83B&aTPkD6pRE?2DrOz8oAAmG>pzPNUYx(e{mQR zcm#=)B%?%nB9YT5j5-~c-PM-?EUuRUFlTNoTn@w4&|t1c?h}KJjdVTE3RP2Lm@>3I zX@b;&aa;=uVvs*uM6|{K4+{v3sQw+^!x(yWdEq#Nb1tK+;;Zn2vFv;B9~YS$BXvFLNPu=Z99OAd5);)zaw1qoBP z0N0|Eo6}&b1ZGOmP4Gm17|*-B-R?#zMOujqW1BIB9s)cibPWUjH?U1cx46&1zYZoQ+_2PrIVXo1(dL5kY~^!Ii6OMc4MjaJjcf8{^IPdN<#S$F!+4{*d!3skn&SWQ#m z@1`|2YL;fkZ&4W?b}!^0W1|)KunvLKYr)~3lCfc_lhZxBIz*ew(Hh5c*`q6%GRm=B zZj0AO0pF>OD0GGIgms{<%~Bco94tPxI)t|*!jKslORK>`0L|qU1XUtDh}U+Wbtk8D ze`6yRnmAsYi059g4Oj%#ASyVCMM=ZsX(K?=uz2dO|E&@h8iW7OwP;fb>aKsRgk-q0 z63)U~)Pvi0U9;lPp$3OglSs^=ID|cosgrRPiv<24XpZFodZUIVfSMp4Ujw+8a4^K; z4Ki(J{%S>h(7aR8yjNv^y+26h15zDizN()e{BUWt4^19?K`y^e7HsYyA_<@Xcviym zTZ#yp`GaO*-1j!WW{L>9eFKuwEW{UNqsJQ#q9??Gf9$kL02qc>-B5`9X4zBkiSRV_ z+Kis#No0oqL7I9|c%Ya~fHo28 zF?{aD@Cl3AbL#L2a&3S#XJ-c(>vHl19SdEBOz=W0PyzM7(p(P(Ld~h5*YI4eetqaBnXX zE@-y=G6*0~B%+1E71Dj!d`+%|#zFpOywU(!kx!D4!g}5jmdtp=B1h2XS$O*kGvUpZ znA<_pQdsl~80NtnVp`gxLBerJlIbvQrk9>)0o0WAz09=P6bq?{ zC+oZjrxp^0a3uD}v}kM~u}x&8ae=}^5ih@xIi6*^LThw25s2M*(9MUM>sV>pCD}(0 zWl}voyGH)U(PVe}lX#`X?+m9$I%}vFcxH933&E(n6H5j z@j8T|`8sAk>cG@GZ*c8T*o^)$Pfs?~9Tr(!P4dS{g4J|>8!Yl~2xHwW-Y^#Kdn5G+ zm}a3j0BL_6XT%LhVUy}Q_StDtZpRssC;Idyxubp;j?sIfTa=ZSrxkz$W#9|uU|a@A zVz(h_5W31h)V>zV!pBi!PlToLt3bm&z+rl41*GQ8*3q2Ytg}2XS-e0Mr6hk-V1nQ5;PxPa||{!a37hEa^O0`kVr=rpNRs| z?Uv=punrkhrkj&66GfqjJj8%KJtRxOZg`qY%hE2RyATHwTbHv=5O2Zevj{|ie}v)R+w3y__L3DgocdoC<0&v}C ztlcg}O0`!Q#%nDWWVDmG0wtqop4MP)jY*&K`ESrfnA>MR?ky?ct}8Un!Sfi7R=~=W zlzK_g*QMBN&vwwAGQS9ECSff_lSB?klSCQNWp?NvpugI6V5vg!?3o#x;}muGpb#YL zAj2U|98!wj!=%B1YD8;m8WKr(Tt%x89*>CR`ykF^h~tYmdybW-UB$rSgSGT3bQKD7 zoUUCW%;N~-r^>Z?p zP>6aY;txN+V^hh`5jwpHQn55xg!83cq*No6TBa{ z{yvwdk%<=UTD;vDgX?;9o7ITI67Phgl|1lyoQ=X)gzF^C7w=9_kf=V z;vEA?h{?5hF*()(8eGOZ!W6Kad3deF8?vjy^|04sOn(mB+V3HP9f{H4kG?yS6jgV@ z%GzF-fUAJt8TcJX)2;wXXzag+y*J9x!}+$O9$|7Ay{pa4#9J70p&_Ups=k|wJnol} ziR zmJz=>OR9Vq9i7%j+i`(^i8dy5F*e+IOnhh-+>tRoLyH0Fc_flv7P`no=abE{)c7bo zCgIt%6@Y_c4WY{k;@19=m^fUpkHHMF2aI#Xgno@pwH<)(;I{+`p8$Lo3BLz;1RG`l z!FyK6Ar@V4TT!9F`uW?SzP|{E?vv7CF9B8rUU+?iE1t){`Yxn>KeA=`x zi;4FhVOKRxYZkhRgG<UEmI5EzhsF?Onzm_u@$jV&Ga93TP`>%O)^h*-IQ;2Zht>MDf`=Hi10) z3ARM$h6LN|PqPHyz`NoVoF4}b!SxFdZ1Kd-inqzN>^B|(J!_MujYo%gWq8}~9r3ov z-E6X!Z>q5^e~ATYyxo*>7|@^~AF%FmQMaF!g!ffS7j?TqgZV%jNkE!`AmdgvHCFS@ zvDE`b?*!Ux&JIJnY71F11(} z7TmA`-|2A?cz~5fw?1YUuJD9!q3MFtRV(BMlMm|_w^J*8(Dnxt9PXH%AcgO?=i8dk-h5o2>gh|7mG{u)h_Hj~-Jr>vCmLrVnz9BR_tmx=+Ovp#N3YodJ=hn92A=jfs2rM!ohYE}px=8}ifNEUQSMSYs ztvg#Fwft6X3;CWc^v*&WHAq9%(EkaC^XhkJS@8h5NE4st`FG+d+z)0b#(~u)FR-2d zjfF6GHBctE+3ig0p=s8x;=;>=-^U-AXPe@|Ps_abJTcgZ_vM9i#X=t*$33EL&-w6I zJUR5R&7Jr*9?;X~*O@=&!B<6#%@I6-$3{crmM5bgon_%3$tUx#szgO3Kf$}t76YPq z77v;&7DgfJgH=6^Xo~(UJDK0D;d2IxgK21ikEhu}(s?%H?+&yT z^yQPL^K`#vm)bov_*xpv#e!@!gkObNm(61nn;km$hyiV=c$5T6 z@4u(JOryTNdn=!Kjrca3XYz|vg<%kg^K7}TY!F}0xm<3$KA6{WtX;*n9G=Hn5Aj0| zKgOq;#jCm8(6P{rX2yl<34phfYtabzp*)9gC=;fk{6+pa3 z-7r3Z_bwCHhw*7Vpoi^&d-%tU?~Abw%p(pw86(2(1^49W#kcqJXWi%Ml{(yH70sjg z5YaS>PZc9a@kI9>dSzN$^i%wjUYJMoCEO#<_QPmg5;dU{&H&M9yhHiw(X92c_r)nw z@5F74Q%df{?Tb^2@5H?uXM5{Dehq4vQ^d>T`2ha<6mcCe%l*xt!MGPCkyV-V3=ABsJKVp?Yocg1PH7H_DtP*Q`Zwmid z=Eq{iKg-Zo@v$~{GY{ABS0)PmG#01TVWBQOBkvS;&G84Z#0L+D8u z341@pvsh?lFJ)z^dH-d((@=f<@sN91Pfr{(c&-FF`~=Fksd!Q^CH#cd)P90(-9nD@ z5QOWvn7^TE>a@tsc4jf(*N(^CZ(Fy5U*>$xc-z9qcpl@`N#cXY(T`)t+Y)McFKuvU zvO-4>M2n-K{xYKe^9C{VNj@O>-DIU13;f&sF2#wrp5zf0k3P!zJN?!sD_`7+yQjBu z>Q0=}TlwHl+&P1C;!a%W-pa8%aeY!0sAYE)B~PI@X7mxep5meWa3AsZQ|La%F@itM z2Sk)$xI7e!?kwNcP>PEemvCR@7@luBi>E9)GmoK*$B2nf^Ko4Q#@Gd}_0)Zat&kO9 zD)aM63TR%lQZa~sKh1{+h8vW!cE*Oir6v1U0l$a!wxzD;nT!XI6>~R$rF_PUO&j=Z z{_PkMyb&__-O*yeMjq+eCL!}io}wR>qP&EDcw198^j4m`6W7vPyuFb}^m(|Cg58DN z!~fJr*>ETB;S@yxSBOfk87(35e%-b$r{p^xT~f(t)Iet7n){`f?#axzoDPQKdQeH-f5v} z>L`)0gPV9^zHQ+S%zJr658I>vZKUq9nv5oFN#R?)E!WonRECnd(`rgH3H}0FJz}Jo`vM=sS-S0m z7kCKcKlBjaz6jw~*;_pL691a##E61@yfgn80r&A@mGUrR_Ee> zl&%S-Yl_WD7Z={+^_u!4)+C!~;wc)7qoDO!8&asC^~Lw6Db?Rsn=CnMK^@onfWPIx zI9mH(-9<=n5;rfGlW-?guD&TXOT0r=B?jBVIQd=%r218mQH%F-yx99l;ncp|imiILui<@Cm{2{T6$%Sz3G1~mNJj0Fq474qBm(O#4se^dH zQ%=UHJyNo5_LP70(lo{1CEG->{2hpwW?SA_9?5{4=2v8X!{OZ9)r%i({>Tgg0JZHiA738C_9JU`X;eW;wrBcMv32bTJ( zyRi}H1CLBSHgx!Eh{0q_pl_fD_TzC8>=wuf~i?;vufa| zt~DDwOUyq-n~ZTCx-D3w>QVhBs=Bn@SIMgPQGEK~R>t@0qBxZ_2&=vr3m*u)x1Wli z418g*)KK(3-ATm3J`$vimjzo*rF|tl3-6zD>aPk=<*R&w@Ks2I;yO%185|as)DoTb zL89&JaICmyON+hF4aj5rB6jjd0f*%WI`+`Oc$r(RNQ;qm+7>UVr4?JoVr-0D&d(%^ zBQbI=kLn`=W90}#7&6+jsTvk^B*R#^!||@T5#OWWwyO9ry$S9@r#mlMOo^4V_}pYs z7b}NYF2GNBpxVTwM@$ii7MspEzccY&C23R7cds#VNT3MaBc@YMzarJo|2Dsq@N<+S z)DQtTm4Pf9Q2AWt=nA*19G&6DO8)K?%ADiFMb^~6YSm#24Xq z6uy(b9&ShBJL>oJ7T?6l<8r^b6))7V8g8Sr(lxi@h3Qw_iU*A>xc{vDLwbuRdde?& zYlj&d&@t;;aWW)E#LGdE&l&LU_iwDS7N=OdvH7yI9aLjmrOKn&<;g{7%q{X2kH*Wp zHE{Wf)C4(^T>iqWx?+n0#O4G!ou5v!eVQPT;}$QZXDz8Vbx%T#tyWVWzID24(_Q#B zVyi0*P*+iH8cA?rwJ8sfc$nA=T5g651c9TS-yr-Jk-uL@!#VuUN2?Lm*M4Phiv<{lFNgm~?(i`-f+b-=Ewbr)Eeb=JiecBjgD; z$WQL7nAo-XAMB^hkZ7F>CBsfYWMX*Dy3q8c+!Z%t!(c8bO#c<6#lr>>YLG+jolO;# z@7qs>i6i&xWA{g(uTh1bQS-s$6xdFQ!!-aZQx1M;*c$EO%+}b3%+}n-%+~SvrdiI< zcy(-EaiCaXkTdz=L~#NcaD9@vY>@i~dpQe78Ij&06=X(|=-V5eY#K7UlkNjy7DYiE z7vF!Ah|2vg4(lNf>s4`B=&$^Ma8^*u)yfyP)R=;SBMQ23^41zt0EGi}ZAi-kONB#e z>#luQ@j-7nK>sZ~vDN+E&(OXt!s>wn&ZbP!5^c$wktBSRcGY{c^hER`z z@?{LvSX{D{c=86~6Pb3l^G_KCH|`Gq37GAi;=0Q_6cWHqCgznf6D%#Kq4s6SB~JRiQ-6KRCiCCc%J_yo?oJf?k7j{ z4&YG0$Olk_QP`v?(c^*y^?B@sm%>B_Q3G1}b=0>-KRLcXA)K9Efr8X+?NfyeyP)kT z43XLuj`qgLEk>lvQTpOGMLd-7*HwG7m!tE%Kw;W2m#LR{y1yLCU+E=YA?Vpll`?%F zr*LhUtXG?Stbdiy*Z}1b#zBB3!yWI$7r=^|`Jaw$g#~Ip zl3_j|35vdeB#NoV>#4~B*CvP)8FDcHAwhhdA&(Zu0dkav=8|H6ww%n%P=x{V41P~9 zo9{rmFXO)@h+LyQm&?7x5uEbx;`k?MS_A0Eilo)W$A5+%UOnD<; zpCCTYlt1N@62uExas|5~!n5URVof$>L}R3yQHKQaO}0Fn{~T|dGDuEfd{?|!cNcPg zAzpY6mM8Gp@uF<7ypWHI7vBt)M|b=d7u}BHq^q>AwV|x9u_X?Z=!qK#iSc*K8SGQ> z)ZOxUapP{eD=Op2BS!QeB75`SdWzg3@)G`ePx1Z`%)zep6rnkCU;au@F)l|Q&GN2*H5oZ6&fbv@ zV`h}wJ3g@^Xx&iRpKmW0fkQ!$_@3gip=h2-_#P%F^u>SxcFc8P?@`2jyHAZ81q{*7kAE6OlFqS<+UV z1z};)9Nwf-Og8z%i3P(U`KHB*XNSuMeHJx`EGgTwrIW;Fn4sXoLRj59u?{>8EvmDp zCcWT!@`N$lf!85H$-ljFVWtmkBf`Rq97OT-*HB<%wraP`Ko$H7-?Wna3~{W$L#3rj zd#;mm@mJPD?o0Hot`)n9=kjDI`KilGEFHyrdGf#xv5IrKh-V9vXf;X8ND(R{?rzb-{8>2FRSHsw3uNrbgUWT&=V8e2eDwmgs5dDgADwqT|<}#bskWC)Egd(^)+2Qut&#VTwhUXpDrtaaefdtfUQcSp^@?Q!5pLF<>-Jr!7Q zAJJI2&w>0E+VD5CWrdz=DQs}yys?D8u?Q>L=t7kIQR?2q{<;a_%8 zW`JqJ%(^uCw&}%VCd@c?>cuN2d3fI;2rF5an!Z8Wv~Ji3jHe@kG8Hq4@-1 z#B``z2MTAZmu5ObJYFtN=gZNaKUFxsdrcRMv5(U|G<1dt93w|Wr#sWiL#aa`f--TALt)3yMciJF zcxiLRxG{3B7m1mRl-OR$TG?JH9@0T6!k)%K z(65bu(=Gpt?Ui#KC4=p+{C{k(6ltxd=N$gyT^anIKv0l!7y?rhDQ3 ziR3@rBjAof-Kl44uXTXNC|TtMb!p=te9Qj__**DKI2v`^ zGt$ZM=?VzZL7#yJ-nr->>N@fq7UmfA^qp=C6Rb~e6Q&3%A0QG|3LW&GL>$!}tapbS z1ZvLG(Iyo6hv`FHxc+|Vq*5449Hj5yj6|(Y1<6zk5~P=7#H;s#OLxYI;p61aK@gI# z>_l>Wte+D8hL4hU!&meeCwJ$o9U;PQh1h&NChb-zY=T{wDJgwo#FBAHuC9lgT!tE0 z+V4o}JOUg z9RgmtUmi7j0rC7IdZ93=?jYO}1S!LtNoOM^#X^37WMgbU+=c7VZ{TLyINW>e5jxEk z7h&qjeZdj-yHc_4AMzzlvm^xyi&gF{HcY_QQg{#B^$BtgV@;5HatwbXT9g&aq1pq{ zn37-@T+|fG8~EyIkx(R?`1{dfVG-t|MbWnFMKX5TL!w1su^dmai{%bHJJ2?!Scct| zFS?7-lObI`>Ta7o88cdbAxeDn0QPOBN7-^qWE^4t5M|p`D(}MvbNHe5VvJdarcRWY zYnH!?X-Wlu|8Os>Z82+V9afro-6ELKNSCapk9m;t(gnPIaK63m(Q-N5jaNm8x=MKg z-x(qFGi1RFgT(7IqUb|_uhp|dTil3_1yezQ;XZWZ)q!@5GF1+$lL!)&k4ljq6Y8YKEzP%HN^F~Ne}hVMef%NESxKM57VR(Z0f zUfL2wgs9}(LIr4G5K-0gPX3=z+lgvY^b=v3|p86hc?J{ zXNVZL5(E5YbnGaPJ->rYPtqqdSXj3MSMuLqzBkz+dewa-Trub)CiB zC*RBLQuK(~;@?6ZNUtnNpGr%l zL(+8Vm}F)Dk>*HanU&oyTk${nhT~rzJBu`WON_ZmZqj1*7@xmy;{TKa z>i@U?`+MvEIMYbWx4vQvdJ{*KWVrUH`c39}pTQKHenH?LC8xir*e!>6>h!TvsV+Q2mnfdy zD&OA;ahwS{bDEMjWy;LSRie`t8E-aH4)Ftur%XwhSvq&J}jQwTxn0V z%$ia#bMj}&@GE;~EYHeM)R@^Feg-$K6qsF%<;AoS!t)aI1oh=QTmK05&oS#o^-BoPeB6suu zo!qLI;g(nX`=`ySnm((lpt$Oxgo;^H3uaHAQB_(zd8RHS!_lsP@NqW9ZFO^T)7>NT z?#%&hGbhb1swkeUW@B--Z1FUtUG%`@93m?kb$U_hjC&_nWvj${fOs*fxV&iQOd=@3 zq&7Z=+k6ZTA4ePAS&rtOKPQXKe^?)A&?gzXGn7GkykAmJp%r+DNaM-hU`+h)ax83fItz7TD zc6$lnMZkK%nc1>^K7CCN8B7wMe#t2}?byIUuHN1JH}Q?2fP_1hQZjxe@XH63hB^IKw_Ae-l>G4{ z{LU2d+iP++T`bmb^w+hEcbFP63LlFRxhLqN9q%Lhy)MTF9s+WH|C@HS0NTjcf0IT$ zaRjGBZ>#~~2!}sPxhH<7fHMNpA5Ddf_-WRP(??`O@S(M6XXn_Y1AZxfht`Scw=g9> zwNB&`^cJGxErk72*zHte`qSap3Gq$|3KJrl-jcObyut3S0F?O%N*K5x0Qw``Bqy$I zxQBrIu}$I>4tEEni*0Z^;I;twxex=6qN3E*+NN;|ejm2M!6=J#6}Y29EI*1#r{+m< zo)ueBw@FI*v*0h@E1=afE+kr#OBb z;qI>$p>N9rg8l34b|NeNZNZOvn*^(YZ_C@)TJ9 zdqezRVj zXhIWz{*v%Ki35*8`^12gnBNz^EEWq1oKnw5asGX5E+sY!&ky8;Uhyx2unf)yn1w8cwm=3P&DNl(h!C%xDfc?dX8 z?s~vWs?liIctKmf9)j+um-a(1_NABhrWd>Fh3@pEw|1vD+v1JPm@WK6`QKbTc}h-f zKOGli>2He@*1y5TnT=qD=2P;J>`#ys{W-!&(uF&|zW^26`hV^G);Z8pO^im&`$X<0 zZ-HYyIqKo~*C#m1xhPsbk@Et^;<6|GVHi^X9uoI`3T>sd7{{kGKWV>M_Nko5#)?ni z%YG3ppUM_XJ&_-Oe-pI)T^T#`#W?pj)!dOU^8Z^4K>7cj1yJ+<8w=pb|L-e+%vV+;6UEfbW+Hyw5 zPlKNue(h{6XWZSh*-^nFaS)Xzsw1_%JTB4{3x5|yL!>q};Fl=Jrwfh~EDE8GiyB~$3`K)YbGkKobT1g{Yt9C$#{FIwBj%hg^rognQA;cBQY zK>Ujku9mC^;#Wc(ayI25Ao}$H!bO`?lm-yD1_tQ-s)gPu4)@R|dOArb>5xzlZHmV< b2Wbu!h`uq}fviBx1<)2buy#=$p$+?gaF8`p delta 43423 zcma%j30##$_y5dXmb<3S;q zMuxV#bG5s3Ar?l`dv)3tSE-xhcbKb|cLY0~sQbG*%6wh9%7g^AU-zmDAfh|2Laabo z>xRn&e_5nyf*V?f_yL4QgjWz2AQT`>M|ct8K7_jv?nm(aYLTc%c*cW39EdQ>4c~)! z1Hx=K{GdA?j(8!0Ku8R+xRF-Gg$OI$@EoC8rZGJar~+Xm!a#&g2vZQ|AtWH&jxZmA z|3X|5F(clFu-Xj|LA(gz7KBuU5eV4`lMpHq9zpmQ0{=aYuo7Va2M94a|2~Jm4?9z? zKh^GZi94R@j)M{Z8)2Or=FvEW#}L90mLilRJcUq)AV+u-VJHIsEp|oM{;nb#LIwkT z6yaHf8ia`mcOvlLOQPY6_sP@jLF9^qJsPK_@65WDSq!8re=iR__3Ob*W zbd7MYPo#Ic6Rz=zr8AtlU-bzaycM|Z2(bur5ne{{{PNw2hY)W@7=y50_}M44&vK-e zAn;zg1Hto4L!wmB`6kkh!UW$)nkC%to8ISfH(8H31L0OT%zJH(u*WwsXAM%kUwHqm zN8p3Oe|!>bM0f#VGlJ*01qt3dE-fGMMnNZkE!MMcfw=aQkw`)=%7iX?7JXKr%1FwD z9K~X4m#0!N16R)Pz!_ZjgwOhumF#m%Cz5mkRER$3Nl{sLfsRr_L5f zlAC+3-pyx8$&C#==H~M#8sOAtMmM9eZbI2j0=?^I^i{o!kw-T^?9N~B7L>S$@{}jP zyGK1k_N#knBy-DIKUwG=f_Qh!Jd@>|o6%nPBzoUn!5?nCvDzh&XY6erf!z7M+zo4Y zbp!}ix zh0{8<&-?}D^B$Vr^rvo-jLL+E`{!_NMr6bb!S#~~hx$JyOc^kMejzL$prLKT3j<fF3hfl^u7rgBze81a$o#O0r;Z4L-V6S`q z9sHXDZ8zaPcFoC~@OwR$%uV<^e{ogZc>^BvV4J(Z#Ty9N+uQ}ZZ^GY|~AEF!Br*Cz>UA&y3>u)e^inN4S6W61ws76Su32hO;P|e{@QPs1do}0?YCEg$3(sMYmwkR%7haSUdNk= z|F!Idv|T5V015u21kdd{&#zsA5Aq-pcS`Wib>OC5l;A_1IF}wE-4cRlhjG$>xIQ%D zZYDgEOYjjAe2@f>jsDs%N`jBNh9yL6k`SULgm?))MuJb3;JJRt62k400vZYaE(u;M!IwzzItji^g6D>o=Qm%1@9VK^IdO@E(9e?_u~~xe zFTt;t;N3>DlUgsq50vD8R)Y8FVQ2lDC4>Y?fo&4JL4w~U!6!=adnNcJ3BE;wPnO^h zay*}ZdZmK@$8)37#JxJim4co*U_&U#A4mEn&~^q6BZ^XA;k^TS6G>LGt** z^;IxTf|pD1{3zx51xfHuBi~JklHjoc@}Fz{X(fbA7s2^AUV^`-GC@g|;73XFXGrjF zE$yTlCHT>j{CO8l*ISk?A>1x0V3gqRlHhYB_!0>|SAs8-;KxYt^F4SI#{L!wVTp$T zyyslP$z}=uHc9@~68u;RzFvaQli;6~;Ku>)>VG6QO9=Ur0^20`0ttSX1V3Ja-z&j; zj`W<|BEc74&u=0JB?Nw?^!(Z+_}e{5#3v>ANfLa!1Yabo;vfm$W7~6blmvhGwf+Y|Dw+wFLiw1Ya+~mr3x?Uc;mQatUGcHG<3A;~{O6;43{y#JeQ; zITHL{37)$#JiitRejZ1<+7FXRLU_=V8*!TiKVO1BDZy7s@a+=(0tvoTf?p`Xn=VQS z4@n5!68yswJaJpMe8{*j%kz^<@QXc2#6c4L5(z%ag*Q2upU02I=~_vFrIG^i68tg= zK2?H$M1s$d;FnAAMhSk!wf;wjJPE-wEWF(961LB141ViYN6@}xiM^%D3n;9LoO6mY2o{seICHQ019_yiCQ*AN$j zPXXR1fxiaaA%Qypvq9GdI15-WfzJcZmB2p&E|tK)0Iv1GCba%C5Dgv#;6DKGlfZuh z?vTLjHVBYu}zdI_uqoGXC?0GCSO5Wux=*u=X(0*D4lh8V#6B(NHAhXmFGW`nN_ zFaWS#0viD5O5ha0r4l#|aIFh=jsI{U8YCG;0Ny8oM+5GVz`1}~+I0bL1FV<8`G9jJ za3SDQ30wrY)(M+VI498*AQ~hYrUKq4fu{rRkieyY*^ui3%m%ENz!iXVCGb4Jr4o1n z;93rwG%f)a0ns4IuoUn<3A_SuhXk$#%!XbUU=?7!1YQd`R{}o?xKskK2V4u-geB+f zfoFhdkYsos@IDFrBH#`Q+yIyjyDq@Xfb|mC3OH8+?*v>bf!_dJJIrF@Yu+iqn?N*3 zGQ0(Np9FpvaEAom2bc}NF2DzX^%D3n;9LoO6mY2o{seICaMN`LCxB>>WH<$Qp9KCI zaEAo$0L;>_mp=AGuR-|bkpxmot9pB1`<+My=?OBQV&tB0;$ZkS3Ct74P zPRMbqD{mcY>5w5W$woe6ZI{Wdy*<5=JuqH+P4kT-VEP&8h?Q`z|IM3wO19}1yUuWWLSewZo+0t+Q_R>mMuz_a1r>o7vv_yMs%mgMRuomtfZE2 z5qKFiHm!FEaa>vGpP)p(w;)RU7~WaY))9g|JJ$3&u#Qlp<2eY}4(w@Jl(hmv6V&b! zI?B2NdD@XDT1H$r2w%-{;It5V<;c4&ob0{}I9~3wEYhIs?G=BQ5d&}J%fQ>h$*|1> zj1Jy#18CjgXUnB(%d^gkqfl|Abv&50U+b+%Yl%>03^h$d@or!seY^WbEIKovB0_>8XRtwW|bfzX0-aMK(HV2d4n^TOAEhCJM4&|z%Z-)@eW=?bC z_HkTa;;gL0H-}fWi^RuTW}&fL0>(D-d>t}s-HI~CATre0zOtwuG(LTudGCw0@cwqD zH^=hnpLVdPH$u$wSyi;nXY+#7p~TYROVT=hiG8-vCs!vnFse3fK|Q*A`dAte=g#kA z*-Xqu-^yYQT(&FANZLK;dWYYTN2_+{i8F}Ea}{}VdV3?C^_nAGd`P5aEBMVC8fB^R zF&FuJ5HNobhmB{a5@MoZ=y8vYeVAMHIL5!KWF0;ZR8IqkztNbV_R>;WE>;t4~rW|Q+ zW9B$-{*J^P!nJXB7By9&amCrkY1K?$R|cNm>;>EzT6Nk7IE67YyOmbefG+npW@^Ap z3uYcBoN2ZKYL{)g&P>9~Qzp@8+$;PC*oz$554O*Ck?%IiN{bmn_04>^yp7`c5w4A3QhXnXLv#v^l1CV~6R%ydX@liDBCp73AcZ0yo5TGUY2iaB~Y<7d>NHx8~FgQaQ$UlSkeFm^ro9*w6)7H!N^*^uQ0_{=%+QGtoJ8yiax&B(;Rjzb^eDn>2=xea-2!YwPnKa$ zbU}b*qro+qF@dj5X3Q~OxpOj~b~SLPzsWV5OQ29H(T({SE0en$JF`ieJPg)_F`-V0 zN#s--sl=X#iVi}np(2AJm<036Uc=<$E9S>OQA1L&gun5J#^b997w>S|D;#-pH6o*jh$9%m;4UrEecBs}g z7`O(mJh=76<3_iV>4%;BAkzL|nvQfQ(tb!!Kw7Re+5?cDg>*d9fk;;)ohLWi#{~g+ z3P2fvV5DC{dYjIeY3+~7Unu)Duh0A@Yl1P8w;KJLDW^(n-tWCbVHKD$Q$A-^FIE=G}0ry`c(f}VMhBU8MERoTctnt z1?5nq{Wok(Gq6vr!?0}gF*>%#nC&X6s%z96?N-d23aICT!N!CNbV41%463Tkf!e-| zo;ES!IM;W=+#jYHd%6WuC4-OKL=w!7h_$Cu^x}!*p9HaS~Iy4 zfiof))^QkW&gjs@?sR!;LY)HTlqi>QZ`9<3EE1YPl?J|%Rr0+efmjljn*=|qsH;0Y zBV+B)GcqbL0+bbIgq6NbZb!TPjll!c2cvwg9fMu z88;QpAc2)f(BiVpa)*38*HQx>AbbSVg=0r z?ZKQfhZ#ctN&~iAASlMp-ad{LPe7f?nf@Dt<6@UIt)szp>lDOt0YdNR{H&@lV@4f`O6Pc7AX{-u7FG{tyvz=)xEa*HEAeHLp~L>c8ONiCdsGh1E<| z5tWMT6;-WfNsxh9-lM@?e3ccTvcbz$8&go(j}#R`z@rd65EULr1(Rq{`s*}4-Ga2) zUD@F2QIiLcCZU5FF$A$-XJuwomd#=p1c#ZYrm`Rv*T!vIG)s0SAG8oo%{+R)ejIqlN0#Biv+)}C7C|Q<4L!t-acVLOIxk|;KjIQ{jMkW$OIoV?Qj)F%E{8MId9_sM zk_c7qBQ#V;!c{uNe5UdY9y%sY@P71y*MXEe*bTw+F*K#P zhxFI?XDNbG)LeU9Lg1R@Zmh9)cz$1V)_W_Xy6^NgW{Lyl!}CK1&krwNq$)9r6!$J0 zv*U+BxkBvieFk0eZOPiP@~-Yb9?03z4SxrAUxOx$ROwoD>RN2!JqvHy!Hs9!p@$(Y z%(^|v}dxLF%mPj9X@eX}VVYiP@ zz!ZIKVX;1}ut*g0EFGM`$ ztF(C=5HJ2}*u1;G8Zz(1iF6Zyq4Pck@GIg^kl{BFBma|LxbVc#!lDzy3ZMRLcwxwi zw89Oar5A>t7*eRy@YD>klX@;bhJ`10}-?w+hMmB9^(4UuR4 z%bXf-SaiNdM;IlJdyy9wQav#{EudYwd#UTt4GZb?Yv!T}5bf{iHE)`WZUtQqn}^#w zAEU{Np+=LP+Y&nfcuYl4EQg7vigFo0O0Cg;2uI3t7(a1#pv1|3F|FsLM4z723YRKGC)LOW5gIgLH4sBFOi$PZO6k%N(ZdC+7H#hE>FQ;d*W8ZHdG z^O*4dJx0?wBXwE;`QBubY8-4SUrkye^-~>PPD76^Pu@7c{K36JN_ZG(P-O!c9!9=R z=;;fvnfNY(5iI@)djrQ!0PfmI)4)2#-LTQ`y>4Y{sp|mY>8alW`v?oC2OG9wlmAV| zVEhs5?J&6EkAjOg4Bp#t!+5}}Q_S|&@P@4M5f0xok{Lq<-+L48`73D>(EOXF=~7*MzYJ2F%;UT$FblmO@B_GLYwZJ8ApZ9_ubB-{%rc?z5vSN{t(#g zT6V=DteU;pxLcuP8b90s(X6F&O7h*>hvHXY& zhSyrBXY86eBcm6S>UB(t%{U(I*dnZdV5ljsOAD*)oGjiNN6GLmFv^F5P$nxk%Bk^< zd>sz$C^R+l`Iu}Px4i{D<;k-~CO;zQ`7r)UFjw80lfm=mBd>{<311tNpddfP{a*Z5 z85w%MuS+XpqSYnB;LlsEo-7w`EekDGfomQ&_a7j;&mosqV)74>k+3|s&J3lh?Oht; z=nTZ+CXzVJ_rn(!rBnOKwdxDl)E#K@6@+eVa@oEv2V3Vfqy2oOu(M1v4aarPJptTu zp@B1~eEa579GB4MEq!(rZbtZ37H5rwbBlNTL0GREoQg}J9W)A3WyY~ggLbvT#V3;P zbk12$V++borSBEA6;aVwfcV{q1mkPLVD9Aa_9DB>U~8#_J{56M)68}SX8bu2mdKzQ z0_AnYnuGu!o0lm_S7Oj)@dOE-RGxnuPt zvRj*7?zjUBz%ZuFQ7R+$DO9n&<#s-uG}b>*A3r=O;rz#I^t7s_<$IG@fGU-5a@hEe zEjJ1Q!tu%@^1Wzf_dugv`1hOy?^(qD!yw_4IR%-6AlEFT{fS^=uk$7j?z+o|wUP~I z2ff-`{GKeL8yl@%<4vmyFf`|7>NI6lpCRQkVanVT6DQ%^V)a3je@FM?c~_W6%sVjy z8-0v+1C3H~1JDR-EPvY2jU+xnosAJTdXwfO*_i1=jP?r96cF`SrJ`;P?)bEsh0W&= z$K#|oP<`GcYs?QO7H&LVMN={NtmjR%@w}dxEPrT7+IiekwI|YKwtR)qj!Pwec#_NX z>MNIe#cj-NZ;!=T{I=p#1}2>L8}JL^I^VXE9WPNEn~64F-H86~#HJrgjgE!Ay?az> zNI5q!C~m+ajLmYbR*f(7ikIP_eg*kV5yTz}6Wnj+qm)Sl*L+?$&8LNO7@(A4c&>6hb1!E~J+^BwPuS~7_QMq0{E54t)-^^$vG7RcGNGDU!9jaf<~*ct2nZ;v*h|EsI_P%t6|Bs4{6?>j#IsCN;hxaHjHpf3>V(me4+>kY6zVG z^Gb&vz>>B;s5Zf+>YRig2LW#zZ*MPT=CZ;SXYF+K?rB835->^mx{t@Y=bN0fZO|mV zs?J&FqW3V7J>~Mcd-wbcW$X~88|wJEc(QvhW)#8TwNE6?eKp4B5^elMb>$#ZY#5l6 z9Iw-=w_w?{Pc$|gk$!0aR2t&L;iULm$j?XG*vDE(aW=?B%tzaXcJzw{4Rka5Nj_Mx z&QGM1g%k7jSx2CCwgFj(7%RHjsO_un?@n(<`T(@{IFg~ZB5)g~H3Th6?oQXp6qP%K zVO2>~C6rbfls}>p4Rqo5K0-s)Y{g_K4x=tbJx2&$Fp_;eMkrjMW+%o7^A_C3-se$- z@X-Pz+c`!ESQx2;V5NPw7rs0OS1_{B%0FbG1|3XZJkkrBN;A~wCJTiN)hW+{d~^Hy z;w+Sdx;kLm)`N~Wnqhr2;?>_z78(|I;ft;(ADSJr7VGKuVTH{fwqOctQ`K^~h6iH3 zol^+`4^JJ=S5W53-aW2WjwYbVeA#s*<|K1v$8|;t#FGUjskz39$4aWH5MF#Z#B$}y$TDJ*A(^tAG*?2evZmg z^O?D*&o8|*Z>+#0fS12z=FjG$@S7QU=o|bkr+>x8>EF@6^0(ADaBm8_pj}+TKD#W` zF3x99JDQFz4xzrQd84xmh3}W>=*xnldLt{iEWBJjfQ37Rqt!*%=mVGbr*{Ywmab%R zzX_i#yez8}44?EO$OvP?EEiT1kABTZ(=|QtyE(;Z|%uF`% z!}~TI*IiVGEa*LpxVulO1ZC zlNCS8FQ6}#7j%V=N!Z4i3aUO>L%k~h)$~lv^D>!g_nVty?!c6OkEtpR*d_$z!IxE) zxUbGK2&ZlFCe%i8SUQ6m1h^yGRV`WMq%J_7O+qQUr&DHh%#cM?!cMWAc;o4qY?-|4 zk*%5~3-@c5Ed5r)zohMH4@4QcPW{kIz$((Ly3||D*I@+gFTPvzE@RF(y5L;j{JG}~ zj6K|q-LvfWMlndFaq%}Spf=`O0Gqumy3sX7?LS?=^=8izv{BlAiQ|q|u-w z39vUD*)VaqhFQHL+&v*fof9(Yr(WS3vrf3LG)@SriJl?%O7L8G-_Z1fUaqG5`B-RC zO_32z|4VwYk3|Q1hNNrwp{f_w#(9V&d^KA;0?x;(F5I5UF@Za=Soo#Hujna^hLzh> zysdn)uTF)7+S^=&Hyw^nI3P2UShNf8~KKfHD!p$)g=ML@eKKC6@0N63dxc{AE(uAZstq1sgBp)eN8Su}1spLB{4znY_UG zg)T+^Uu_EQ<5$?3XtZlFTTg3*h?ObWjP70;R{*Bu(JcYw(T0F!n6<{o>DARReNC9T zbq;<)4L59Nu_|Yqv0!27TY7Qnclwv!Vm?cGzntqkX72e=V~;rJB^o8nxe#XRmH8h3 zX=KRU3qwNZb|r?*J=ZsU?$rk)@Omo}ueYM`dMg^I%$UZWWwDJt`+Y3(AgCJjG#>@t zvz3dv@i$P-)kzsVI={-iFcQ?tw>$2Y?^Mx7IYz;OZrrmU!-zF=J{?C#*gxM*^onVW zUoPKhEGv6Q4pZV>C~+jiQa*^gq(cI&9qH{#<4YcrDgwFHc$Irl&-L|hEL%V<^pMe?PY$y$ zy{i4#copfCa}N-Q7QR4dA6joI7p_|3N0nn1$q$t;X~0-)UC56AdnG&mlEC1$jlhbI zGQ1}X-}~N}h`pV!5&OHpIbCE!x9z`U?-tn|?+Ev-PcogW#N3ZCI%Md_`*7dK3!Xv2 z_JQWC4s=Zd4$g8MU(P*3T#8maI0h%yzLSq-0J%fVWC&>lkmBBM$UkITd zLIr3^cUL_01ca&9E75hhd!|tZu{2DD1Mu-}E5o|WWXAP;mOjs-3Lb&CV4Ezgdoy~5 zZ?+x$sCxmMor+B2r|fvVJ*cB5va2#nW5EmyswgkZz$B=fcgNF3g?H>(prx7tl0o0W{H?g$&Gf@n z!yLrp(HlD<$dd|V(_A>nK0=vSsb9fr+@!1W{YmhvAdUx7i2_fcK!rESgnid_9+RU6 zhtKn}Si`h1lKwMhRZOT$s60G7X`D8%79swyZ$!NhP942Oz^(|I8-5N}lhg!2fsF_@%( z1fiA&xP)4b$Atf1LZQ*9%XIt+FyHQ!YUjqvo|&I|B)eI#YeJzlT&PO4XggC`dH1T8 zyUKC_xo|n|9@`i|(qDpb&nsNQ9SpoK+|K8oD|+&|T>FB5>^k%S7vx4EOK%WT*t<$= zx>1tSPoH>wt}SJ4WYP)hEJXuG_0}<2ld&&apCx68>uA2w}V$AcyXSF z%JPg#R94`b8wwK4>%oyKQ@I>hons`0r^)}1!WhHrh1q00ce_^cGN1pWEGEwNvO72C zW6l^%l?fUB+)TF1io1CW65$Q|#};60J&dfF3~QgWFHkPGf??^W2Jj1#2=yggmH))c zq>?FA9%f2(J!im$;9YBQI*XLtL27j>j`H%1q)akwJT#eSj9*39%CTPkPUrBJEQ!PMX?b^FS&y{be~oNrQYOp-+vyebRh-{GgN zgKAxeGlB|2j>BZc6-M0?-sJd>AwwFUpvLuZK^YzauK0@S(+Fx()QQyp$lKKK$c1z~ zmB57Y=-j?PT-Uj)ojMmPcf#MR+-|6 zS{qh}p8A<Hi2Rys$3P zbfZXIqS6~An&Ig$u8Sd2Cv@>&b(cS;JMW?!nvQkJ^)4UNkI>{K_gLe7PB51S8@s8A z4;&vrPe#um@Ie#cZs`=* zjO)i-tgKH*#p<-hJy0*)Y4D%>_u8Xs2bQhlwa;#Ur zwHBa!K8>l{4&4j`aqmJOVhV<1&T<0BG!v6oZvW5!C~2pTJ~wDWW9MtQB2uZ-@*h-g z`~iBJ-+aP~w2#AWIllpw)vZl1OSZ%%-Z7X@&@Xy$ph09TTrQyarw z`8tQ-HN88ZF`6`U<9;d{#?PNK_Q!W6KHXc)4_4fXGZ|PA_Vsl=|=mxzIWg_T8v}qzrQ zaQ^=mF6i%Ylk!;8z0W>E)Bl3<`X9Yw&oXSoaOM6waV%=O4Q;x$v3Cq}wuPUVgw%%k zptJB>^(-5MMp7rC>DjIEH0e^Hy1Qo?ZR{Dt?{%m_j?WKzmgO{RNN6R$2EXK++s(U# zv$0)mru|q`$?o}7D6uDnEJsUm8*OOEw!{T~x>I=39x?i0?oj8`N&bNWw#wpjc>b1s z0Pk|3Tljnbb4oIdKh zAA9bMpnf+Z=FYR2&OXK+wE;Oh2(CO!1L%$tAF|_#GeY6J22<@BkX2+ie{`Uc6Gy~7 zB%$3mGVKwL_rZ;vlI-U9^Z3t?mfZKuMcnMl1j{n`{z>ClI51<=-ebi6rjk^fm89pP z;lwc)WlPeqGUfPG@H_G#&r5fV?IDEhXkmD(ruHkGIfC@S!7BXzZgj*wJpTaVXz}46 z^6{f|xHa~yFyK8klVu3Ez1P5M&j{z=d(yWYjI^(h6-+H_uB8K8SM@K%T@>6R;o!46 zBsX(4{59s$E?f|B+|L$pMtG}LpX==gWxUEXR~Ew4_EwHQl){gPQ7f|MI~yXV&LAe{4!< z8kW2!jdy3JlXti^5H#+I81f5}qLL#!p1r2=D7@aONI{Z;=lka%;G|{6Lg< zy%7lojr)?vG!R*S4X@)fKaL(~f zC&$pVi=ed^!ugNEa}M$z404fh;{8FlcHpZwSxnkybIi2fuW9DLP+E=` zVy;VJuG;Wwp_bTx!{>UJLs+J%B7W~BTK?^3B6LX1RB4h^7W_Ah17gapSirCnf9R z^=cM0O3nTDfQ7n)_xmow>^pH-FZ_P+zx4N}&kvQzQ0efGO}sWDPjc2q+_f!4ZS8A? zqaSPNlfsW5N5;5$w}Us4@CGbsjwZAI-wK6Cr~59!J`{CCFEruZ(dMSX$Lgu>iTu5P zz-{fo!=P?BO1U%DhWF3#MGq#>mhy>0N81Rmt|6>Zh&!I7JeQ4~v4Ge=JR?j!-oU1u z6aG9t0ROcz6*r2C0=`kp_=XHGr&7rLBq`*|EqHK1s*e2LTZ|ijYwXq#Veuz@OmpxF zrWtDhue0oYe#(cFVe%`F^1DGC`Q=@SuuHb15BUQf&oLhclc5XMt6;;d{=@WX$#85~ z*dD`L6YI|5Dhfxuf?=={zFkNy-_4>JyfD7h4P7IN9T#7A?uCc5(hxj^m^PI7<6$ix zT={W(WnggvE;lRBW4V!uctyb5`71eJ+ytJroA z=}GnB0eC5`1T&lw*KAEtt=%e|_;f%@7mX`8GMrQ&;qeGky&dMv5oFs&iTyrYu$Mux ztm&tW<(ErO|0JY*_EyOAX=H=(=iXuM_zD`YQtUsfgg-ue5dV$2;`1~$mRuXnDQxC3 zzf7XH7B-Xkc(oR8;oSD7w?026Gr7gb^Ij|O0^Su|eBKq0NWQGb6Rg4fO+^EJXL7!<#Z}&(~l~E!S6dcvPiKHf9>|!tOA>wkgM4NXTIZ z6Cd<^bc5eG*F(8^cunJZC|Ca%59LhM^-#_q<8%&Vcm(~-ar~hi%#pBKVr&jX%%7ym zla1BxmwKVx&(3|k1hbXmPMpUz#As@k<0hO>WqrJsKLlo87Q<5tDaVn-C+I6j2{8Ao^ui0akansCcQ_bbApuk!WZ;aQ*@&s5;1cPL@4myIx1AHg%PO1yl}_lg>>T_bdSH7I(G zv6M$Sba0b+24K#}mc;2DBqrU-N z>&;ac9|@OQ1T4Jv--mrGU`yv8(hG@S-%oEBEMF(mEltf|kCge&0b!MWtk8RUZXi#q zWW;W+NPfrMJho|B$4(iVVmO<~h121cjSdqW=36uRaX0UO{Gal9XCtXaSao(Xa-KSy zjsHp>^SuUtN8s-h!qo3$l@Re~h{pUU2__&X37ft*gabJX3}<17As7g3<;^mS@b&ka za8z}Tf)Ug@DNP}rZ&7ABB^*7s=(caa27D>3J)g^3zZ8z1k6?jc3TMyjl|IPKjf{Vt5<oI*ItO=)t6+iY3-g141)x1RPai@ege#~W85{1h@uI;x?h6Bu* zu@27^dE|@hFK_u&;dJ5OKlO{4iH_%ni2JPo?jxCX?kVBxp9VzvqHb>A@GE?%n_coo zA4?-I7k6=Nzg==&UkjlvS#kyLo@CyQ$Wec3Ke0RvD}aC9Pg=(ck6*k$=%pmGfm<}~ zp?Kzn(oI({Zea3$CpqtMtI+Py3VSb=_?=3GS?$R(|Mz+(?7o~WulI1ea=F~k_r@$q zGQJ(|iaL@ZZ2jZ8pu6uT8@Q2b9^tNM{FTpG&|L{+1Hbd$>|$Ntl=`Q@l6IL zo<2hRCmsCEd5E!U{m5?q5~2>Llrly_%9vag2Q9W5l@Nuona5%rrAfYd*yxp+h2lg? zXR^;e6W_oK0Cwav@dTy$Z0~2Hp3$P%{b1{ho@>X0pcbUjc2~7~BE_c|y%&mtTx?%i zGYTEm(-|oIdAYCHM@Cm=IPF5|a4i1ZdAqwC0@UBo>nmBKgo*g2jApo-*61U~deI#A z^Jn68#Bu*v?rksnj#vGO!x`c-Z~9%5v;HHH7&prQXPtFEwAia2V<3L(LtkL=pNX}; zblgAJ_q{L8^Q!+H^*yMduZ!Qw=}?ul9eouN`tAgD{&iJ{KG;RzIq=MDid$5^^>Ms7 zUP(1{mpDgBjqL7E#GOid8{7Jch-aP}F-i_d5-{`7gW zt*<{lKv~RM@q7S{Vc)N{`2^AzDcf{hd^w2fBO2C_4O)E5)gFk~vn&QHJi_q88u4q; zyjJ7?n}}Y)bkuO3l2>J8Wsn_Qh1LMpUCg$ye&(X(;LtMC#leZ6pACCCHf`}5aZxaR zQMCqn^C3)r&Tvr^f=86$YsJD4TF4rYi!X*yg9gO5d|is=p6ar_3H`l}=?Lr=v&P#!gkWdTM<4AKm<`WfEhha%~26CXKw zd9)=SSl)UFb1~sUnk85Y9~x%io4fPf2+#jgh9yo)-xFz3obh!;OL2o!a5~Z$I6l-} zmhzy=gm_^|M9vf!im)=eSD&)Q(XBx~oBi_C7VAi{TphYmh9XH(wNyw|w z7QB(Xm>WODG6wOi-9s#`%{4`~W6+C`Dd7#}h zzj=?^evPHC((D|F!!YR-M9hHN+u=bs#(u5Xsb zbeF-q#NS?b!`tF4vUm`V4$(MbMp-W$#G@$u4+j3PIe7h3;m~@uM(h}b1-%t~Aloio zT&nY*wQydi4vI0USp5SJi^Egt051D3-MUnijk5B8=;A=Q<*;o*Dt(@@szbJbA@q>U zt3Ll;jTo3t!^MlkX)M52CzvGPg|6O(eMTIUP7h);b7^}qG=o0JzW6}gnL#6%_@Veg z22D|a_yKl${!eY-P{FjVC;VKE({#yb($n&R7?Mf#CL8jYu@c*14LI{07~A9ATUF6% zaK`k!#_38t(}1JINk25U$K^c;OEU+Mo>w>>F3}QiH~r(WJ?02FWt71V?49_QHPrf$ zQg5FCAE2|meSemG%%epm728IYDUD)NCLPSW+QqY(^tO=C!HoCmr_MOcdi(=%^axtP z4u2?GN6^eZ^}6Q$S?GXzee3?LbFqpyNY1}TDO%&YIqsQ}v}XDNjvx1i!k;)ej?`=# zMQY5WjQ;XM(khP99v|D|#OJW9TDXUt=~ko8-x;KzIRoFPk>9eFww}BP|MbB4KlqafR@wlZ!zU3dLhan&r$L zJgHC&&7t=@fe--rpAh{6c{bhDcy+v9s}8=SP;AO^XZJ>q-*f0-XO44QjdOFy^VjNy zVtOu37|4qe3=Q|@5n|5rs2a~Hg40>^e(~{KI*CnxUp$qI!RAQ0eQXa`HaL>?j6Wcz zjiJK>M<3`FIjzKpG?N4SZHvdyaWs)*ax!MB*?-6OXtkwkT!|Jt*`9X6_*ASo0eQ5| z`)ysf&|!24r_#G!P3Og)g|^AJp)OxHA93qgx}5p#7xj5` z5&LDo_hgH<_pJr)o8BvLxU&h)8>JE z7@f$R=SOLB`t0?}**Hqm8r|)M$$JY5c(ukjGp85O_XpPVOJQzw8lbYVztlrtIL#-+ z7lC&EkIwLz&~OiA8czqX%lpLq@zfAHW*^RE*qfk=>&GE~0#xzivG@lVZ9yZJslUVk5&bgt1q=wseR+DU?SUfNpYiG3mQROU z5+7MEBq6f8q zC-%AbdPV2S97DMXY5ro^nPG0BC{CrfvRmI3zn+SHGV@(AU>daHkaxua)9A~0@=SgY z7dC6PNooU}^Kv}rJAgwc1@p&Wf7Fd9!GQsGUXqluqLNzLv4g;_z7@W;WYEyq9_HiW;dE zkKK zes2=4?0VsO*5ZPV4*MAo%*Dn zz{R1%Cl$(jq3jk=9gACNYgj-}Q8w5vu6T&vpIWcDEDOAXK07~+G`Ek0`YCs+hx+zd zq@k)HVSNBrERO?Gap=ReKV>g35JxPcOJgV6dPODVZC`9`Ztb(PumCX6i3uhiTZHZ! zVG}DB(?zjfAowF=P7bsYG7?Wl%%&@gapw8)P22NJplev+o3@x`^m)p@-y^>H2t67+ z74YJg9nTrO!25p1S zhGs&u8Sx#J73U-ZHvCrihWzp%ODppCeN9|tr~SwLZ-zE7{J~rl3Wl6fIT-#Wqxc{T zMLxxA;*WN^#q__7UJbOgo--Gn+6l@2N|KKPEvG^MeXgiY}2;T`zXuaX zMyFHOnjrRm4)goCL5w{?r*p!x6Lgh~EseLyPSKQrkaJO%2ydM0usvc@)F(to+s1U# zKbamU&>}Ah!5(EPl)~epZL_-Q{c={i*>?C64fFDoTc+Y|8Jr2hQ#Xm{f2U=-EKB*y zKHYrF$j0ZdxK=CXu5P@&DlW%AGEJyq;=*p4NJopCy0Jy}-DLZq8$zah|6;HB;|!x? z(~8lJW;UaHGiHB>2gfwsn_#hu^B|np7`%g40r|i*Z#N1dmf}Ih?6|roX_pS|x zGc2wnUt28uh$TNGz8J>}7);o%IQBwF$}^ZvWAXn*#Dd}~_GxixU)F=HS;@9#{n#yX zB%esO?N4Hld4(_wUUN9FLF26LGl*lK#Wr;?tM$u0$ourU6sPmzH~h0$C)^C!?WEw2 zjGJ*h-z7YkZ^v9qc+#dG&0?spGt-%5TXr^+E4Z{UwcC_D3*xMCK|WuHAJ?wf_8BOeuK-^Yftgg3<(?_&nG{xRF(`&bcW zS&xb8*5od{^os6_OYq(>Om|e@_1KUn4;tq-kI4Hub!Xx6MT9z5u=J7(nl5x~L zBEDOTjySelJWuo8n) z@rcd3lC5Rz!)3PNtC*FskCuuZtJy?0PA3jo!w#{*%fvs|u(Zg2%h1iZYu6*b#_okw zaqL<)j+HDG*RN$wEK?_rtz*O3@ulL5IyQwJTPB{UW7FC1)#C7V>_K+7&i2YWc7n3I z!)&G}`3!tGOq{VEv*$v%I7nbG`}T>jSaA(0rasN`#Gt3yT+y#>ywyp+t ziprM8Tf}uwu|Bpl|7KAzw8AYR{JU~S>LFr%!mw~#;LGfUjLi)fzi&ie9S^gOwKAO- zTd_c_*vT}kG2B+SlYQdDcfc8Ym>xTzZRH;JF6DdV7#mg+w!(!rhJV`JnqXO1Ub*)? z-bx#i564WPNy>a20Pq;MZ5{T_Pxqpu%A>_Q?W{B!leHF0CHM9?%SyzvNFPgUo4M%Z zgW@N4Hj?%9u?4=x(!BKG*_CEY=#)hiK4ElWNa<4+CBJStbN1>bz|o%Jr;`FH$k z=h+PSa*}cB(_7gpcfPh1GArArd7tg^ zVO^EB6NlM(#)>O#`#xq9DW3j|p~tX}&sEsw9b<#!5oa_Oeig;X;vhzU4IlkG)MC?r z*yxBVt>q#v`fi{-5h?nfWO~yMt)=5;TBg?W-9P)}pDRAnyUO;R`l3_Vd~NpO@qNT0H!z!=$RDNfwNG{kqdhV&o}S7*dsF zsldnCJIl-VJ^}oWNy)awr&tbUCms;r`Vv#>;|IjAzhsNpYY&K1zJgA+%obOC#ri5G zjJAKph8rBZ|5x0#hgDT=`?c3x;1&>(m#8EgM1$=EBt_gHY#v9AylOi$QnQUBqL?A# zBh+}Pg@(maa;W)0kGF`dNbPJiQ+%9`x4Z^sX`M1q^J-SdS3U||_c!)K(UX1WKllFD z_nULfG3OlfHRfFNwbboshj(S=Ga>5x_tMsdkmq-DSpU#ab>qEmt3%bb_tHYcR07S4 zL}p~ugzun|`e)mI`A#0~CNIpQ!KdV0^hLDolssv4O%~SVyfM*6%NT@@3*?V;+tODzK@K{2*=H$UufKlrd38dPfOJBg;BmMwC4mTli@ z41DFOp|*dVkuSClDb3`|bUO0H7HXGY&5N*C%hH7@Xfu%z>DUE1hC7A{+?ISI)QQ}d z_}-^?iY>|n%oW1UQr+b~KT=JuF1EB}Qp!c-`WY+jyeK~<|97~}?-Dw0IX;Y{EOZ7wfOHL!KZjGd z_M%p)_@tqy?O1yes}wl|sZBA5v7ogRrEs<6Qi&z?X}h4cPC@UuM|4+{e=V`Z-_L!1 zceVNV63Zj^bFYWHTdAcd+<6MoR_-sJ)XAAf+o=Fi<1UvNZLbB3^=_=vqQb;@A>Rb0 zyU6IG)Jl!}>AYE3VLCU&HX>Q%yU8CIZTkm{lNb)@=&eUZKlIwa_OyNfsJP;()JC4` zV>|YwxG2kKhS)yM5RdCX>xAX9F=7`?$+5QY$B5A~7gh?=ZeP{mJaDe++!%~^IM_K4 z?Cu!@)KqrQic^#KmRK$hrs>a!eX{=$Tg-Sd0&f+=KaN7-{;=ACQ!zb*4bix&xmQ;O z^F?R+54Zi*DkjNodV}l3ABIr-iQ+@M#fBM&&n600=j+_@ixqasDEZ;&YAQ{iB!c>P zQ6r(X(myb&xy`*)>}{(!`!Ei-0)LE>-);-B@Fvo5IJuvySNnlCPEFt2jy{?sLOO(~ zk$of7kfG9z@)EdngtCI`%wblc154 z&qdwqWgkgZL-t5gKotYE}2JoiAIW9>=bB8 zV6kP2iEl6QiCud?0enpAYVh|%80?q#EnjY9a%@<(OEiBV0`;p2<`mt~`d^1W))wj- zZ(vF3`m-|jN(=1DR)Op`aHk$a9vmrtjWB}atCoPrEh>r1d7 zQi=&ioS~lP9cI`&!CY*ohZqB4wmQvzY4m1}NReaH=*JwVfBkF z8=UrJ*b5~6fRo)TEHV^Om|?MHmD4TL?&fosn+i9F99?71Kqi)fcb~9)E;*WDcFFM_ z%y^R@63dZ)0*k9uf5#c%KdcoE@#=NvD>d(^My+9g96=GbYrdLFpH2}*J=d_d5yd;G zWs1m&9`{k;hIaf^;Sux27*CD(VQwXyw6X(F}5I)FQ0JB5*j>Z|O)F)Sr zNq_IQzpgP)!EAOWdem)yA;!mV`wKA+hxw1>_e!NBxne6d9ndLy{V=|QSgN6lX~MtT zOk~HNTe=x<-?DzO1#>*r?l`A=Q<`xQ6G!Q2ln#|=lNgE z=fDx@bUR8h(}0L1W?yls<+KRqOK**QK`t)Ctr?U;<7bG@PsDNp#nW{x%)h{I*q>1s zhPK8DnrM$_oc#oR&oNjGf=rQkjCk~Yu?!PAWx3d2`>aYUp zu)?kmTjJIC!B>pZa^>==stU_D&JuLd#KsECm!NU!&I1)u$)yPrGBBM&P{DLF!(}J6jly7AHTe^7q02hnYVrLEU1ele0y-?>gpbRn-TXDRB-ez12sb|5 zO2kEfB4Pe>JBV*6RPXR$**_btb?LJEfk#b5@qqPR5(4G^lBQ#=-F zV;P=KB<}?xP_`vfj|F11f&*kK&0iqG>3XT?CmWH31tMQ=mt-6MqA=;?-HEicNEFKZ z6Un_;#K?b3BvY}7^shZTM*oI?cR3QHc;4PmQbVaLqA#%wv{1~JZG&uYE);!qa_%7dY7t`2A4KVk#dtY(5Y;RerE&lm zUlOA`{;Wuq2XXb-6jSkzsrVXGPmE|MEEqv=yd(zcj?>pKiLr*8IF8oV@Mt7oQ*;e` zo33C7DtF5vy0*E$;zR?dF@om5EWG613AFTO@shkYfqcs_HhVXL#+M0`T$n&>%EV}$ zg)Wwf+!fZniityzBn;7@=)1?Gap8hAHjidA-jmt<1k8LwBw|=0V|;(X-F3pw*DN3(R||(M&x2&Mx-u^G0c3UH;_l2tq%r8 z#A_XSGsC_DT=kW=-=EA&g^zrtfGkT?bQcqH}dA4=0_y8 zzEZUyZ*ZHJYYS=^az+4b#JQ{K6Y^m$1nZ`+CKXT^?v}AuF^!0TjJVc-h~5(0A2Dl$-0g z4!Fv-%^yVA^_~d(AVPkH;IiXmkHbxlGHZQAawwFMzQ1GO2+h`)SBLPXaUrz9UP{8! zXrkTApbDen>C7?_V|3^25R$q%Rcho4h7k)+VujRHKys$z!a)0Qs?tO$uZr4ZP~GnPPLDb=y%k6$G>g0~pYO~(3%FoywPcX1ZLG~j)J*l z1hrAcjPcQ2t_$0%r#Y5Z<-Ie`L3fq+Ztyjs$K$+7X&Q2)36WvjV$4zSAuq9Qvz;1R ztW*1;{)FTj;@JLziM~=X8kuS$dAS&F@J~*H|Nt=mFTCx&Zn!e zdtAj-J;yV2E}343?C%y*_Uj_d;~->W`iXh8oat}n)9%;NF4yJLnb(olk7iTXl?bQJ zTuNMt{yMLa#;g=!JzjD8+laLDeRs)N%i(a|Ek$^^TaC?2OKH9K=xLMm9vQ4|5>Q5va=C5cNxR z6tzkOcz*08>X)>k5g-(O2m{Z(oV%~O%#0Y-t0tX}wx{hhHHFX8CVjNjbF z6KMP`_6|=b&WfWj@LCvPYyjP14mAER%qWP4lwCaG#O_cDF4}QZH?%ql8ra|XPp79D z&PbB&g7_Q%X8^gc7N)4FpjYo_f%G$Sq4seNX3Vzz57n`@<`&D5NLNg1sCA&40(JiU zYSG>F18(w>@H7>=f?zyF7pnBhqnsoC|*vsWd9y9^py&*@JM7gZ~HnESKDP zzNZ^5;B$ZO>Qikn%Y}Of=C#Evm#p%>Csy}lT_Z-)_BCQuw>q?Jz6TlPD7=T<#LIa_ z4)!ga#py=O;@u40F@$=)A%5sKyES81Cu3(PV-M-30gR8V6;FtSiy3VAkn-cIBR6ugfoZWVkn-a`2|+(}}g>oYEjwVQyfZ zm?3{3YfD@&9@XL4N7)7u5mAaVl;=w~T-QeOS7wv&5jOtPEOs@IDunw)EFRJE4PveQ zcr4AX5*E2KmOib*Fg66CZ4{WCKi;3lY!bbLYFjV>{mnig6*WaZ;zp2Ed;~8qwhfyE zcCl^fPwO{Bhfsgp?#&n%%NzSq>|2=qiS1`w{+7T(_=o*$XR5`An5GW3Ceel(5i0L~ zg!a{lAKYpOKs(TucSI+TO-btZQ#$opX_D>pcSNY091}yAYQ>B4)ELVDK#(j+Jg6_t-UcOE)|b|76H#te32JV%?eI1s>ts`3+mY>JwoWdKwx$0~7O*UNhc}vbldG<_Xy# z(Zbyj`R{$`&E1%gc)t(b+Kpj8^`Y^5#3TjNCK8uJCu-V*c|dC)LSe+vw0co3zum_c zxL1sJmsj+%P5+1Jsszq7VlHbE_ zZUlX6BrR`5;?6|SzD6-z_Arv~5%HqYI}#iJpx6CSl8lunhTPbW-8S`M?y6Mmu1m<;!81@{{EGC7HVTvv?K{hlH!2& zU&q>xz8yWJ^zJjH$9m*b>M@aITlBRUC)-Z^Q+Nxya6;76q3^}06pv%w@SW1YG`lyP zvGot=8gff>{AJ6p)gcJ8AIq(+g6j6g-!i7cueq=`#xql=LqV zNR8*jqja@d%%WdTim|p;XM|4JI{zq=+uE`&3w(BC=A>!aS@~0DPqH;$5%0IBB1QSQ zXcsE>Xh=VDL5p@2W-CyS%qU*iqM3mWz;VDUlQa$A5Ri^%Yg#3+WwNH#0?To6@^N5L zuBPGoN=bQ6(+oJ0-?Bi{GJqo&YFZhv{$)+u1^j7=rkw>IT&ig}4_qW2f&pjzq^4Ii zEe#k{u4yuJ#7zZo{4g;0}tw0H%T3HLc{uTrP25-@{XsjtUe1L=jzul&3O+_%&ZP&C2 zv;*ZsOjH670IPttf77%pz|A&I>*py+)xe=Z!wv`n^xvsz6<)Zu@*}vnLrQl+P+%`$ z3$O)PfkmzGk2P&GFbh}*ECwC|ns;kjksb%RuE3B69JNQ&a)8@`wx~)5+3v^>Hu)qXUGZQt_I`;Fr!h^!hIo7 zqZY5l!LS*GX~4K62nd)4tOMo&n;5YHzy~ML3V`9jRlt#cG^UNx*@NQ`!c$O4JKHD^ z8Gh&m3x2^}yh5aYFofe7S=gclab=j}L)Y3UkwuF@j4N)@h61IbUJv=Km)D_I+C!=W zPJsm@v}mZ-w6Ob{wRHiI7kS!>~JU;jmu8la__-LKBn5 zc@;S#T;X1+f8ArH7kRJpS?w?3Jf4IvqDWiN#>!#76A1WV<$x049)z}+#gUA2MRIpI zoN9LeHV18z^C#LHt+tA=> z*bc#|{zXm8&279lalriJG+IHc2F;(-c$Xh%UV+SoQ3k%sm(coPzLQsa$pCB7W;oWuvF;B8@v#SR z5IkvRXs+;ZZ)u)}TN&Ik*sWD*a>No8-2u4ewRVF!4NovD!zEf9EeB0o%Cl!HpjOAAzX3%?#up$704a4qHI=N=#r7 zG_1V{Kr`Se!xOZcKG7>-a`bBYkuhsEdA9{`0<^Fm?))?02|}(%uVJ3fl-E|#XJ@ry z;K)aUAp^A5;&Pp3nkyjYn+w{oduZjLnOo5~!Ya`Et)UZbl`vymD>n|~INW-*qH%rs z2{gkRGI}T`dE6Sx_E6Gg{RZ0Vp$wK!Z=&Bk6pNfzO~XBvG4hqSsm2rZvKqSNsTk$z z8tUo={@{0Lsu%dSzeBsdl*GUsXn0pWu0k9~VaeD+zU`DvZoS@xGACVoC4dgMQLd@9Ip_m=uY(fnmWK|kg-Y}YsilMBFPpcLudgyVFasSLOTs^nJsN%2 zsBJXe7g^lTMm4@ljJ(!HCw!F@xvq}F{D9RvDBBNNd1yCn^;1lNz0md8^)CCza{&EZ z_#Tq|;Wv5@#ri9;f#t1uSY4#S!=gP@>aX;W%l1%>ztSf#16`M^C?dd93!b6%^ou`= z&sI#6x^~SZTHmId+HiI^|%uKxF?#^A}@WVm#*9kk?CxE1C-BYTSI_StD}k_ zCE71~G3p$CRww3Rd(DXNMSxnXko9|^(1jqyTyzux^UuL6Nhj{HH=s;gyMOJp8ysY5 z6=o9o7wWXTN(2YH?Z0ZLdzX9MG10<5MXEb1Xj>;`kgkC)c2Y)ku%34W$a;r=R(ia% z64JpC;jlWzld7nsvobNcU*B$&G5EebCh@J7G6MR4^cf`w`@Pib9 z*yDeI0yyG-Z~_!P*ybmt{->3%$*Gj$@JVO>g^zTomAWYXibh>PUzgpb+@PcE zd{13+@VS(l%bxM_jSvNo8ylOwonW&Fy+h8BdLE+PmiTVK@ zPI700p9?ccmjy0!4+q&y1GDr4+EzKORrCU^x7DCa9a?EGJaxD?;a0-Irzqd11V>md zT$@2Dlk|Oji(hx7$A#-KvjTbtL%oCU!d!tYEt=*-%KAjD4w!BsX*90mxtI|S=L9kEr>-pTrC n4` #include #include +#include #include #include +#include #include -#include -#include -#include -#include + #include "common/util.h" -#include "common/timing.h" #include "common/swaglog.h" -#include "common/touch.h" #include "common/visionimg.h" -#include "common/params.h" #include "common/utilpp.h" #include "ui.hpp" +#include "paint.hpp" -static void ui_set_brightness(UIState *s, int brightness) { - static int last_brightness = -1; - if (last_brightness != brightness && (s->awake || brightness == 0)) { - if (set_brightness(brightness)) { - last_brightness = brightness; - } - } -} - -int event_processing_enabled = -1; -static void enable_event_processing(bool yes) { - if (event_processing_enabled != 1 && yes) { - system("service call window 18 i32 1"); // enable event processing - event_processing_enabled = 1; - } else if (event_processing_enabled != 0 && !yes) { - system("service call window 18 i32 0"); // disable event processing - event_processing_enabled = 0; - } -} +extern volatile sig_atomic_t do_exit; -static void set_awake(UIState *s, bool awake) { -#ifdef QCOM - if (awake) { - // 30 second timeout - s->awake_timeout = 30*UI_FREQ; - } - if (s->awake != awake) { - s->awake = awake; - - // TODO: replace command_awake and command_sleep with direct calls to android - if (awake) { - LOGW("awake normal"); - framebuffer_set_power(s->fb, HWC_POWER_MODE_NORMAL); - enable_event_processing(true); - } else { - LOGW("awake off"); - ui_set_brightness(s, 0); - framebuffer_set_power(s->fb, HWC_POWER_MODE_OFF); - enable_event_processing(false); - } - } -#else - // computer UI doesn't sleep - s->awake = true; -#endif -} - -static void update_offroad_layout_state(UIState *s) { -#ifdef QCOM - static int timeout = 0; - static bool prev_collapsed = false; - static cereal::UiLayoutState::App prev_app = cereal::UiLayoutState::App::NONE; - if (timeout > 0) { - timeout--; - } - if (prev_collapsed != s->scene.uilayout_sidebarcollapsed || prev_app != s->active_app || timeout == 0) { - capnp::MallocMessageBuilder msg; - auto event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - auto layout = event.initUiLayoutState(); - layout.setActiveApp(s->active_app); - layout.setSidebarCollapsed(s->scene.uilayout_sidebarcollapsed); - s->pm->send("offroadLayout", msg); - LOGD("setting active app to %d with sidebar %d", (int)s->active_app, s->scene.uilayout_sidebarcollapsed); - prev_collapsed = s->scene.uilayout_sidebarcollapsed; - prev_app = s->active_app; - timeout = 2 * UI_FREQ; - } -#endif -} - -static void handle_sidebar_touch(UIState *s, int touch_x, int touch_y) { - if (!s->scene.uilayout_sidebarcollapsed && touch_x <= sbr_w) { - if (touch_x >= settings_btn_x && touch_x < (settings_btn_x + settings_btn_w) - && touch_y >= settings_btn_y && touch_y < (settings_btn_y + settings_btn_h)) { - s->active_app = cereal::UiLayoutState::App::SETTINGS; - } - else if (touch_x >= home_btn_x && touch_x < (home_btn_x + home_btn_w) - && touch_y >= home_btn_y && touch_y < (home_btn_y + home_btn_h)) { - if (s->started) { - s->active_app = cereal::UiLayoutState::App::NONE; - s->scene.uilayout_sidebarcollapsed = true; - } else { - s->active_app = cereal::UiLayoutState::App::HOME; - } - } - } -} - -static void handle_vision_touch(UIState *s, int touch_x, int touch_y) { - if (s->started && (touch_x >= s->scene.ui_viz_rx - bdr_s) - && (s->active_app != cereal::UiLayoutState::App::SETTINGS)) { - if (!s->scene.frontview) { - s->scene.uilayout_sidebarcollapsed = !s->scene.uilayout_sidebarcollapsed; - } else { - write_db_value("IsDriverViewEnabled", "0", 1); - } - } -} - -volatile sig_atomic_t do_exit = 0; -static void set_do_exit(int sig) { - do_exit = 1; -} - -template -static int read_param(T* param, const char *param_name, bool persistent_param = false){ - T param_orig = *param; - char *value; - size_t sz; - - int result = read_db_value(param_name, &value, &sz, persistent_param); - if (result == 0){ - std::string s = std::string(value, sz); // value is not null terminated - free(value); - - // Parse result - std::istringstream iss(s); - iss >> *param; - - // Restore original value if parsing failed - if (iss.fail()) { - *param = param_orig; - result = -1; - } - } - return result; -} - -template -static int read_param_timeout(T* param, const char* param_name, int* timeout, bool persistent_param = false) { - int result = -1; - if (*timeout > 0){ - (*timeout)--; - } else { - *timeout = 2 * UI_FREQ; // 0.5Hz - result = read_param(param, param_name, persistent_param); - } - return result; -} - -static int write_param_float(float param, const char* param_name, bool persistent_param = false) { +int write_param_float(float param, const char* param_name, bool persistent_param) { char s[16]; int size = snprintf(s, sizeof(s), "%f", param); - return write_db_value(param_name, s, MIN(size, sizeof(s)), persistent_param); + return write_db_value(param_name, s, size < sizeof(s) ? size : sizeof(s), persistent_param); } -static void ui_init(UIState *s) { - - pthread_mutex_init(&s->lock, NULL); +void ui_init(UIState *s) { s->sm = new SubMaster({"model", "controlsState", "uiLayoutState", "liveCalibration", "radarState", "thermal", - "health", "ubloxGnss", "driverState", "dMonitoringState" -#ifdef SHOW_SPEEDLIMIT - , "liveMapData" -#endif - }); - s->pm = new PubMaster({"offroadLayout"}); + "health", "carParams", "ubloxGnss", "driverState", "dMonitoringState", "sensorEvents"}); - s->ipc_fd = -1; - s->scene.satelliteCount = -1; s->started = false; - s->vision_seen = false; + s->status = STATUS_OFFROAD; + s->scene.satelliteCount = -1; + read_param(&s->is_metric, "IsMetric"); - // init display s->fb = framebuffer_init("ui", 0, true, &s->fb_w, &s->fb_h); assert(s->fb); - set_awake(s, true); - ui_nvg_init(s); } -static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, - int num_back_fds, const int *back_fds, - const VisionStreamBufs front_bufs, int num_front_fds, - const int *front_fds) { - assert(num_back_fds == UI_BUF_COUNT); - assert(num_front_fds == UI_BUF_COUNT); - - vipc_bufs_load(s->bufs, &back_bufs, num_back_fds, back_fds); - vipc_bufs_load(s->front_bufs, &front_bufs, num_front_fds, front_fds); - - s->cur_vision_idx = -1; - s->cur_vision_front_idx = -1; - - s->scene.frontview = getenv("FRONTVIEW") != NULL; - s->scene.fullview = getenv("FULLVIEW") != NULL; - s->scene.world_objects_visible = false; // Invisible until we receive a calibration message. +static void ui_init_vision(UIState *s) { + // Invisible until we receive a calibration message. + s->scene.world_objects_visible = false; - s->rgb_width = back_bufs.width; - s->rgb_height = back_bufs.height; - s->rgb_stride = back_bufs.stride; - s->rgb_buf_len = back_bufs.buf_len; + for (int i = 0; i < UI_BUF_COUNT; i++) { + if (s->khr[i] != 0) { + visionimg_destroy_gl(s->khr[i], s->priv_hnds[i]); + glDeleteTextures(1, &s->frame_texs[i]); + } - s->rgb_front_width = front_bufs.width; - s->rgb_front_height = front_bufs.height; - s->rgb_front_stride = front_bufs.stride; - s->rgb_front_buf_len = front_bufs.buf_len; + VisionImg img = { + .fd = s->stream.bufs[i].fd, + .format = VISIONIMG_FORMAT_RGB24, + .width = s->stream.bufs_info.width, + .height = s->stream.bufs_info.height, + .stride = s->stream.bufs_info.stride, + .bpp = 3, + .size = s->stream.bufs_info.buf_len, + }; +#ifndef QCOM + s->priv_hnds[i] = s->stream.bufs[i].addr; +#endif + s->frame_texs[i] = visionimg_to_gl(&img, &s->khr[i], &s->priv_hnds[i]); - read_param(&s->speed_lim_off, "SpeedLimitOffset"); - read_param(&s->is_metric, "IsMetric"); - read_param(&s->longitudinal_control, "LongitudinalControl"); - read_param(&s->limit_set_speed, "LimitSetSpeed"); + glBindTexture(GL_TEXTURE_2D, s->frame_texs[i]); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); - // Set offsets so params don't get read at the same time - s->longitudinal_control_timeout = UI_FREQ / 3; - s->is_metric_timeout = UI_FREQ / 2; - s->limit_set_speed_timeout = UI_FREQ; + // BGR + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); + } + assert(glGetError() == GL_NO_ERROR); } -static void read_path(PathData& p, const cereal::ModelData::PathData::Reader &pathp) { - p = {}; - - p.prob = pathp.getProb(); - p.std = pathp.getStd(); +void ui_update_vision(UIState *s) { - auto polyp = pathp.getPoly(); - for (int i = 0; i < POLYFIT_DEGREE; i++) { - p.poly[i] = polyp[i]; + if (!s->vision_connected && s->started) { + const VisionStreamType type = s->scene.frontview ? VISION_STREAM_RGB_FRONT : VISION_STREAM_RGB_BACK; + int err = visionstream_init(&s->stream, type, true, nullptr); + if (err == 0) { + ui_init_vision(s); + s->vision_connected = true; + } } - // Compute points locations - for (int i = 0; i < MODEL_PATH_DISTANCE; i++) { - p.points[i] = p.poly[0] * (i*i*i) + p.poly[1] * (i*i)+ p.poly[2] * i + p.poly[3]; + if (s->vision_connected) { + if (!s->started) goto destroy; + + // poll for a new frame + struct pollfd fds[1] = {{ + .fd = s->stream.ipc_fd, + .events = POLLOUT, + }}; + int ret = poll(fds, 1, 100); + if (ret > 0) { + if (!visionstream_get(&s->stream, nullptr)) goto destroy; + } } - p.validLen = pathp.getValidLen(); -} + return; -static void read_model(ModelData &d, const cereal::ModelData::Reader &model) { - d = {}; - read_path(d.path, model.getPath()); - read_path(d.left_lane, model.getLeftLane()); - read_path(d.right_lane, model.getRightLane()); - auto leadd = model.getLead(); - d.lead = (LeadData){ - .dist = leadd.getDist(), .prob = leadd.getProb(), .std = leadd.getStd(), - }; +destroy: + visionstream_destroy(&s->stream); + s->vision_connected = false; } -static void update_status(UIState *s, int status) { - if (s->status != status) { - s->status = status; +static inline void fill_path_points(const cereal::ModelData::PathData::Reader &path, float *points) { + const capnp::List::Reader &poly = path.getPoly(); + for (int i = 0; i < path.getValidLen(); i++) { + points[i] = poly[0] * (i * i * i) + poly[1] * (i * i) + poly[2] * i + poly[3]; } } -void handle_message(UIState *s, SubMaster &sm) { +void update_sockets(UIState *s) { + UIScene &scene = s->scene; + SubMaster &sm = *(s->sm); + + if (sm.update(0) == 0){ + return; + } + if (s->started && sm.updated("controlsState")) { auto event = sm["controlsState"]; scene.controls_state = event.getControlsState(); - s->controls_timeout = 1 * UI_FREQ; - s->controls_seen = true; + // TODO: the alert stuff shouldn't be handled here auto alert_sound = scene.controls_state.getAlertSound(); if (scene.alert_type.compare(scene.controls_state.getAlertType()) != 0) { if (alert_sound == AudibleAlert::NONE) { - s->sound.stop(); + s->sound->stop(); } else { - s->sound.play(alert_sound); + s->sound->play(alert_sound); } } scene.alert_text1 = scene.controls_state.getAlertText1(); @@ -285,11 +140,11 @@ void handle_message(UIState *s, SubMaster &sm) { scene.alert_type = scene.controls_state.getAlertType(); auto alertStatus = scene.controls_state.getAlertStatus(); if (alertStatus == cereal::ControlsState::AlertStatus::USER_PROMPT) { - update_status(s, STATUS_WARNING); + s->status = STATUS_WARNING; } else if (alertStatus == cereal::ControlsState::AlertStatus::CRITICAL) { - update_status(s, STATUS_ALERT); + s->status = STATUS_ALERT; } else{ - update_status(s, scene.controls_state.getEnabled() ? STATUS_ENGAGED : STATUS_DISENGAGED); + s->status = scene.controls_state.getEnabled() ? STATUS_ENGAGED : STATUS_DISENGAGED; } float alert_blinkingrate = scene.controls_state.getAlertBlinkingRate(); @@ -323,28 +178,16 @@ void handle_message(UIState *s, SubMaster &sm) { } } if (sm.updated("model")) { - read_model(scene.model, sm["model"].getModel()); + scene.model = sm["model"].getModel(); + fill_path_points(scene.model.getPath(), scene.path_points); + fill_path_points(scene.model.getLeftLane(), scene.left_lane_points); + fill_path_points(scene.model.getRightLane(), scene.right_lane_points); } - // else if (which == cereal::Event::LIVE_MPC) { - // auto data = event.getLiveMpc(); - // auto x_list = data.getX(); - // auto y_list = data.getY(); - // for (int i = 0; i < 50; i++){ - // scene.mpc_x[i] = x_list[i]; - // scene.mpc_y[i] = y_list[i]; - // } - // s->livempc_or_radarstate_changed = true; - // } if (sm.updated("uiLayoutState")) { auto data = sm["uiLayoutState"].getUiLayoutState(); s->active_app = data.getActiveApp(); scene.uilayout_sidebarcollapsed = data.getSidebarCollapsed(); } -#ifdef SHOW_SPEEDLIMIT - if (sm.updated("liveMapData")) { - scene.map_valid = sm["liveMapData"].getLiveMapData().getMapValid(); - } -#endif if (sm.updated("thermal")) { scene.thermal = sm["thermal"].getThermal(); } @@ -355,8 +198,14 @@ void handle_message(UIState *s, SubMaster &sm) { } } if (sm.updated("health")) { - scene.hwType = sm["health"].getHealth().getHwType(); - s->hardware_timeout = 5*UI_FREQ; // 5 seconds + auto health = sm["health"].getHealth(); + scene.hwType = health.getHwType(); + s->ignition = health.getIgnitionLine() || health.getIgnitionCan(); + } else if ((s->sm->frame - s->sm->rcv_frame("health")) > 5*UI_FREQ) { + scene.hwType = cereal::HealthData::HwType::UNKNOWN; + } + if (sm.updated("carParams")) { + s->longitudinal_control = sm["carParams"].getCarParams().getOpenpilotLongitudinalControl(); } if (sm.updated("driverState")) { scene.driver_state = sm["driverState"].getDriverState(); @@ -365,526 +214,76 @@ void handle_message(UIState *s, SubMaster &sm) { scene.dmonitoring_state = sm["dMonitoringState"].getDMonitoringState(); scene.is_rhd = scene.dmonitoring_state.getIsRHD(); scene.frontview = scene.dmonitoring_state.getIsPreview(); - } - - // timeout on frontview - if ((sm.frame - sm.rcv_frame("dMonitoringState")) > 1*UI_FREQ) { + } else if ((sm.frame - sm.rcv_frame("dMonitoringState")) > UI_FREQ/2) { scene.frontview = false; } - s->started = scene.thermal.getStarted() || scene.frontview; - // Handle onroad/offroad transition - if (!s->started) { - if (s->status != STATUS_STOPPED) { - update_status(s, STATUS_STOPPED); - s->vision_seen = false; - s->controls_seen = false; - s->active_app = cereal::UiLayoutState::App::HOME; - - #ifndef QCOM - // disconnect from visionipc on PC - close(s->ipc_fd); - s->ipc_fd = -1; - #endif +#ifdef QCOM2 // TODO: use this for QCOM too + if (sm.updated("sensorEvents")) { + for (auto sensor : sm["sensorEvents"].getSensorEvents()) { + if (sensor.which() == cereal::SensorEventData::LIGHT) { + s->light_sensor = sensor.getLight(); + } } - } else if (s->status == STATUS_STOPPED) { - update_status(s, STATUS_DISENGAGED); - s->active_app = cereal::UiLayoutState::App::NONE; } -} +#endif -static void check_messages(UIState *s) { - if (s->sm->update(0) > 0){ - handle_message(s, *(s->sm)); - } + s->started = scene.thermal.getStarted() || scene.frontview; } -static void ui_update(UIState *s) { - int err; - - if (s->vision_connect_firstrun) { - // cant run this in connector thread because opengl. - // do this here for now in lieu of a run_on_main_thread event - - for (int i=0; ikhr[i] != 0) { - visionimg_destroy_gl(s->khr[i], s->priv_hnds[i]); - glDeleteTextures(1, &s->frame_texs[i]); - } - - VisionImg img = { - .fd = s->bufs[i].fd, - .format = VISIONIMG_FORMAT_RGB24, - .width = s->rgb_width, - .height = s->rgb_height, - .stride = s->rgb_stride, - .bpp = 3, - .size = s->rgb_buf_len, - }; - #ifndef QCOM - s->priv_hnds[i] = s->bufs[i].addr; - #endif - s->frame_texs[i] = visionimg_to_gl(&img, &s->khr[i], &s->priv_hnds[i]); - - glBindTexture(GL_TEXTURE_2D, s->frame_texs[i]); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); - - // BGR - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); - } - - for (int i=0; ikhr_front[i] != 0) { - visionimg_destroy_gl(s->khr_front[i], s->priv_hnds_front[i]); - glDeleteTextures(1, &s->frame_front_texs[i]); - } +void ui_update(UIState *s) { - VisionImg img = { - .fd = s->front_bufs[i].fd, - .format = VISIONIMG_FORMAT_RGB24, - .width = s->rgb_front_width, - .height = s->rgb_front_height, - .stride = s->rgb_front_stride, - .bpp = 3, - .size = s->rgb_front_buf_len, - }; - #ifndef QCOM - s->priv_hnds_front[i] = s->bufs[i].addr; - #endif - s->frame_front_texs[i] = visionimg_to_gl(&img, &s->khr_front[i], &s->priv_hnds_front[i]); - - glBindTexture(GL_TEXTURE_2D, s->frame_front_texs[i]); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); - - // BGR - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); - } + update_sockets(s); + ui_update_vision(s); - assert(glGetError() == GL_NO_ERROR); + // Handle onroad/offroad transition + if (!s->started && s->status != STATUS_OFFROAD) { + s->status = STATUS_OFFROAD; + s->active_app = cereal::UiLayoutState::App::HOME; + s->scene.uilayout_sidebarcollapsed = false; + } else if (s->started && s->status == STATUS_OFFROAD) { + s->status = STATUS_DISENGAGED; + s->started_frame = s->sm->frame; + s->active_app = cereal::UiLayoutState::App::NONE; s->scene.uilayout_sidebarcollapsed = true; - s->scene.ui_viz_rx = (box_x-sbr_w+bdr_s*2); - s->scene.ui_viz_rw = (box_w+sbr_w-(bdr_s*2)); - s->scene.ui_viz_ro = 0; - - s->vision_connect_firstrun = false; - - s->alert_blinking_alpha = 1.0; s->alert_blinked = false; - } - - zmq_pollitem_t polls[1] = {{0}}; - // Take an rgb image from visiond if there is one - assert(s->ipc_fd >= 0); - while(true) { - if (s->ipc_fd < 0) { - // TODO: rethink this, for now it should only trigger on PC - LOGW("vision disconnected by other thread"); - s->vision_connected = false; - return; - } - polls[0].fd = s->ipc_fd; - polls[0].events = ZMQ_POLLIN; - #ifdef UI_60FPS - // uses more CPU in both UI and surfaceflinger - // 16% / 21% - int ret = zmq_poll(polls, 1, 1); - #else - // 9% / 13% = a 14% savings - int ret = zmq_poll(polls, 1, 1000); - #endif - if (ret < 0) { - if (errno == EINTR || errno == EAGAIN) continue; - - LOGE("poll failed (%d - %d)", ret, errno); - close(s->ipc_fd); - s->ipc_fd = -1; - s->vision_connected = false; - return; - } else if (ret == 0) { - break; - } - // vision ipc event - VisionPacket rp; - err = vipc_recv(s->ipc_fd, &rp); - if (err <= 0) { - LOGW("vision disconnected"); - close(s->ipc_fd); - s->ipc_fd = -1; - s->vision_connected = false; - return; - } - if (rp.type == VIPC_STREAM_ACQUIRE) { - bool front = rp.d.stream_acq.type == VISION_STREAM_RGB_FRONT; - int idx = rp.d.stream_acq.idx; - - int release_idx; - if (front) { - release_idx = s->cur_vision_front_idx; - } else { - release_idx = s->cur_vision_idx; - } - if (release_idx >= 0) { - VisionPacket rep = { - .type = VIPC_STREAM_RELEASE, - .d = { .stream_rel = { - .type = rp.d.stream_acq.type, - .idx = release_idx, - }}, - }; - vipc_send(s->ipc_fd, &rep); - } - - if (front) { - assert(idx < UI_BUF_COUNT); - s->cur_vision_front_idx = idx; - } else { - assert(idx < UI_BUF_COUNT); - s->cur_vision_idx = idx; - // printf("v %d\n", ((uint8_t*)s->bufs[idx].addr)[0]); + s->alert_blinking_alpha = 1.0; + s->scene.alert_size = cereal::ControlsState::AlertSize::NONE; + } + + // Handle controls timeout + if (s->started && !s->scene.frontview && ((s->sm)->frame - s->started_frame) > 5*UI_FREQ) { + if ((s->sm)->rcv_frame("controlsState") < s->started_frame) { + // car is started, but controlsState hasn't been seen at all + s->scene.alert_text1 = "openpilot Unavailable"; + s->scene.alert_text2 = "Waiting for controls to start"; + s->scene.alert_size = cereal::ControlsState::AlertSize::MID; + } else if (((s->sm)->frame - (s->sm)->rcv_frame("controlsState")) > 5*UI_FREQ) { + // car is started, but controls is lagging or died + if (s->scene.alert_text2 != "Controls Unresponsive") { + s->sound->play(AudibleAlert::CHIME_WARNING_REPEAT); + LOGE("Controls unresponsive"); } - } else { - assert(false); - } - break; - } -} - -static int vision_subscribe(int fd, VisionPacket *rp, VisionStreamType type) { - int err; - LOGW("vision_subscribe type:%d", type); - - VisionPacket p1 = { - .type = VIPC_STREAM_SUBSCRIBE, - .d = { .stream_sub = { .type = type, .tbuffer = true, }, }, - }; - err = vipc_send(fd, &p1); - if (err < 0) { - close(fd); - return 0; - } - do { - err = vipc_recv(fd, rp); - if (err <= 0) { - close(fd); - return 0; + s->scene.alert_text1 = "TAKE CONTROL IMMEDIATELY"; + s->scene.alert_text2 = "Controls Unresponsive"; + s->scene.alert_size = cereal::ControlsState::AlertSize::FULL; + s->status = STATUS_ALERT; } - - // release what we aren't ready for yet - if (rp->type == VIPC_STREAM_ACQUIRE) { - VisionPacket rep = { - .type = VIPC_STREAM_RELEASE, - .d = { .stream_rel = { - .type = rp->d.stream_acq.type, - .idx = rp->d.stream_acq.idx, - }}, - }; - vipc_send(fd, &rep); - } - } while (rp->type != VIPC_STREAM_BUFS || rp->d.stream_bufs.type != type); - - return 1; -} - -static void* vision_connect_thread(void *args) { - set_thread_name("vision_connect"); - - UIState *s = (UIState*)args; - while (!do_exit) { - usleep(100000); - pthread_mutex_lock(&s->lock); - bool connected = s->vision_connected; - pthread_mutex_unlock(&s->lock); - if (connected) continue; - - int fd = vipc_connect(); - if (fd < 0) continue; - - VisionPacket back_rp, front_rp; - if (!vision_subscribe(fd, &back_rp, VISION_STREAM_RGB_BACK)) continue; - if (!vision_subscribe(fd, &front_rp, VISION_STREAM_RGB_FRONT)) continue; - - pthread_mutex_lock(&s->lock); - assert(!s->vision_connected); - s->ipc_fd = fd; - - ui_init_vision(s, - back_rp.d.stream_bufs, back_rp.num_fds, back_rp.fds, - front_rp.d.stream_bufs, front_rp.num_fds, front_rp.fds); - - s->vision_connected = true; - s->vision_seen = true; - s->vision_connect_firstrun = true; - - // Drain sockets - s->sm->drain(); - - pthread_mutex_unlock(&s->lock); } - return NULL; -} - -#ifdef QCOM -#include -#include -#include - -static void* light_sensor_thread(void *args) { - int err; - set_thread_name("light_sensor"); - - UIState *s = (UIState*)args; - s->light_sensor = 0.0; - - struct sensors_poll_device_t* device; - struct sensors_module_t* module; - - hw_get_module(SENSORS_HARDWARE_MODULE_ID, (hw_module_t const**)&module); - sensors_open(&module->common, &device); - - // need to do this - struct sensor_t const* list; - module->get_sensors_list(module, &list); - - int SENSOR_LIGHT = 7; - - err = device->activate(device, SENSOR_LIGHT, 0); - if (err != 0) goto fail; - err = device->activate(device, SENSOR_LIGHT, 1); - if (err != 0) goto fail; - - device->setDelay(device, SENSOR_LIGHT, ms2ns(100)); - - while (!do_exit) { - static const size_t numEvents = 1; - sensors_event_t buffer[numEvents]; - - int n = device->poll(device, buffer, numEvents); - if (n < 0) { - LOG_100("light_sensor_poll failed: %d", n); - } - if (n > 0) { - s->light_sensor = buffer[0].light; - } - } - sensors_close(device); - return NULL; - -fail: - LOGE("LIGHT SENSOR IS MISSING"); - s->light_sensor = 255; - return NULL; -} - -#endif - -int main(int argc, char* argv[]) { - int err; - setpriority(PRIO_PROCESS, 0, -14); - - zsys_handler_set(NULL); - signal(SIGINT, (sighandler_t)set_do_exit); - - UIState uistate = {}; - UIState *s = &uistate; - ui_init(s); - - enable_event_processing(true); - - pthread_t connect_thread_handle; - err = pthread_create(&connect_thread_handle, NULL, - vision_connect_thread, s); - assert(err == 0); - -#ifdef QCOM - pthread_t light_sensor_thread_handle; - err = pthread_create(&light_sensor_thread_handle, NULL, - light_sensor_thread, s); - assert(err == 0); -#endif - - TouchState touch = {0}; - touch_init(&touch); - s->touch_fd = touch.fd; - - // light sensor scaling params - const bool LEON = util::read_file("/proc/cmdline").find("letv") != std::string::npos; - - float brightness_b, brightness_m; - int result = read_param(&brightness_b, "BRIGHTNESS_B", true); - result += read_param(&brightness_m, "BRIGHTNESS_M", true); - - if(result != 0){ - brightness_b = LEON ? 10.0 : 5.0; - brightness_m = LEON ? 2.6 : 1.3; - write_param_float(brightness_b, "BRIGHTNESS_B", true); - write_param_float(brightness_m, "BRIGHTNESS_M", true); - } - - float smooth_brightness = brightness_b; - - const int MIN_VOLUME = LEON ? 12 : 9; - const int MAX_VOLUME = LEON ? 15 : 12; - assert(s->sound.init(MIN_VOLUME)); - - int draws = 0; - - while (!do_exit) { - bool should_swap = false; - if (!s->started) { - // Delay a while to avoid 9% cpu usage while car is not started and user is keeping touching on the screen. - // Don't hold the lock while sleeping, so that vision_connect_thread have chances to get the lock. - usleep(30 * 1000); - } - pthread_mutex_lock(&s->lock); - double u1 = millis_since_boot(); - - // light sensor is only exposed on EONs - float clipped_brightness = (s->light_sensor*brightness_m) + brightness_b; - if (clipped_brightness > 512) clipped_brightness = 512; - smooth_brightness = clipped_brightness * 0.01 + smooth_brightness * 0.99; - if (smooth_brightness > 255) smooth_brightness = 255; - ui_set_brightness(s, (int)smooth_brightness); - - // resize vision for collapsing sidebar - const bool hasSidebar = !s->scene.uilayout_sidebarcollapsed; - s->scene.ui_viz_rx = hasSidebar ? box_x : (box_x - sbr_w + (bdr_s * 2)); - s->scene.ui_viz_rw = hasSidebar ? box_w : (box_w + sbr_w - (bdr_s * 2)); - s->scene.ui_viz_ro = hasSidebar ? -(sbr_w - 6 * bdr_s) : 0; - - // poll for touch events - int touch_x = -1, touch_y = -1; - int touched = touch_poll(&touch, &touch_x, &touch_y, 0); - if (touched == 1) { - set_awake(s, true); - handle_sidebar_touch(s, touch_x, touch_y); - handle_vision_touch(s, touch_x, touch_y); - } - - if (!s->started) { - // always process events offroad - check_messages(s); - - if (s->started) { - s->controls_timeout = 5 * UI_FREQ; - } - } else { - set_awake(s, true); - // Car started, fetch a new rgb image from ipc - if (s->vision_connected){ - ui_update(s); - } - - check_messages(s); - - // Visiond process is just stopped, force a redraw to make screen blank again. - if (!s->started) { - s->scene.uilayout_sidebarcollapsed = false; - ui_draw(s); - glFinish(); - should_swap = true; - } - } - - // manage wakefulness - if (s->awake_timeout > 0) { - s->awake_timeout--; - } else { - set_awake(s, false); - } - - // manage hardware disconnect - if (s->hardware_timeout > 0) { - s->hardware_timeout--; + // Read params + if ((s->sm)->frame % (5*UI_FREQ) == 0) { + read_param(&s->is_metric, "IsMetric"); + } else if ((s->sm)->frame % (6*UI_FREQ) == 0) { + int param_read = read_param(&s->last_athena_ping, "LastAthenaPingTime"); + if (param_read != 0) { // Failed to read param + s->scene.athenaStatus = NET_DISCONNECTED; + } else if (nanos_since_boot() - s->last_athena_ping < 70e9) { + s->scene.athenaStatus = NET_CONNECTED; } else { - s->scene.hwType = cereal::HealthData::HwType::UNKNOWN; - } - - // Don't waste resources on drawing in case screen is off - if (s->awake) { - ui_draw(s); - glFinish(); - should_swap = true; - } - - s->sound.setVolume(fmin(MAX_VOLUME, MIN_VOLUME + s->scene.controls_state.getVEgo() / 5)); // up one notch every 5 m/s - - if (s->controls_timeout > 0) { - s->controls_timeout--; - } else if (s->started && !s->scene.frontview) { - if (!s->controls_seen) { - // car is started, but controlsState hasn't been seen at all - s->scene.alert_text1 = "openpilot Unavailable"; - s->scene.alert_text2 = "Waiting for controls to start"; - s->scene.alert_size = cereal::ControlsState::AlertSize::MID; - } else { - // car is started, but controls is lagging or died - LOGE("Controls unresponsive"); - - if (s->scene.alert_text2 != "Controls Unresponsive") { - s->sound.play(AudibleAlert::CHIME_WARNING_REPEAT); - } - - s->scene.alert_text1 = "TAKE CONTROL IMMEDIATELY"; - s->scene.alert_text2 = "Controls Unresponsive"; - s->scene.alert_size = cereal::ControlsState::AlertSize::FULL; - update_status(s, STATUS_ALERT); - } - ui_draw_vision_alert(s, s->scene.alert_size, s->status, s->scene.alert_text1.c_str(), s->scene.alert_text2.c_str()); - } - - read_param_timeout(&s->is_metric, "IsMetric", &s->is_metric_timeout); - read_param_timeout(&s->longitudinal_control, "LongitudinalControl", &s->longitudinal_control_timeout); - read_param_timeout(&s->limit_set_speed, "LimitSetSpeed", &s->limit_set_speed_timeout); - read_param_timeout(&s->speed_lim_off, "SpeedLimitOffset", &s->limit_set_speed_timeout); - int param_read = read_param_timeout(&s->last_athena_ping, "LastAthenaPingTime", &s->last_athena_ping_timeout); - if (param_read != -1) { // Param was updated this loop - if (param_read != 0) { // Failed to read param - s->scene.athenaStatus = NET_DISCONNECTED; - } else if (nanos_since_boot() - s->last_athena_ping < 70e9) { - s->scene.athenaStatus = NET_CONNECTED; - } else { - s->scene.athenaStatus = NET_ERROR; - } - } - update_offroad_layout_state(s); - - pthread_mutex_unlock(&s->lock); - - // the bg thread needs to be scheduled, so the main thread needs time without the lock - // safe to do this outside the lock? - if (should_swap) { - double u2 = millis_since_boot(); - if (u2-u1 > 66) { - // warn on sub 15fps - LOGW("slow frame(%d) time: %.2f", draws, u2-u1); - } - draws++; - framebuffer_swap(s->fb); + s->scene.athenaStatus = NET_ERROR; } } - - set_awake(s, true); - - // wake up bg thread to exit - pthread_mutex_lock(&s->lock); - pthread_mutex_unlock(&s->lock); - -#ifdef QCOM - // join light_sensor_thread? -#endif - - err = pthread_join(connect_thread_handle, NULL); - assert(err == 0); - delete s->sm; - delete s->pm; - return 0; } diff --git a/selfdrive/ui/ui.hpp b/selfdrive/ui/ui.hpp index bf64ef27aa2124..1255e54b7a5418 100644 --- a/selfdrive/ui/ui.hpp +++ b/selfdrive/ui/ui.hpp @@ -11,8 +11,12 @@ #define NANOVG_GLES3_IMPLEMENTATION #define nvgCreate nvgCreateGLES3 #endif + #include -#include +#include +#include +#include + #include "nanovg.h" #include "common/mat.h" @@ -20,18 +24,9 @@ #include "common/visionimg.h" #include "common/framebuffer.h" #include "common/modeldata.h" +#include "common/params.h" #include "sound.hpp" -#define STATUS_STOPPED 0 -#define STATUS_DISENGAGED 1 -#define STATUS_ENGAGED 2 -#define STATUS_WARNING 3 -#define STATUS_ALERT 4 - -#define NET_CONNECTED 0 -#define NET_DISCONNECTED 1 -#define NET_ERROR 2 - #define COLOR_BLACK nvgRGBA(0, 0, 0, 255) #define COLOR_BLACK_ALPHA(x) nvgRGBA(0, 0, 0, x) #define COLOR_WHITE nvgRGBA(255, 255, 255, 255) @@ -40,76 +35,72 @@ #define COLOR_RED nvgRGBA(201, 34, 49, 255) #define COLOR_OCHRE nvgRGBA(218, 111, 37, 255) -#ifndef QCOM - #define UI_60FPS -#endif - #define UI_BUF_COUNT 4 -//#define SHOW_SPEEDLIMIT 1 -//#define DEBUG_TURN -const int vwp_w = 1920; -const int vwp_h = 1080; -const int nav_w = 640; -const int nav_ww= 760; +typedef struct Rect { + int x, y, w, h; + int centerX() const { return x + w / 2; } + int right() const { return x + w; } + int bottom() const { return y + h; } + bool ptInRect(int px, int py) const { + return px >= x && px < (x + w) && py >= y && py < (y + h); + } +} Rect; + const int sbr_w = 300; const int bdr_s = 30; -const int box_x = sbr_w+bdr_s; -const int box_y = bdr_s; -const int box_w = vwp_w-sbr_w-(bdr_s*2); -const int box_h = vwp_h-(bdr_s*2); -const int viz_w = vwp_w-(bdr_s*2); -const int ff_xoffset = 32; const int header_h = 420; const int footer_h = 280; -const int footer_y = vwp_h-bdr_s-footer_h; -const int settings_btn_h = 117; -const int settings_btn_w = 200; -const int settings_btn_x = 50; -const int settings_btn_y = 35; -const int home_btn_h = 180; -const int home_btn_w = 180; -const int home_btn_x = 60; -const int home_btn_y = vwp_h - home_btn_h - 40; - -const int UI_FREQ = 30; // Hz +const Rect settings_btn = {50, 35, 200, 117}; +const Rect home_btn = {60, 1080 - 180 - 40, 180, 180}; + +const int UI_FREQ = 20; // Hz const int MODEL_PATH_MAX_VERTICES_CNT = 98; -const int MODEL_LANE_PATH_CNT = 3; +const int MODEL_LANE_PATH_CNT = 2; const int TRACK_POINTS_MAX_CNT = 50 * 2; const int SET_SPEED_NA = 255; -const uint8_t bg_colors[][4] = { - [STATUS_STOPPED] = {0x07, 0x23, 0x39, 0xff}, - [STATUS_DISENGAGED] = {0x17, 0x33, 0x49, 0xff}, - [STATUS_ENGAGED] = {0x17, 0x86, 0x44, 0xff}, - [STATUS_WARNING] = {0xDA, 0x6F, 0x25, 0xff}, - [STATUS_ALERT] = {0xC9, 0x22, 0x31, 0xff}, +typedef struct Color { + uint8_t r, g, b; +} Color; + +typedef enum NetStatus { + NET_CONNECTED, + NET_DISCONNECTED, + NET_ERROR, +} NetStatus; + +typedef enum UIStatus { + STATUS_OFFROAD, + STATUS_DISENGAGED, + STATUS_ENGAGED, + STATUS_WARNING, + STATUS_ALERT, +} UIStatus; + +static std::map bg_colors = { + {STATUS_OFFROAD, {0x07, 0x23, 0x39}}, + {STATUS_DISENGAGED, {0x17, 0x33, 0x49}}, + {STATUS_ENGAGED, {0x17, 0x86, 0x44}}, + {STATUS_WARNING, {0xDA, 0x6F, 0x25}}, + {STATUS_ALERT, {0xC9, 0x22, 0x31}}, }; typedef struct UIScene { - int frontview; - int fullview; - - ModelData model; float mpc_x[50]; float mpc_y[50]; - bool world_objects_visible; mat4 extrinsic_matrix; // Last row is 0 so we can use mat4. - - float speedlimit; - bool speedlimit_valid; + bool world_objects_visible; bool is_rhd; - bool map_valid; + bool frontview; bool uilayout_sidebarcollapsed; - bool uilayout_mapenabled; // responsive layout - int ui_viz_rx; - int ui_viz_rw; + Rect viz_rect; int ui_viz_ro; std::string alert_text1; @@ -119,18 +110,22 @@ typedef struct UIScene { cereal::HealthData::HwType hwType; int satelliteCount; - uint8_t athenaStatus; + NetStatus athenaStatus; cereal::ThermalData::Reader thermal; cereal::RadarState::LeadData::Reader lead_data[2]; cereal::ControlsState::Reader controls_state; cereal::DriverState::Reader driver_state; cereal::DMonitoringState::Reader dmonitoring_state; + cereal::ModelData::Reader model; + float left_lane_points[MODEL_PATH_DISTANCE]; + float path_points[MODEL_PATH_DISTANCE]; + float right_lane_points[MODEL_PATH_DISTANCE]; } UIScene; typedef struct { float x, y; -}vertex_data; +} vertex_data; typedef struct { vertex_data v[MODEL_PATH_MAX_VERTICES_CNT]; @@ -144,8 +139,6 @@ typedef struct { typedef struct UIState { - pthread_mutex_t lock; - // framebuffer FramebufferState *fb; int fb_w, fb_h; @@ -160,93 +153,77 @@ typedef struct UIState { int img_wheel; int img_turn; int img_face; - int img_map; int img_button_settings; int img_button_home; int img_battery; int img_battery_charging; int img_network[6]; - // sockets SubMaster *sm; - PubMaster *pm; + Sound *sound; + UIStatus status; + UIScene scene; cereal::UiLayoutState::App active_app; // vision state bool vision_connected; - bool vision_connect_firstrun; - int ipc_fd; - - VIPCBuf bufs[UI_BUF_COUNT]; - VIPCBuf front_bufs[UI_BUF_COUNT]; - int cur_vision_idx; - int cur_vision_front_idx; + VisionStream stream; + // graphics GLuint frame_program; GLuint frame_texs[UI_BUF_COUNT]; EGLImageKHR khr[UI_BUF_COUNT]; void *priv_hnds[UI_BUF_COUNT]; - GLuint frame_front_texs[UI_BUF_COUNT]; - EGLImageKHR khr_front[UI_BUF_COUNT]; - void *priv_hnds_front[UI_BUF_COUNT]; GLint frame_pos_loc, frame_texcoord_loc; GLint frame_texture_loc, frame_transform_loc; + GLuint frame_vao[2], frame_vbo[2], frame_ibo[2]; + mat4 rear_frame_mat, front_frame_mat; - int rgb_width, rgb_height, rgb_stride; - size_t rgb_buf_len; - - int rgb_front_width, rgb_front_height, rgb_front_stride; - size_t rgb_front_buf_len; - - UIScene scene; + // device state bool awake; - - // timeouts int awake_timeout; - int controls_timeout; - int speed_lim_off_timeout; - int is_metric_timeout; - int longitudinal_control_timeout; - int limit_set_speed_timeout; - int hardware_timeout; - int last_athena_ping_timeout; - - bool controls_seen; + std::atomic light_sensor; - uint64_t last_athena_ping; - int status; + bool started; + bool ignition; bool is_metric; bool longitudinal_control; - bool limit_set_speed; - float speed_lim_off; - bool is_ego_over_limit; - float alert_blinking_alpha; - bool alert_blinked; - bool started; - bool vision_seen; - - std::atomic light_sensor; - - int touch_fd; - - GLuint frame_vao[2], frame_vbo[2], frame_ibo[2]; - mat4 rear_frame_mat, front_frame_mat; + uint64_t last_athena_ping; + uint64_t started_frame; - model_path_vertices_data model_path_vertices[MODEL_LANE_PATH_CNT * 2]; + bool alert_blinked; + float alert_blinking_alpha; track_vertices_data track_vertices[2]; - - Sound sound; + model_path_vertices_data model_path_vertices[MODEL_LANE_PATH_CNT * 2]; } UIState; -// API -void ui_draw_vision_alert(UIState *s, cereal::ControlsState::AlertSize va_size, int va_color, - const char* va_text1, const char* va_text2); -void ui_draw(UIState *s); -void ui_draw_sidebar(UIState *s); -void ui_draw_image(NVGcontext *vg, float x, float y, float w, float h, int image, float alpha); -void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGcolor color, float r = 0, int width = 0); -void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint &paint, float r = 0); -void ui_nvg_init(UIState *s); +void ui_init(UIState *s); +void ui_update(UIState *s); + +int write_param_float(float param, const char* param_name, bool persistent_param = false); +template +int read_param(T* param, const char *param_name, bool persistent_param = false){ + T param_orig = *param; + char *value; + size_t sz; + + int result = read_db_value(param_name, &value, &sz, persistent_param); + if (result == 0){ + std::string s = std::string(value, sz); // value is not null terminated + free(value); + + // Parse result + std::istringstream iss(s); + iss >> *param; + + // Restore original value if parsing failed + if (iss.fail()) { + *param = param_orig; + result = -1; + } + } + return result; +} diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 205906806733a4..1788816d342fd9 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -31,15 +31,15 @@ import fcntl import time import threading -from cffi import FFI from pathlib import Path +from typing import List, Tuple, Optional +from common.hardware import ANDROID from common.basedir import BASEDIR from common.params import Params from selfdrive.swaglog import cloudlog from selfdrive.controls.lib.alertmanager import set_offroad_alert -TEST_IP = os.getenv("UPDATER_TEST_IP", "8.8.8.8") LOCK_FILE = os.getenv("UPDATER_LOCK_FILE", "/tmp/safe_staging_overlay.lock") STAGING_ROOT = os.getenv("UPDATER_STAGING_ROOT", "/data/safe_staging") @@ -52,14 +52,6 @@ FINALIZED = os.path.join(STAGING_ROOT, "finalized") -# Workaround for lack of os.link in the NEOS/termux python -ffi = FFI() -ffi.cdef("int link(const char *oldpath, const char *newpath);") -libc = ffi.dlopen(None) -def link(src, dest): - return libc.link(src.encode(), dest.encode()) - - class WaitTimeHelper: def __init__(self, proc): self.proc = proc @@ -69,7 +61,7 @@ def __init__(self, proc): signal.signal(signal.SIGINT, self.graceful_shutdown) signal.signal(signal.SIGHUP, self.update_now) - def graceful_shutdown(self, signum, frame): + def graceful_shutdown(self, signum: int, frame) -> None: # umount -f doesn't appear effective in avoiding "device busy" on NEOS, # so don't actually die until the next convenient opportunity in main(). cloudlog.info("caught SIGINT/SIGTERM, dismounting overlay at next opportunity") @@ -82,35 +74,42 @@ def graceful_shutdown(self, signum, frame): self.shutdown = True self.ready_event.set() - def update_now(self, signum, frame): + def update_now(self, signum: int, frame) -> None: cloudlog.info("caught SIGHUP, running update check immediately") self.ready_event.set() - def sleep(self, t): + def sleep(self, t: float) -> None: self.ready_event.wait(timeout=t) -def run(cmd, cwd=None, low_priority=False): +def run(cmd: List[str], cwd: Optional[str] = None, low_priority: bool = False): if low_priority: cmd = ["nice", "-n", "19"] + cmd return subprocess.check_output(cmd, cwd=cwd, stderr=subprocess.STDOUT, encoding='utf8') -def set_consistent_flag(consistent): - os.system("sync") +def set_consistent_flag(consistent: bool) -> None: + os.sync() consistent_file = Path(os.path.join(FINALIZED, ".overlay_consistent")) if consistent: consistent_file.touch() elif not consistent and consistent_file.exists(): consistent_file.unlink() - os.system("sync") + os.sync() -def set_update_available_params(new_version): +def set_params(new_version: bool, failed_count: int, exception: Optional[str]) -> None: params = Params() - t = datetime.datetime.utcnow().isoformat() - params.put("LastUpdateTime", t.encode('utf8')) + params.put("UpdateFailedCount", str(failed_count)) + if failed_count == 0: + t = datetime.datetime.utcnow().isoformat() + params.put("LastUpdateTime", t.encode('utf8')) + + if exception is None: + params.delete("LastUpdateException") + else: + params.put("LastUpdateException", exception) if new_version: try: @@ -123,13 +122,7 @@ def set_update_available_params(new_version): params.put("UpdateAvailable", "1") -def dismount_ovfs(): - if os.path.ismount(OVERLAY_MERGED): - cloudlog.error("unmounting existing overlay") - run(["umount", "-l", OVERLAY_MERGED]) - - -def setup_git_options(cwd): +def setup_git_options(cwd: str) -> None: # We sync FS object atimes (which NEOS doesn't use) and mtimes, but ctimes # are outside user control. Make sure Git is set up to ignore system ctimes, # because they change when we make hard links during finalize. Otherwise, @@ -143,66 +136,133 @@ def setup_git_options(cwd): ("core.checkStat", "minimal"), ] for option, value in git_cfg: - try: - ret = run(["git", "config", "--get", option], cwd) - config_ok = ret.strip() == value - except subprocess.CalledProcessError: - config_ok = False + run(["git", "config", option, value], cwd) + + +def dismount_overlay() -> None: + if os.path.ismount(OVERLAY_MERGED): + cloudlog.info("unmounting existing overlay") + run(["umount", "-l", OVERLAY_MERGED]) - if not config_ok: - cloudlog.info(f"Setting git '{option}' to '{value}'") - run(["git", "config", option, value], cwd) +def init_overlay() -> None: + + overlay_init_file = Path(os.path.join(BASEDIR, ".overlay_init")) + + # Re-create the overlay if BASEDIR/.git has changed since we created the overlay + if overlay_init_file.is_file(): + git_dir_path = os.path.join(BASEDIR, ".git") + new_files = run(["find", git_dir_path, "-newer", str(overlay_init_file)]) + if not len(new_files.splitlines()): + # A valid overlay already exists + return + else: + cloudlog.info(".git directory changed, recreating overlay") -def init_ovfs(): cloudlog.info("preparing new safe staging area") - Params().put("UpdateAvailable", "0") + Params().put("UpdateAvailable", "0") set_consistent_flag(False) - - dismount_ovfs() + dismount_overlay() if os.path.isdir(STAGING_ROOT): shutil.rmtree(STAGING_ROOT) - for dirname in [STAGING_ROOT, OVERLAY_UPPER, OVERLAY_METADATA, OVERLAY_MERGED, FINALIZED]: + for dirname in [STAGING_ROOT, OVERLAY_UPPER, OVERLAY_METADATA, OVERLAY_MERGED]: os.mkdir(dirname, 0o755) - if not os.lstat(BASEDIR).st_dev == os.lstat(OVERLAY_MERGED).st_dev: + if os.lstat(BASEDIR).st_dev != os.lstat(OVERLAY_MERGED).st_dev: raise RuntimeError("base and overlay merge directories are on different filesystems; not valid for overlay FS!") - # Remove consistent flag from current BASEDIR so it's not copied over - if os.path.isfile(os.path.join(BASEDIR, ".overlay_consistent")): - os.remove(os.path.join(BASEDIR, ".overlay_consistent")) - # Leave a timestamped canary in BASEDIR to check at startup. The device clock # should be correct by the time we get here. If the init file disappears, or # critical mtimes in BASEDIR are newer than .overlay_init, continue.sh can # assume that BASEDIR has used for local development or otherwise modified, # and skips the update activation attempt. - Path(os.path.join(BASEDIR, ".overlay_init")).touch() + consistent_file = Path(os.path.join(BASEDIR, ".overlay_consistent")) + if consistent_file.is_file(): + consistent_file.unlink() + overlay_init_file.touch() - os.system("sync") + os.sync() overlay_opts = f"lowerdir={BASEDIR},upperdir={OVERLAY_UPPER},workdir={OVERLAY_METADATA}" run(["mount", "-t", "overlay", "-o", overlay_opts, "none", OVERLAY_MERGED]) -def finalize_from_ovfs(): +def finalize_update() -> None: """Take the current OverlayFS merged view and finalize a copy outside of OverlayFS, ready to be swapped-in at BASEDIR. Copy using shutil.copytree""" # Remove the update ready flag and any old updates cloudlog.info("creating finalized version of the overlay") set_consistent_flag(False) - shutil.rmtree(FINALIZED) # Copy the merged overlay view and set the update ready flag + if os.path.exists(FINALIZED): + shutil.rmtree(FINALIZED) shutil.copytree(OVERLAY_MERGED, FINALIZED, symlinks=True) + + # Log git repo corruption + fsck = run(["git", "fsck", "--no-progress"], FINALIZED).rstrip() + if len(fsck): + cloudlog.error(f"found git corruption, git fsck:\n{fsck}") + set_consistent_flag(True) cloudlog.info("done finalizing overlay") -def attempt_update(wait_helper): - cloudlog.info("attempting git update inside staging overlay") +def handle_neos_update(wait_helper: WaitTimeHelper) -> None: + with open(NEOS_VERSION, "r") as f: + cur_neos = f.read().strip() + + updated_neos = run(["bash", "-c", r"unset REQUIRED_NEOS_VERSION && source launch_env.sh && \ + echo -n $REQUIRED_NEOS_VERSION"], OVERLAY_MERGED).strip() + + cloudlog.info(f"NEOS version check: {cur_neos} vs {updated_neos}") + if cur_neos == updated_neos: + return + + cloudlog.info(f"Beginning background download for NEOS {updated_neos}") + set_offroad_alert("Offroad_NeosUpdate", True) + + updater_path = os.path.join(OVERLAY_MERGED, "installer/updater/updater") + update_manifest = f"file://{OVERLAY_MERGED}/installer/updater/update.json" + + neos_downloaded = False + start_time = time.monotonic() + # Try to download for one day + while not neos_downloaded and not wait_helper.shutdown and \ + (time.monotonic() - start_time < 60*60*24): + wait_helper.ready_event.clear() + try: + run([updater_path, "bgcache", update_manifest], OVERLAY_MERGED, low_priority=True) + neos_downloaded = True + except subprocess.CalledProcessError: + cloudlog.info("NEOS background download failed, retrying") + wait_helper.sleep(120) + + # If the download failed, we'll show the alert again when we retry + set_offroad_alert("Offroad_NeosUpdate", False) + if not neos_downloaded: + raise Exception("Failed to download NEOS update") + cloudlog.info(f"NEOS background download successful, took {time.monotonic() - start_time} seconds") + + +def check_git_fetch_result(fetch_txt): + err_msg = "Failed to add the host to the list of known hosts (/data/data/com.termux/files/home/.ssh/known_hosts).\n" + return len(fetch_txt) > 0 and (fetch_txt != err_msg) + + +def check_for_update() -> Tuple[bool, bool]: + setup_git_options(OVERLAY_MERGED) + try: + git_fetch_output = run(["git", "fetch", "--dry-run"], OVERLAY_MERGED, low_priority=True) + return True, check_git_fetch_result(git_fetch_output) + except subprocess.CalledProcessError: + return False, False + + +def fetch_update(wait_helper: WaitTimeHelper) -> bool: + cloudlog.info("attempting git fetch inside staging overlay") setup_git_options(OVERLAY_MERGED) @@ -212,9 +272,7 @@ def attempt_update(wait_helper): cur_hash = run(["git", "rev-parse", "HEAD"], OVERLAY_MERGED).rstrip() upstream_hash = run(["git", "rev-parse", "@{u}"], OVERLAY_MERGED).rstrip() new_version = cur_hash != upstream_hash - - err_msg = "Failed to add the host to the list of known hosts (/data/data/com.termux/files/home/.ssh/known_hosts).\n" - git_fetch_result = len(git_fetch_output) > 0 and (git_fetch_output != err_msg) + git_fetch_result = check_git_fetch_result(git_fetch_output) cloudlog.info("comparing %s to %s" % (cur_hash, upstream_hash)) if new_version or git_fetch_result: @@ -230,48 +288,15 @@ def attempt_update(wait_helper): ] cloudlog.info("git reset success: %s", '\n'.join(r)) - # Download the accompanying NEOS version if it doesn't match the current version - with open(NEOS_VERSION, "r") as f: - cur_neos = f.read().strip() - - updated_neos = run(["bash", "-c", r"unset REQUIRED_NEOS_VERSION && source launch_env.sh && \ - echo -n $REQUIRED_NEOS_VERSION"], OVERLAY_MERGED).strip() - - cloudlog.info(f"NEOS version check: {cur_neos} vs {updated_neos}") - if cur_neos != updated_neos: - cloudlog.info(f"Beginning background download for NEOS {updated_neos}") - - set_offroad_alert("Offroad_NeosUpdate", True) - updater_path = os.path.join(OVERLAY_MERGED, "installer/updater/updater") - update_manifest = f"file://{OVERLAY_MERGED}/installer/updater/update.json" - - neos_downloaded = False - start_time = time.monotonic() - # Try to download for one day - while (time.monotonic() - start_time < 60*60*24) and not wait_helper.shutdown: - wait_helper.ready_event.clear() - try: - run([updater_path, "bgcache", update_manifest], OVERLAY_MERGED, low_priority=True) - neos_downloaded = True - break - except subprocess.CalledProcessError: - cloudlog.info("NEOS background download failed, retrying") - wait_helper.sleep(120) - - # If the download failed, we'll show the alert again when we retry - set_offroad_alert("Offroad_NeosUpdate", False) - if not neos_downloaded: - raise Exception("Failed to download NEOS update") - - cloudlog.info(f"NEOS background download successful, took {time.monotonic() - start_time} seconds") + if ANDROID: + handle_neos_update(wait_helper) # Create the finalized, ready-to-swap update - finalize_from_ovfs() + finalize_update() cloudlog.info("openpilot update successful!") else: cloudlog.info("nothing new from git at this time") - set_update_available_params(new_version) return new_version @@ -281,7 +306,7 @@ def main(): if params.get("DisableUpdates") == b"1": raise RuntimeError("updates are disabled by the DisableUpdates param") - if os.geteuid() != 0: + if ANDROID and os.geteuid() != 0: raise RuntimeError("updated must be launched as root!") # Set low io priority @@ -292,52 +317,56 @@ def main(): ov_lock_fd = open(LOCK_FILE, 'w') try: fcntl.flock(ov_lock_fd, fcntl.LOCK_EX | fcntl.LOCK_NB) - except IOError: - raise RuntimeError("couldn't get overlay lock; is another updated running?") + except IOError as e: + raise RuntimeError("couldn't get overlay lock; is another updated running?") from e # Wait for IsOffroad to be set before our first update attempt wait_helper = WaitTimeHelper(proc) wait_helper.sleep(30) + overlay_init = Path(os.path.join(BASEDIR, ".overlay_init")) + if overlay_init.exists(): + overlay_init.unlink() + + first_run = True + last_fetch_time = 0 update_failed_count = 0 - update_available = False - overlay_initialized = False + + # Run the update loop + # * every 1m, do a lightweight internet/update check + # * every 10m, do a full git fetch while not wait_helper.shutdown: + update_now = wait_helper.ready_event.is_set() wait_helper.ready_event.clear() - # Check for internet every 30s + # Don't run updater while onroad or if the time's wrong time_wrong = datetime.datetime.utcnow().year < 2019 - ping_failed = os.system(f"ping -W 4 -c 1 {TEST_IP}") != 0 - if ping_failed or time_wrong: + is_onroad = params.get("IsOffroad") != b"1" + if is_onroad or time_wrong: wait_helper.sleep(30) + cloudlog.info("not running updater, not offroad") continue # Attempt an update exception = None + new_version = False update_failed_count += 1 try: - # Re-create the overlay if BASEDIR/.git has changed since we created the overlay - if overlay_initialized: - overlay_init_fn = os.path.join(BASEDIR, ".overlay_init") - git_dir_path = os.path.join(BASEDIR, ".git") - new_files = run(["find", git_dir_path, "-newer", overlay_init_fn]) - - if len(new_files.splitlines()): - cloudlog.info(".git directory changed, recreating overlay") - overlay_initialized = False - - if not overlay_initialized: - init_ovfs() - overlay_initialized = True - - if params.get("IsOffroad") == b"1": - update_available = attempt_update(wait_helper) or update_available + init_overlay() + + internet_ok, update_available = check_for_update() + if internet_ok and not update_available: update_failed_count = 0 - if not update_available and os.path.isdir(NEOSUPDATE_DIR): - shutil.rmtree(NEOSUPDATE_DIR) - else: - cloudlog.info("not running updater, openpilot running") + # Fetch updates at most every 10 minutes + if internet_ok and (update_now or time.monotonic() - last_fetch_time > 60*10): + new_version = fetch_update(wait_helper) + update_failed_count = 0 + last_fetch_time = time.monotonic() + + if first_run and not new_version and os.path.isdir(NEOSUPDATE_DIR): + shutil.rmtree(NEOSUPDATE_DIR) + first_run = False except subprocess.CalledProcessError as e: cloudlog.event( "update process failed", @@ -345,21 +374,15 @@ def main(): output=e.output, returncode=e.returncode ) - exception = e - overlay_initialized = False - except Exception: + exception = f"command failed: {e.cmd}\n{e.output}" + except Exception as e: cloudlog.exception("uncaught updated exception, shouldn't happen") + exception = str(e) - params.put("UpdateFailedCount", str(update_failed_count)) - if exception is None: - params.delete("LastUpdateException") - else: - params.put("LastUpdateException", f"command failed: {exception.cmd}\n{exception.output}") - - # Wait 10 minutes between update attempts - wait_helper.sleep(60*10) + set_params(new_version, update_failed_count, exception) + wait_helper.sleep(60) - dismount_ovfs() + dismount_overlay() if __name__ == "__main__": main() diff --git a/selfdrive/version.py b/selfdrive/version.py index 4fec0b4cc75bc0..ef975f8940b98e 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -1,34 +1,36 @@ #!/usr/bin/env python3 import os import subprocess +from typing import List, Optional + from common.basedir import BASEDIR from selfdrive.swaglog import cloudlog -def run_cmd(cmd): +def run_cmd(cmd: List[str]) -> str: return subprocess.check_output(cmd, encoding='utf8').strip() -def run_cmd_default(cmd, default=None): +def run_cmd_default(cmd: List[str], default: Optional[str] = None) -> Optional[str]: try: return run_cmd(cmd) except subprocess.CalledProcessError: return default -def get_git_commit(branch="HEAD", default=None): +def get_git_commit(branch: str = "HEAD", default: Optional[str] = None) -> Optional[str]: return run_cmd_default(["git", "rev-parse", branch], default=default) -def get_git_branch(default=None): +def get_git_branch(default: Optional[str] = None) -> Optional[str]: return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "HEAD"], default=default) -def get_git_full_branchname(default=None): +def get_git_full_branchname(default: Optional[str] = None) -> Optional[str]: return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "--symbolic-full-name", "@{u}"], default=default) -def get_git_remote(default=None): +def get_git_remote(default: Optional[str] = None) -> Optional[str]: try: local_branch = run_cmd(["git", "name-rev", "--name-only", "HEAD"]) tracking_remote = run_cmd(["git", "config", "branch." + local_branch + ".remote"]) @@ -42,12 +44,12 @@ def get_git_remote(default=None): prebuilt = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) -training_version = b"0.2.0" -terms_version = b"2" +training_version: bytes = b"0.2.0" +terms_version: bytes = b"2" -dirty = True -comma_remote = False -tested_branch = False +dirty: bool = True +comma_remote: bool = False +tested_branch: bool = False origin = get_git_remote() branch = get_git_full_branchname() From 6d6f3032c135db377e09c0f4a857c3b582637494 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Sun, 4 Oct 2020 16:42:36 +0300 Subject: [PATCH 02/22] clean up --- panda/board/safety/safety_defaults.h | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h index c187032870a668..21a034c8556931 100644 --- a/panda/board/safety/safety_defaults.h +++ b/panda/board/safety/safety_defaults.h @@ -16,13 +16,16 @@ int default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { if (HKG_forward_BUS2 != false) { HKG_forward_BUS2 = false;} HKG_lkas_bus0_cnt = 10; } else if (bus == 2) { - if (HKG_lkas_bus0_cnt == 0) { HKG_forward_BUS2 = true;} + if (HKG_lkas_bus0_cnt == 0 && !HKG_forward_BUS2) { HKG_forward_BUS2 = true;} else if (HKG_lkas_bus0_cnt > 0) { HKG_lkas_bus0_cnt -= 1;} } } // check if we have a LCAN on Bus1 if (bus == 1 && (addr == 1296 || addr == 524)) { - HKG_LCAN_on_BUS1 = true; + if (HKG_forward_BUS1 || !HKG_LCAN_on_BUS1) { + HKG_LCAN_on_BUS1 = true; + HKG_forward_BUS1 = false; + } } // check if we have a MDPS or SCC on Bus1 if (bus == 1 && (addr == 593 || addr == 897 || addr == 1057) && !HKG_LCAN_on_BUS1) { From bd0d0103e1595e6249e247ed3442e39086f89b97 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Tue, 6 Oct 2020 00:49:37 +0300 Subject: [PATCH 03/22] typo --- panda/board/safety/safety_defaults.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h index 21a034c8556931..16a7b539eaa741 100644 --- a/panda/board/safety/safety_defaults.h +++ b/panda/board/safety/safety_defaults.h @@ -62,7 +62,7 @@ static void nooutput_init(int16_t param) { UNUSED(param); controls_allowed = false; relay_malfunction_reset(); - if (board_has_obd() && HKG_forward_BUS2) { + if (board_has_obd() && HKG_forward_BUS1) { current_board->set_can_mode(CAN_MODE_OBD_CAN2); } } @@ -170,7 +170,7 @@ static void alloutput_init(int16_t param) { UNUSED(param); controls_allowed = true; relay_malfunction_reset(); - if (board_has_obd() && HKG_forward_BUS2) { + if (board_has_obd() && HKG_forward_BUS1) { current_board->set_can_mode(CAN_MODE_OBD_CAN2); } } From 073d1f74cca67d8097a3f005cd2f7c7878109264 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Tue, 6 Oct 2020 00:50:03 +0300 Subject: [PATCH 04/22] typo --- panda/board/safety/safety_hyundai_community.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda/board/safety/safety_hyundai_community.h b/panda/board/safety/safety_hyundai_community.h index 50ce36c184db9a..5d4c4f54f5d066 100644 --- a/panda/board/safety/safety_hyundai_community.h +++ b/panda/board/safety/safety_hyundai_community.h @@ -296,7 +296,7 @@ static void hyundai_community_init(int16_t param) { controls_allowed = false; relay_malfunction_reset(); - if (board_has_obd() && HKG_forward_BUS2) { + if (board_has_obd() && HKG_forward_BUS1) { current_board->set_can_mode(CAN_MODE_OBD_CAN2); } } From 638f8d587bf444cdc144618a0f500a943c197fd0 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Tue, 6 Oct 2020 02:40:18 +0300 Subject: [PATCH 05/22] fix for harness --- panda/board/safety/safety_defaults.h | 53 ++++++++++++++++------------ 1 file changed, 31 insertions(+), 22 deletions(-) diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h index 16a7b539eaa741..67161f14bf3bac 100644 --- a/panda/board/safety/safety_defaults.h +++ b/panda/board/safety/safety_defaults.h @@ -1,7 +1,9 @@ -bool HKG_forward_BUS1 = false; -bool HKG_forward_BUS2 = true; -bool HKG_LCAN_on_BUS1 = false; -int HKG_lkas_bus0_cnt = 0; +bool HKG_LCAN_on_bus1 = false; +bool HKG_forward_bus1 = false; +bool HKG_forward_obd = false; +bool HKG_forward_bus2 = true; +int HKG_obd_int_cnt = 10; +int HKG_LKAS_bus0_cnt = 0; int HKG_MDPS12_checksum = -1; int HKG_MDPS12_cnt = 0; int HKG_last_StrColT = 0; @@ -13,26 +15,33 @@ int default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { // check if LKAS connected to Bus0 if (addr == 832) { if (bus == 0) { - if (HKG_forward_BUS2 != false) { HKG_forward_BUS2 = false;} - HKG_lkas_bus0_cnt = 10; + if (HKG_forward_bus2 != false) { HKG_forward_bus2 = false;} + HKG_LKAS_bus0_cnt = 10; } else if (bus == 2) { - if (HKG_lkas_bus0_cnt == 0 && !HKG_forward_BUS2) { HKG_forward_BUS2 = true;} - else if (HKG_lkas_bus0_cnt > 0) { HKG_lkas_bus0_cnt -= 1;} + if (HKG_LKAS_bus0_cnt == 0 && !HKG_forward_bus2) { HKG_forward_bus2 = true;} + else if (HKG_LKAS_bus0_cnt > 0) { HKG_LKAS_bus0_cnt -= 1;} + if (HKG_obd_int_cnt > 1) {HKG_obd_int_cnt -= 1;} } } // check if we have a LCAN on Bus1 if (bus == 1 && (addr == 1296 || addr == 524)) { - if (HKG_forward_BUS1 || !HKG_LCAN_on_BUS1) { - HKG_LCAN_on_BUS1 = true; - HKG_forward_BUS1 = false; + if (HKG_forward_bus1 || !HKG_LCAN_on_bus1) { + HKG_LCAN_on_bus1 = true; + HKG_forward_bus1 = false; } } // check if we have a MDPS or SCC on Bus1 - if (bus == 1 && (addr == 593 || addr == 897 || addr == 1057) && !HKG_LCAN_on_BUS1) { - if (HKG_forward_BUS1 != true) { - HKG_forward_BUS1 = true; + if (bus == 1 && (addr == 593 || addr == 897 || addr == 1057) && !HKG_LCAN_on_bus1) { + if (HKG_forward_bus1 != true) { + HKG_forward_bus1 = true; + if (HKG_obd_int_cnt > 0 || current_safety_mode == SAFETY_ELM327) {HKG_forward_obd = true;} } } + // set CAN2 mode to normal if int_cnt expaired + if (HKG_obd_int_cnt == 1) { + if (!HKG_forward_obd) {current_board->set_can_mode(CAN_MODE_NORMAL);} + HKG_obd_int_cnt = 0; + } if ((addr == 593) && (HKG_MDPS12_checksum == -1)){ int New_Chksum2 = 0; @@ -62,7 +71,7 @@ static void nooutput_init(int16_t param) { UNUSED(param); controls_allowed = false; relay_malfunction_reset(); - if (board_has_obd() && HKG_forward_BUS1) { + if (board_has_obd() && (HKG_forward_obd || HKG_obd_int_cnt > 0) { current_board->set_can_mode(CAN_MODE_OBD_CAN2); } } @@ -83,16 +92,16 @@ static int default_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { int addr = GET_ADDR(to_fwd); int bus_fwd = -1; int HKG_bus1 = 0, HKG_bus2 = 0; - if (HKG_forward_BUS1){HKG_bus1 = 1;} - if (HKG_forward_BUS2){HKG_bus2 = 2;} + if (HKG_forward_bus1){HKG_bus1 = 1;} + if (HKG_forward_bus2){HKG_bus2 = 2;} - if (bus_num == 0 && (HKG_forward_BUS1 || HKG_forward_BUS2)) { - bus_fwd = (HKG_forward_BUS1 && HKG_forward_BUS2) ? 12 : HKG_bus1 + HKG_bus2; + if (bus_num == 0 && (HKG_forward_bus1 || HKG_forward_bus2)) { + bus_fwd = (HKG_forward_bus1 && HKG_forward_bus2) ? 12 : HKG_bus1 + HKG_bus2; } - if (bus_num == 1 && HKG_forward_BUS1) { + if (bus_num == 1 && HKG_forward_bus1) { bus_fwd = HKG_bus2 * 10; } - if (bus_num == 2 && HKG_forward_BUS2) { + if (bus_num == 2 && HKG_forward_bus2) { bus_fwd = HKG_bus1 * 10; } // Code for LKA/LFA/HDA anti-nagging. @@ -170,7 +179,7 @@ static void alloutput_init(int16_t param) { UNUSED(param); controls_allowed = true; relay_malfunction_reset(); - if (board_has_obd() && HKG_forward_BUS1) { + if (board_has_obd() && HKG_forward_obd) { current_board->set_can_mode(CAN_MODE_OBD_CAN2); } } From 923e09b905f96896b9f4c7dd260c8538e47d814b Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Tue, 6 Oct 2020 02:40:23 +0300 Subject: [PATCH 06/22] fix for harness --- panda/board/safety/safety_hyundai_community.h | 27 +++++++++---------- 1 file changed, 12 insertions(+), 15 deletions(-) diff --git a/panda/board/safety/safety_hyundai_community.h b/panda/board/safety/safety_hyundai_community.h index 5d4c4f54f5d066..f10b3acafa52da 100644 --- a/panda/board/safety/safety_hyundai_community.h +++ b/panda/board/safety/safety_hyundai_community.h @@ -40,24 +40,21 @@ static int hyundai_community_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { hyundai_get_checksum, hyundai_compute_checksum, hyundai_get_counter); - if (bus == 1 && HKG_LCAN_on_BUS1) {valid = false;} + if (bus == 1 && HKG_LCAN_on_bus1) {valid = false;} // check MDPS on Bus if ((addr == 593 || addr == 897) && HKG_mdps_bus != bus) { if (bus == 0){ HKG_mdps_bus = bus; - if (!HKG_forward_BUS1 && board_has_obd()) { - current_board->set_can_mode(CAN_MODE_NORMAL); - } - } else if (bus == 1 && !HKG_LCAN_on_BUS1) { + } else if (bus == 1 && !HKG_LCAN_on_bus1) { HKG_mdps_bus = bus; - HKG_forward_BUS1 = true; + HKG_forward_bus1 = true; } } // check if we have a SCC on Bus1 and LCAN not on the bus - if (bus == 1 && addr == 1057 && !HKG_LCAN_on_BUS1) { - if (!HKG_forward_BUS1) { - HKG_forward_BUS1 = true; + if (bus == 1 && addr == 1057 && !HKG_LCAN_on_bus1) { + if (!HKG_forward_bus1) { + HKG_forward_bus1 = true; } } @@ -230,7 +227,7 @@ static int hyundai_community_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_f int bus_fwd = -1; int addr = GET_ADDR(to_fwd); int fwd_to_bus1 = -1; - if (HKG_forward_BUS1){fwd_to_bus1 = 1;} + if (HKG_forward_bus1){fwd_to_bus1 = 1;} // forward cam to ccan and viceversa, except lkas cmd if (!relay_malfunction) { @@ -238,7 +235,7 @@ static int hyundai_community_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_f if (!OP_CLU_live || addr != 1265 || HKG_mdps_bus == 0) { if (!OP_MDPS_live || addr != 593) { if (!OP_EMS_live || addr != 790) { - bus_fwd = HKG_forward_BUS1 ? 12 : 2; + bus_fwd = HKG_forward_bus1 ? 12 : 2; } else { bus_fwd = 2; // EON create EMS11 for MDPS OP_EMS_live -= 1; @@ -252,7 +249,7 @@ static int hyundai_community_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_f OP_CLU_live -= 1; } } - if (bus_num == 1 && HKG_forward_BUS1) { + if (bus_num == 1 && HKG_forward_bus1) { if (!OP_MDPS_live || addr != 593) { if (!OP_SCC_live || (addr != 1056 && addr != 1057 && addr != 1290 && addr != 905)) { bus_fwd = 20; @@ -268,7 +265,7 @@ static int hyundai_community_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_f if (bus_num == 2) { if (!OP_LKAS_live || (addr != 832 && addr != 1157)) { if (!OP_SCC_live || (addr != 1056 && addr != 1057 && addr != 1290 && addr != 905)) { - bus_fwd = HKG_forward_BUS1 ? 10 : 0; + bus_fwd = HKG_forward_bus1 ? 10 : 0; } else { bus_fwd = fwd_to_bus1; // EON create SCC12 for Car OP_SCC_live -= 1; @@ -284,7 +281,7 @@ static int hyundai_community_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_f if (bus_num == 0) { bus_fwd = fwd_to_bus1; } - if (bus_num == 1 && HKG_forward_BUS1) { + if (bus_num == 1 && HKG_forward_bus1) { bus_fwd = 0; } } @@ -296,7 +293,7 @@ static void hyundai_community_init(int16_t param) { controls_allowed = false; relay_malfunction_reset(); - if (board_has_obd() && HKG_forward_BUS1) { + if (board_has_obd() && HKG_forward_obd) { current_board->set_can_mode(CAN_MODE_OBD_CAN2); } } From 51423e9922b135302d601d31405d0e046a3abde7 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Tue, 6 Oct 2020 02:40:29 +0300 Subject: [PATCH 07/22] relay off --- panda/board/main.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/panda/board/main.c b/panda/board/main.c index e9316b9af8c7f2..ab2864f5150b6c 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -123,21 +123,21 @@ void set_safety_mode(uint16_t mode, int16_t param) { } switch (mode_copy) { case SAFETY_SILENT: - set_intercept_relay(false); + set_intercept_relay(true); if (board_has_obd()) { current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_SILENT; break; case SAFETY_NOOUTPUT: - set_intercept_relay(false); + set_intercept_relay(true); if (board_has_obd()) { current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_LIVE; break; case SAFETY_ELM327: - set_intercept_relay(false); + set_intercept_relay(true); heartbeat_counter = 0U; if (board_has_obd()) { current_board->set_can_mode(CAN_MODE_OBD_CAN2); From ec1754b067e63265b1e159c600d2fcd6a8e80c0e Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Tue, 6 Oct 2020 02:49:14 +0300 Subject: [PATCH 08/22] bugs --- panda/board/safety/safety_defaults.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h index 67161f14bf3bac..6546ceaad0a700 100644 --- a/panda/board/safety/safety_defaults.h +++ b/panda/board/safety/safety_defaults.h @@ -34,7 +34,7 @@ int default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { if (bus == 1 && (addr == 593 || addr == 897 || addr == 1057) && !HKG_LCAN_on_bus1) { if (HKG_forward_bus1 != true) { HKG_forward_bus1 = true; - if (HKG_obd_int_cnt > 0 || current_safety_mode == SAFETY_ELM327) {HKG_forward_obd = true;} + if (HKG_obd_int_cnt > 0) {HKG_forward_obd = true;} } } // set CAN2 mode to normal if int_cnt expaired @@ -71,7 +71,7 @@ static void nooutput_init(int16_t param) { UNUSED(param); controls_allowed = false; relay_malfunction_reset(); - if (board_has_obd() && (HKG_forward_obd || HKG_obd_int_cnt > 0) { + if (board_has_obd() && (HKG_forward_obd || HKG_obd_int_cnt > 0)) { current_board->set_can_mode(CAN_MODE_OBD_CAN2); } } From 7a7f343978fc4f976615c320aa727ea62ae38464 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 5 Oct 2020 22:08:03 -0700 Subject: [PATCH 09/22] Fix calibration invalid alert on startup --- selfdrive/controls/controlsd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index fe576192e79c9b..d13d83cf84b8e6 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -124,7 +124,7 @@ def __init__(self, sm=None, pm=None, can_sock=None): self.events_prev = [] self.current_alert_types = [ET.PERMANENT] - self.sm['liveCalibration'].calStatus = Calibration.INVALID + self.sm['liveCalibration'].calStatus = Calibration.CALIBRATED self.sm['thermal'].freeSpace = 1. self.sm['dMonitoringState'].events = [] self.sm['dMonitoringState'].awarenessStatus = 1. From db336329c58234218f9e6183ed235c75adf0d291 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 6 Oct 2020 02:10:45 -0700 Subject: [PATCH 10/22] fix not going onroad on clean dashcam install (#2280) --- selfdrive/thermald/thermald.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 10b8a454786c11..fc963242d943f4 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -363,7 +363,8 @@ def thermald_thread(): should_start = should_start and msg.thermal.freeSpace > 0.02 # confirm we have completed training and aren't uninstalling - should_start = should_start and accepted_terms and completed_training and (not do_uninstall) + should_start = should_start and accepted_terms and (not do_uninstall) and \ + (completed_training or current_branch in ['dashcam', 'dashcam-staging']) # check for firmware mismatch should_start = should_start and fw_version_match From 62c438c7dace9d6ee45136383bee6dcbb90467b0 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Tue, 6 Oct 2020 21:00:08 +0300 Subject: [PATCH 11/22] fix bug --- panda/board/safety/safety_defaults.h | 25 +++++++------------------ 1 file changed, 7 insertions(+), 18 deletions(-) diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h index 6546ceaad0a700..3f198616a43979 100644 --- a/panda/board/safety/safety_defaults.h +++ b/panda/board/safety/safety_defaults.h @@ -12,16 +12,8 @@ int default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { int bus = GET_BUS(to_push); int addr = GET_ADDR(to_push); - // check if LKAS connected to Bus0 - if (addr == 832) { - if (bus == 0) { - if (HKG_forward_bus2 != false) { HKG_forward_bus2 = false;} - HKG_LKAS_bus0_cnt = 10; - } else if (bus == 2) { - if (HKG_LKAS_bus0_cnt == 0 && !HKG_forward_bus2) { HKG_forward_bus2 = true;} - else if (HKG_LKAS_bus0_cnt > 0) { HKG_LKAS_bus0_cnt -= 1;} - if (HKG_obd_int_cnt > 1) {HKG_obd_int_cnt -= 1;} - } + if (addr == 832 && bus == 2) { + if (HKG_obd_int_cnt > 1) {HKG_obd_int_cnt -= 1;} } // check if we have a LCAN on Bus1 if (bus == 1 && (addr == 1296 || addr == 524)) { @@ -91,18 +83,15 @@ static int nooutput_tx_lin_hook(int lin_num, uint8_t *data, int len) { static int default_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { int addr = GET_ADDR(to_fwd); int bus_fwd = -1; - int HKG_bus1 = 0, HKG_bus2 = 0; - if (HKG_forward_bus1){HKG_bus1 = 1;} - if (HKG_forward_bus2){HKG_bus2 = 2;} - if (bus_num == 0 && (HKG_forward_bus1 || HKG_forward_bus2)) { - bus_fwd = (HKG_forward_bus1 && HKG_forward_bus2) ? 12 : HKG_bus1 + HKG_bus2; + if (bus_num == 0 && HKG_forward_bus1) { + bus_fwd = HKG_forward_bus1 ? 12 : 2; } if (bus_num == 1 && HKG_forward_bus1) { - bus_fwd = HKG_bus2 * 10; + bus_fwd = 20; } - if (bus_num == 2 && HKG_forward_bus2) { - bus_fwd = HKG_bus1 * 10; + if (bus_num == 2) { + bus_fwd = HKG_forward_bus1 ? 10 : 0; } // Code for LKA/LFA/HDA anti-nagging. if (addr == 593 && bus_fwd != -1) { From 2de12deb4c9aacbe2b2c78e7e889ab20e23b1a69 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Thu, 8 Oct 2020 04:12:48 +0300 Subject: [PATCH 12/22] revert SCC auto resume logic --- selfdrive/car/hyundai/carcontroller.py | 22 ++++++++++++++++++---- 1 file changed, 18 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 4fdcdb5218c757..77c3d3c8695a93 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -71,6 +71,7 @@ def __init__(self, dbc_name, CP, VM): self.lkas11_cnt = 0 self.scc12_cnt = 0 self.last_resume_frame = 0 + self.last_lead_distance = 0 self.turning_signal_timer = 0 self.lkas_button_on = True self.longcontrol = CP.openpilotLongitudinalControl @@ -190,11 +191,24 @@ def update(self, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert, if pcm_cancel_cmd and self.longcontrol: can_sends.append(create_clu11(self.packer, frame, CS.scc_bus, CS.clu11, Buttons.CANCEL, clu11_speed)) - elif CS.out.cruiseState.standstill: - # send resume at a max freq of 5Hz - if CS.lead_distance > 3.7 and (frame - self.last_resume_frame)*DT_CTRL > 0.2: + + if CS.out.cruiseState.standstill: + # run only first time when the car stopped + if self.last_lead_distance == 0: + # get the lead distance from the Radar + self.last_lead_distance = CS.lead_distance + self.resume_cnt = 0 + # when lead car starts moving, create 6 RES msgs + elif CS.lead_distance != self.last_lead_distance and (frame - self.last_resume_frame) > 5: can_sends.append(create_clu11(self.packer, frame, CS.scc_bus, CS.clu11, Buttons.RES_ACCEL, clu11_speed)) - self.last_resume_frame = frame + self.resume_cnt += 1 + # interval after 6 msgs + if self.resume_cnt > 5: + self.last_resume_frame = frame + self.clu11_cnt = 0 + # reset lead distnce after the car starts moving + elif self.last_lead_distance != 0: + self.last_lead_distance = 0 if CS.mdps_bus: # send mdps12 to LKAS to prevent LKAS error can_sends.append(create_mdps12(self.packer, frame, CS.mdps12)) From a437f97aee4ea347f6af4e67313ddf682a27db2b Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Fri, 9 Oct 2020 23:56:26 +0900 Subject: [PATCH 13/22] fix carname cardenza -> cadenza Update hyundaican.py ldws active car add --- selfdrive/car/hyundai/hyundaican.py | 9 ++++----- selfdrive/car/hyundai/interface.py | 2 +- selfdrive/car/hyundai/values.py | 18 +++++++++--------- 3 files changed, 14 insertions(+), 15 deletions(-) diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index 4e30d66f0cda56..65dcd598c6f632 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -35,13 +35,12 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, # SysWarning 5 = keep hands on wheel (red) # SysWarning 6 = keep hands on wheel (red) + beep # Note: the warning is hidden while the blinkers are on - values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 + values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 + # This field is actually LdwsActivemode ( only use ldws camera ) elif car_fingerprint == CAR.GENESIS: - # This field is actually LdwsActivemode - # Genesis and Optima fault when forwarding while engaged - values["CF_Lkas_LdwsActivemode"] = 2 - elif car_fingerprint == CAR.OPTIMA: + values["CF_Lkas_LdwsActivemode"] = 2 + elif car_fingerprint in [CAR.OPTIMA, CAR.OPTIMA_HEV, CAR.CADENZA, CAR.CADENZA_HEV]: values["CF_Lkas_LdwsActivemode"] = 0 dat = packer.make_can_msg("LKAS11", 0, values)[2] diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 47c7246cbea47c..d739d8aec9ab07 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -213,7 +213,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, ret.mass = 1737. + STD_CARGO_KG ret.wheelbase = 2.7 tire_stiffness_factor = 0.385 - elif candidate in [CAR.CARDENZA, CAR.CARDENZA_HEV]: + elif candidate in [CAR.CADENZA, CAR.CADENZA_HEV]: ret.mass = 1575. + STD_CARGO_KG ret.wheelbase = 2.85 ret.steerRatio = 12.5 diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 3116874fa732b1..2a2548111ade3b 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -50,8 +50,8 @@ class CAR: NIRO_EV = "KIA NIRO EV 2020 PLATINUM" NIRO_HEV = "KIA NIRO HEV 2018" CEED = "KIA CEED 2019" - CARDENZA = "KIA K7 2016-2019" - CARDENZA_HEV = "KIA K7 HEV 2016-2019" + CADENZA = "KIA K7 2016-2019" + CADENZA_HEV = "KIA K7 HEV 2016-2019" class Buttons: NONE = 0 @@ -226,7 +226,7 @@ class Buttons: CAR.CEED: [{ 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1157: 4, 1168: 7, 1170: 8, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8, 1407: 8, 1414: 3, 1427: 6, 1456: 4, 2015: 8 }], - CAR.CARDENZA: [{ + CAR.CADENZA: [{ 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 546: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1162: 4, 1168: 7, 1170: 8, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1427: 6, 1444: 8, 1456: 4, 1470: 8 },{ 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 608: 8, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1162: 4, 1168: 7, 1170: 8, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1427: 6, 1444: 8, 1456: 4, 1470: 8 @@ -235,7 +235,7 @@ class Buttons: },{ 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 546: 8, 549: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1162: 4, 1168: 7, 1170: 8, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1427: 6, 1444: 8, 1456: 4, 1470: 8 }], - CAR.CARDENZA_HEV: [{ + CAR.CADENZA_HEV: [{ 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 576: 8, 593: 8, 688: 5, 832: 8, 865: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1096: 8, 1102: 8, 1108: 8, 1136: 6, 1138: 5, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 7, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1210: 8, 1227: 8, 1265: 4, 1268: 8, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1343: 8, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1379: 8, 1407: 8, 1419: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 },{ 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 549: 8, 832: 8, 881: 8, 882: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1078: 4, 1136: 6, 1151: 6, 1156: 8, 1168: 7, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1291: 8, 1292: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1378: 4, 1407: 8, 1419: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 @@ -445,13 +445,13 @@ class Buttons: FEATURES = { # Use Cluster for Gear Selection, rather than Transmission - "use_cluster_gears": set([CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30, CAR.CARDENZA, CAR.NIRO_HEV, CAR.GRANDEUR]), + "use_cluster_gears": set([CAR.ELANTRA, CAR.KONA, CAR.ELANTRA_GT_I30, CAR.CADENZA, CAR.NIRO_HEV, CAR.GRANDEUR]), # Use TCU Message for Gear Selection "use_tcu_gears": set([CAR.OPTIMA, CAR.SONATA19, CAR.VELOSTER]), # Use E_GEAR Message for Gear Selection - "use_elect_gears": set([CAR.OPTIMA_HEV, CAR.IONIQ_EV, CAR.KONA_EV, CAR.SONATA_HEV, CAR.NIRO_EV, CAR.CARDENZA_HEV, CAR.GRANDEUR_HEV]), + "use_elect_gears": set([CAR.OPTIMA_HEV, CAR.IONIQ_EV, CAR.KONA_EV, CAR.SONATA_HEV, CAR.NIRO_EV, CAR.CADENZA_HEV, CAR.GRANDEUR_HEV]), # Use E_EMS11 Message for Gas and Brake for Hybrid/ELectric - "use_elect_ems": set([CAR.OPTIMA_HEV, CAR.IONIQ_EV, CAR.KONA_EV, CAR.SONATA_HEV, CAR.NIRO_EV, CAR.CARDENZA_HEV, CAR.GRANDEUR_HEV]), + "use_elect_ems": set([CAR.OPTIMA_HEV, CAR.IONIQ_EV, CAR.KONA_EV, CAR.SONATA_HEV, CAR.NIRO_EV, CAR.CADENZA_HEV, CAR.GRANDEUR_HEV]), # send LFA MFA message for new HKG models "send_lfa_mfa": set([CAR.SONATA, CAR.PALISADE, CAR.SONATA_HEV, CAR.SANTA_FE, CAR.NIRO_EV]), "has_scc13": set([]), @@ -494,8 +494,8 @@ class Buttons: CAR.NIRO_EV: dbc_dict('hyundai_kia_generic', None), CAR.NIRO_HEV: dbc_dict('hyundai_kia_generic', None), CAR.CEED: dbc_dict('hyundai_kia_generic', None), - CAR.CARDENZA: dbc_dict('hyundai_kia_generic', None), - CAR.CARDENZA_HEV: dbc_dict('hyundai_kia_generic', None), + CAR.CADENZA: dbc_dict('hyundai_kia_generic', None), + CAR.CADENZA_HEV: dbc_dict('hyundai_kia_generic', None), } STEER_THRESHOLD = 150 From c49d4b91be4849dea65496c2d44fb61bb95f159b Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Sun, 11 Oct 2020 18:32:36 +0300 Subject: [PATCH 14/22] remove white spaces --- selfdrive/car/hyundai/hyundaican.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index 65dcd598c6f632..1793883f3eec09 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -35,7 +35,7 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, # SysWarning 5 = keep hands on wheel (red) # SysWarning 6 = keep hands on wheel (red) + beep # Note: the warning is hidden while the blinkers are on - values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 + values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 # This field is actually LdwsActivemode ( only use ldws camera ) elif car_fingerprint == CAR.GENESIS: From 52e3cfb948a49b16900e48055fc389f0d29d04d0 Mon Sep 17 00:00:00 2001 From: xx979xx Date: Fri, 16 Oct 2020 17:33:22 +0300 Subject: [PATCH 15/22] fix merge --- panda/board/main.c | 1 + 1 file changed, 1 insertion(+) diff --git a/panda/board/main.c b/panda/board/main.c index ab37392c2ab734..42829b7cc64a35 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -710,6 +710,7 @@ void TIM1_BRK_TIM9_IRQ_Handler(void) { // increase heartbeat counter and cap it at the uint32 limit if (heartbeat_counter < __UINT32_MAX__) { heartbeat_counter += 1U; + } #ifdef EON // check heartbeat counter if we are running EON code. From a0c892f88215c540f812535ed3bacb578e34bf04 Mon Sep 17 00:00:00 2001 From: xx979xx Date: Fri, 16 Oct 2020 18:36:16 +0300 Subject: [PATCH 16/22] cleanup --- panda/board/safety/safety_defaults.h | 8 +++-- panda/board/safety/safety_hyundai_community.h | 30 +++++++++++-------- 2 files changed, 23 insertions(+), 15 deletions(-) diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h index 3f198616a43979..ecb16c04281236 100644 --- a/panda/board/safety/safety_defaults.h +++ b/panda/board/safety/safety_defaults.h @@ -12,8 +12,12 @@ int default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { int bus = GET_BUS(to_push); int addr = GET_ADDR(to_push); - if (addr == 832 && bus == 2) { - if (HKG_obd_int_cnt > 1) {HKG_obd_int_cnt -= 1;} + if (addr == 832) { + if (bus == 0 && HKG_forward_BUS2) {HKG_forward_BUS2 = false;HKG_LKAS_bus0_cnt = 10;} + if (bus == 2) { + if (HKG_LKAS_bus0_cnt > 0) {HKG_LKAS_bus0_cnt--;} else if (!HKG_forward_BUS2) {HKG_forward_BUS2 = true;} + if (HKG_obd_int_cnt > 1) {HKG_obd_int_cnt -= 1;} + } } // check if we have a LCAN on Bus1 if (bus == 1 && (addr == 1296 || addr == 524)) { diff --git a/panda/board/safety/safety_hyundai_community.h b/panda/board/safety/safety_hyundai_community.h index f10b3acafa52da..ef160192858ff6 100644 --- a/panda/board/safety/safety_hyundai_community.h +++ b/panda/board/safety/safety_hyundai_community.h @@ -1,4 +1,3 @@ -bool hyundai_has_scc = false; int OP_LKAS_live = 0; int OP_MDPS_live = 0; int OP_CLU_live = 0; @@ -6,6 +5,7 @@ int OP_SCC_live = 0; int car_SCC_live = 0; int OP_EMS_live = 0; int HKG_mdps_bus = -1; +int HKG_scc_bus = -1; const CanMsg HYUNDAI_COMMUNITY_TX_MSGS[] = { {832, 0, 8}, {832, 1, 8}, // LKAS11 Bus 0, 1 {1265, 0, 4}, {1265, 1, 4}, {1265, 2, 4}, // CLU11 Bus 0, 1, 2 @@ -42,19 +42,25 @@ static int hyundai_community_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { if (bus == 1 && HKG_LCAN_on_bus1) {valid = false;} + // check if LKAS on Bus0 + if (addr == 832) { + if (bus == 0 && HKG_forward_BUS2) {HKG_forward_BUS2 = false; HKG_LKAS_bus0_cnt = 10;} + if (bus == 2) { + if (HKG_LKAS_bus0_cnt > 0) {HKG_LKAS_bus0_cnt--;} else if (!HKG_forward_BUS2) {HKG_forward_BUS2 = true;} + } + } // check MDPS on Bus if ((addr == 593 || addr == 897) && HKG_mdps_bus != bus) { - if (bus == 0){ + if (bus != 1 || !HKG_LCAN_on_bus1) { HKG_mdps_bus = bus; - } else if (bus == 1 && !HKG_LCAN_on_bus1) { - HKG_mdps_bus = bus; - HKG_forward_bus1 = true; - } + if (bus == 1 && !HKG_forward_bus1) {HKG_forward_bus1 = true;} + } } - // check if we have a SCC on Bus1 and LCAN not on the bus - if (bus == 1 && addr == 1057 && !HKG_LCAN_on_bus1) { - if (!HKG_forward_bus1) { - HKG_forward_bus1 = true; + // check SCC on Bus + if ((addr == 1056 || addr == 1057) && HKG_scc_bus != bus) { + if (bus != 1 || !HKG_LCAN_on_bus1) { + HKG_scc_bus = bus; + if (bus == 1 && !HKG_forward_bus1) {HKG_forward_bus1 = true;} } } @@ -67,7 +73,6 @@ static int hyundai_community_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { // enter controls on rising edge of ACC, exit controls on ACC off if (addr == 1057 && OP_SCC_live) { // for cars with long control - hyundai_has_scc = true; car_SCC_live = 50; // 2 bits: 13-14 int cruise_engaged = (GET_BYTES_04(to_push) >> 13) & 0x3; @@ -80,7 +85,6 @@ static int hyundai_community_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { cruise_engaged_prev = cruise_engaged; } if (addr == 1056 && !OP_SCC_live) { // for cars without long control - hyundai_has_scc = true; // 2 bits: 13-14 int cruise_engaged = GET_BYTES_04(to_push) & 0x1; // ACC main_on signal if (cruise_engaged && !cruise_engaged_prev) { @@ -92,7 +96,7 @@ static int hyundai_community_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { cruise_engaged_prev = cruise_engaged; } // cruise control for car without SCC - if (addr == 608 && bus == 0 && !hyundai_has_scc && !OP_SCC_live) { + if (addr == 608 && bus == 0 && HKG_scc_bus != -1 && !OP_SCC_live) { // bit 25 int cruise_engaged = (GET_BYTES_04(to_push) >> 25 & 0x1); // ACC main_on signal if (cruise_engaged && !cruise_engaged_prev) { From 3688768e4b048fd7e84cafd2c3cefc3c0b8428b5 Mon Sep 17 00:00:00 2001 From: xx979xx Date: Fri, 16 Oct 2020 20:36:52 +0300 Subject: [PATCH 17/22] PUF cleanup --- panda/board/safety/safety_defaults.h | 9 ++++++--- panda/board/safety/safety_hyundai_community.h | 13 +++++++++---- 2 files changed, 15 insertions(+), 7 deletions(-) diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h index ecb16c04281236..785fbf582b82ee 100644 --- a/panda/board/safety/safety_defaults.h +++ b/panda/board/safety/safety_defaults.h @@ -4,6 +4,7 @@ bool HKG_forward_obd = false; bool HKG_forward_bus2 = true; int HKG_obd_int_cnt = 10; int HKG_LKAS_bus0_cnt = 0; +int HKG_Lcan_bus1_cnt = 0; int HKG_MDPS12_checksum = -1; int HKG_MDPS12_cnt = 0; int HKG_last_StrColT = 0; @@ -13,14 +14,16 @@ int default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { int addr = GET_ADDR(to_push); if (addr == 832) { - if (bus == 0 && HKG_forward_BUS2) {HKG_forward_BUS2 = false;HKG_LKAS_bus0_cnt = 10;} + if (bus == 0 && HKG_forward_bus2) {HKG_forward_bus2 = false; HKG_LKAS_bus0_cnt = 10;} if (bus == 2) { - if (HKG_LKAS_bus0_cnt > 0) {HKG_LKAS_bus0_cnt--;} else if (!HKG_forward_BUS2) {HKG_forward_BUS2 = true;} - if (HKG_obd_int_cnt > 1) {HKG_obd_int_cnt -= 1;} + if (HKG_LKAS_bus0_cnt > 0) {HKG_LKAS_bus0_cnt--;} else if (!HKG_forward_bus2) {HKG_forward_bus2 = true;} + if (HKG_Lcan_bus1_cnt > 0) {HKG_Lcan_bus1_cnt--;} else if (HKG_LCAN_on_bus1) {HKG_LCAN_on_bus1 = false;} + if (HKG_obd_int_cnt > 1) {HKG_obd_int_cnt--;} } } // check if we have a LCAN on Bus1 if (bus == 1 && (addr == 1296 || addr == 524)) { + HKG_Lcan_bus1_cnt = 100; if (HKG_forward_bus1 || !HKG_LCAN_on_bus1) { HKG_LCAN_on_bus1 = true; HKG_forward_bus1 = false; diff --git a/panda/board/safety/safety_hyundai_community.h b/panda/board/safety/safety_hyundai_community.h index ef160192858ff6..b81dac54881de1 100644 --- a/panda/board/safety/safety_hyundai_community.h +++ b/panda/board/safety/safety_hyundai_community.h @@ -41,12 +41,17 @@ static int hyundai_community_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { hyundai_get_counter); if (bus == 1 && HKG_LCAN_on_bus1) {valid = false;} - + // check if we have a LCAN on Bus1 + if (bus == 1 && (addr == 1296 || addr == 524)) { + HKG_Lcan_bus1_cnt = 100; + if (HKG_forward_bus1 || !HKG_LCAN_on_bus1) { HKG_LCAN_on_bus1 = true; HKG_forward_bus1 = false;} + } // check if LKAS on Bus0 if (addr == 832) { - if (bus == 0 && HKG_forward_BUS2) {HKG_forward_BUS2 = false; HKG_LKAS_bus0_cnt = 10;} + if (bus == 0 && HKG_forward_bus2) {HKG_forward_bus2 = false; HKG_LKAS_bus0_cnt = 10;} if (bus == 2) { - if (HKG_LKAS_bus0_cnt > 0) {HKG_LKAS_bus0_cnt--;} else if (!HKG_forward_BUS2) {HKG_forward_BUS2 = true;} + if (HKG_LKAS_bus0_cnt > 0) {HKG_LKAS_bus0_cnt--;} else if (!HKG_forward_bus2) {HKG_forward_bus2 = true;} + if (HKG_Lcan_bus1_cnt > 0) {HKG_Lcan_bus1_cnt--;} else if (HKG_LCAN_on_bus1) {HKG_LCAN_on_bus1 = false;} } } // check MDPS on Bus @@ -234,7 +239,7 @@ static int hyundai_community_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_f if (HKG_forward_bus1){fwd_to_bus1 = 1;} // forward cam to ccan and viceversa, except lkas cmd - if (!relay_malfunction) { + if (HKG_forward_bus2) { if (bus_num == 0) { if (!OP_CLU_live || addr != 1265 || HKG_mdps_bus == 0) { if (!OP_MDPS_live || addr != 593) { From 501fdac61df0051332070ce4cd6c0a47ec3cd038 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Fri, 16 Oct 2020 21:04:06 +0300 Subject: [PATCH 18/22] config for Noctua fan --- selfdrive/thermald/thermald.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index fc963242d943f4..c2d4069b7ac3c2 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -125,6 +125,10 @@ def set_eon_fan(val): _FAN_SPEEDS = [0, 16384, 32768, 65535] # max fan speed only allowed if battery is hot _BAT_TEMP_THRESHOLD = 45. +# config for Noctua fan +if os.getenv("NOCTUA") == 1: + _FAN_SPEEDS = [0, 65535, 65535, 65535] + _BAT_TEMP_THRESHOLD = 25. def handle_fan_eon(max_cpu_temp, bat_temp, fan_speed, ignition): From bdee0a2759801ceba08b859ef29df77b4de1087f Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Fri, 16 Oct 2020 21:21:42 +0300 Subject: [PATCH 19/22] fix grey not charging --- selfdrive/boardd/boardd.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 9823ad98509443..122dae2aa515fa 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -157,9 +157,9 @@ bool usb_connect() { // power on charging, only the first time. Panda can also change mode and it causes a brief disconneciton #ifndef __x86_64__ - if (!connected_once) { - panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CDP); - } + //if (!connected_once) { + panda->set_usb_power_mode(cereal::HealthData::UsbPowerMode::CDP); + //} #endif if (panda->has_rtc){ From 2b01dc47c21a12111d7d5f58e978d8c732a4e1db Mon Sep 17 00:00:00 2001 From: xx979xx Date: Fri, 16 Oct 2020 22:57:44 +0300 Subject: [PATCH 20/22] Revert "obd2 default" This reverts commit c3c2c6f063b1ce893f785b1e2f962b0b8f70e6ac. --- panda/board/main.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/panda/board/main.c b/panda/board/main.c index 7755016f2a4090..42829b7cc64a35 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -125,14 +125,14 @@ void set_safety_mode(uint16_t mode, int16_t param) { case SAFETY_SILENT: set_intercept_relay(true); if (board_has_obd()) { - current_board->set_can_mode(CAN_MODE_OBD_CAN2); + current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_SILENT; break; case SAFETY_NOOUTPUT: set_intercept_relay(true); if (board_has_obd()) { - current_board->set_can_mode(CAN_MODE_OBD_CAN2); + current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_LIVE; break; @@ -148,7 +148,7 @@ void set_safety_mode(uint16_t mode, int16_t param) { set_intercept_relay(true); heartbeat_counter = 0U; if (board_has_obd()) { - current_board->set_can_mode(CAN_MODE_OBD_CAN2); + current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_LIVE; break; From de5dc89eab5bf2aab2dc3fb9f797c8ac48a7d81c Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Fri, 16 Oct 2020 23:15:02 +0300 Subject: [PATCH 21/22] bug --- panda/board/safety/safety_hyundai_community.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda/board/safety/safety_hyundai_community.h b/panda/board/safety/safety_hyundai_community.h index b81dac54881de1..a7aa2dd14420ad 100644 --- a/panda/board/safety/safety_hyundai_community.h +++ b/panda/board/safety/safety_hyundai_community.h @@ -101,7 +101,7 @@ static int hyundai_community_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { cruise_engaged_prev = cruise_engaged; } // cruise control for car without SCC - if (addr == 608 && bus == 0 && HKG_scc_bus != -1 && !OP_SCC_live) { + if (addr == 608 && bus == 0 && HKG_scc_bus == -1 && !OP_SCC_live) { // bit 25 int cruise_engaged = (GET_BYTES_04(to_push) >> 25 & 0x1); // ACC main_on signal if (cruise_engaged && !cruise_engaged_prev) { From 2fd25662112adb41c1f9c41d7d0e07dbf7b70669 Mon Sep 17 00:00:00 2001 From: xx979xx <40252818+xx979xx@users.noreply.github.com> Date: Fri, 16 Oct 2020 23:21:55 +0300 Subject: [PATCH 22/22] remove 0x10 error debug --- panda/board/drivers/usb.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/panda/board/drivers/usb.h b/panda/board/drivers/usb.h index e85af95af587c3..452eda60dd78ee 100644 --- a/panda/board/drivers/usb.h +++ b/panda/board/drivers/usb.h @@ -842,7 +842,7 @@ void usb_irqhandler(void) { // TODO: why was this here? fires when TX buffers when we can't clear NAK // USBx_OUTEP(3)->DOEPTSIZ = (1U << 19) | 0x40U; // USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - } else if ((USBx_OUTEP(3)->DOEPINT) != 0) { + } else if ((USBx_OUTEP(3)->DOEPINT) != 0 && (USBx_OUTEP(3)->DOEPINT) != 0x10) { puts("OUTEP3 error "); puth(USBx_OUTEP(3)->DOEPINT); puts("\n"); @@ -1051,4 +1051,4 @@ void usb_init(void) { // enable the IRQ NVIC_EnableIRQ(OTG_FS_IRQn); -} \ No newline at end of file +}