From 04e96bb64dfc8e4238d9f916993b9868994daacd Mon Sep 17 00:00:00 2001 From: Paul Beuchat <beuchatp@control.ee.ethz.ch> Date: Thu, 14 May 2020 21:29:17 +0200 Subject: [PATCH] Upgrade the crazyradio cflib to release 0.1.10 (13 Mar 2020) from the crazyflie-lib-python repository on the bitcraze github --- .../src/dfall_pkg/crazyradio/CONTRIBUTING.md | 55 + .../src/dfall_pkg/crazyradio/CrazyRadio.py | 106 +- dfall_ws/src/dfall_pkg/crazyradio/README.md | 53 +- dfall_ws/src/dfall_pkg/crazyradio/TestCF.py | 244 -- .../crazyradio/build/lib/cflib/__init__.py | 54 - .../build/lib/cflib/bootloader/__init__.py | 386 -- .../build/lib/cflib/bootloader/boottypes.py | 96 - .../build/lib/cflib/bootloader/cloader.py | 389 -- .../build/lib/cflib/crazyflie/__init__.py | 400 -- .../build/lib/cflib/crazyflie/commander.py | 129 - .../build/lib/cflib/crazyflie/console.py | 61 - .../build/lib/cflib/crazyflie/extpos.py | 52 - .../build/lib/cflib/crazyflie/localization.py | 122 - .../build/lib/cflib/crazyflie/log.py | 558 --- .../build/lib/cflib/crazyflie/mem.py | 950 ----- .../build/lib/cflib/crazyflie/param.py | 340 -- .../lib/cflib/crazyflie/platformservice.py | 56 - .../build/lib/cflib/crazyflie/swarm.py | 192 - .../lib/cflib/crazyflie/syncCrazyflie.py | 97 - .../build/lib/cflib/crazyflie/syncLogger.py | 115 - .../build/lib/cflib/crazyflie/toc.py | 189 - .../build/lib/cflib/crazyflie/toccache.py | 123 - .../build/lib/cflib/crtp/__init__.py | 96 - .../build/lib/cflib/crtp/crtpdriver.py | 94 - .../build/lib/cflib/crtp/crtpstack.py | 152 - .../build/lib/cflib/crtp/debugdriver.py | 897 ----- .../build/lib/cflib/crtp/exceptions.py | 45 - .../build/lib/cflib/crtp/radiodriver.py | 538 --- .../build/lib/cflib/crtp/serialdriver.py | 59 - .../build/lib/cflib/crtp/udpdriver.py | 107 - .../build/lib/cflib/crtp/usbdriver.py | 257 -- .../build/lib/cflib/drivers/cfusb.py | 197 - .../build/lib/cflib/drivers/crazyradio.py | 315 -- .../build/lib/cflib/utils/callbacks.py | 54 - .../crazyradio/build/lib/lpslib/__init__.py | 40 - .../crazyradio/build/lib/lpslib/lopoanchor.py | 59 - .../build/lib/test/crazyflie/test_swarm.py | 225 -- .../lib/test/crazyflie/test_syncCrazyflie.py | 144 - .../lib/test/crazyflie/test_syncLogger.py | 230 -- .../build/lib/test/crtp/__init__.py | 0 .../build/lib/test/crtp/test_crtpstack.py | 104 - .../build/lib/test/support/__init__.py | 0 .../lib/test/support/asyncCallbackCaller.py | 46 - .../build/lib/test/utils/__init__.py | 0 .../build/lib/test/utils/test_callbacks.py | 97 - .../crazyradio/cflib.egg-info/PKG-INFO | 16 - .../crazyradio/cflib.egg-info/SOURCES.txt | 52 - .../cflib.egg-info/dependency_links.txt | 1 - .../crazyradio/cflib.egg-info/requires.txt | 1 - .../crazyradio/cflib.egg-info/top_level.txt | 3 - .../crazyradio/cflib/bootloader/__init__.py | 2 +- .../crazyradio/cflib/bootloader/cloader.py | 47 +- .../crazyradio/cflib/crazyflie/__init__.py | 15 +- .../crazyradio/cflib/crazyflie/commander.py | 15 + .../crazyradio/cflib/crazyflie/extpos.py | 10 +- .../cflib/crazyflie/high_level_commander.py | 201 + .../cflib/crazyflie/localization.py | 30 +- .../crazyradio/cflib/crazyflie/log.py | 50 +- .../crazyradio/cflib/crazyflie/mem.py | 496 ++- .../crazyradio/cflib/crazyflie/param.py | 76 +- .../cflib/crazyflie/platformservice.py | 76 +- .../crazyradio/cflib/crazyflie/swarm.py | 19 + .../cflib/crazyflie/syncCrazyflie.py | 25 +- .../crazyradio/cflib/crazyflie/syncLogger.py | 38 +- .../crazyradio/cflib/crazyflie/toc.py | 53 +- .../crazyradio/cflib/crtp/__init__.py | 4 +- .../crazyradio/cflib/crtp/crtpstack.py | 1 + .../crazyradio/cflib/crtp/debugdriver.py | 28 +- .../crazyradio/cflib/crtp/prrtdriver.py | 104 + .../crazyradio/cflib/crtp/radiodriver.py | 102 +- .../crazyradio/cflib/crtp/serialdriver.py | 232 +- .../crazyradio/cflib/drivers/cfusb.py | 10 +- .../crazyradio/cflib/drivers/crazyradio.py | 27 +- .../utils => cflib/positioning}/__init__.py | 8 +- .../cflib/positioning/motion_commander.py | 484 +++ .../positioning/position_hl_commander.py | 298 ++ .../crazyradio/cflib/utils/callbacks.py | 3 +- .../crazyradio/cflib/utils/multiranger.py | 115 + .../crazyradio/dist/cflib-0.1.3-py3.5.egg | Bin 194915 -> 0 bytes .../dfall_pkg/crazyradio/docs/_data/menu.yml | 16 + .../crazyradio/docs/crazyradio_lib.md | 161 + .../src/dfall_pkg/crazyradio/docs/eeprom.md | 23 + .../src/dfall_pkg/crazyradio/docs/index.md | 12 + .../crazyradio/docs/install_from_source.md | 37 + .../src/dfall_pkg/crazyradio/docs/matlab.md | 107 + .../dfall_pkg/crazyradio/docs/python_api.md | 414 ++ .../src/dfall_pkg/crazyradio/docs/testing.md | 26 + .../crazyradio/docs/usb_permissions.md | 35 + .../crazyradio/examples/autonomousSequence.py | 14 +- .../autonomous_sequence_high_level.py | 182 + .../crazyradio/examples/basicLedmemSync.py | 66 + .../crazyradio/examples/basicLedparamSync.py | 74 + .../dfall_pkg/crazyradio/examples/basiclog.py | 3 +- .../crazyradio/examples/basiclogSync.py | 7 +- .../crazyradio/examples/basicparam.py | 3 +- .../crazyradio/examples/cache/.gitkeep | 1 + .../crazyradio/examples/cache/AB949641.json | 1738 +++++++++ .../crazyradio/examples/cache/CA011AD2.json | 3393 +++++++++++++++++ .../dfall_pkg/crazyradio/examples/cfbridge.py | 147 + .../crazyradio/examples/flowsequenceSync.py | 5 +- .../lighthouse/lighthouse_openvr_grab.py | 176 + .../lighthouse_openvr_grab_color.py | 208 + .../lighthouse/lighthouse_openvr_multigrab.py | 204 + .../examples/lighthouse/read-geometry-mem.py | 69 + .../examples/lighthouse/write-geometry-mem.py | 88 + .../examples/motion_commander_demo.py | 100 + .../crazyradio/examples/multiramp.py | 2 +- .../examples/multiranger_pointcloud.py | 365 ++ .../crazyradio/examples/multiranger_push.py | 105 + .../examples/position_commander_demo.py | 82 + .../examples/positioning/bezier_trajectory.py | 425 +++ .../initial_position.py} | 113 +- .../positioning/matrix_light_printer.py | 115 + .../examples/positioning/monalisa.png | Bin 0 -> 4886 bytes .../qualisys/qualisys_hl_commander.py | 315 ++ .../crazyradio/examples/radio-test.py | 8 +- .../src/dfall_pkg/crazyradio/examples/ramp.py | 2 +- .../dfall_pkg/crazyradio/examples/read-ow.py | 1 + .../examples/swarm/hl-commander-swarm.py | 145 + .../examples/swarm/swarmSequence.py | 296 ++ .../{ => swarm}/swarmSequenceCircle.py | 4 +- .../examples/swarm/synchronizedSequence.py | 250 ++ .../dfall_pkg/crazyradio/examples/write-ow.py | 17 +- .../dfall_pkg/crazyradio/lpslib/lopoanchor.py | 13 + dfall_ws/src/dfall_pkg/crazyradio/setup.py | 2 +- .../{build/lib/test => sys_test}/__init__.py | 0 .../swarm_test_rig}/__init__.py | 8 +- .../sys_test/swarm_test_rig/cload_all_nrf.sh | 14 + .../sys_test/swarm_test_rig/cload_all_stm.sh | 14 + .../sys_test/swarm_test_rig/rig_support.py | 77 + .../swarm_test_rig/test_connection.py | 114 + .../sys_test/swarm_test_rig/test_logging.py | 73 + .../swarm_test_rig/test_memory_map.py | 110 + .../swarm_test_rig/test_response_time.py | 144 + .../test/crazyflie/test_syncCrazyflie.py | 9 + .../test/crazyflie/test_syncLogger.py | 50 +- .../positioning}/__init__.py | 0 .../test/positioning/test_motion_commander.py | 491 +++ .../positioning/test_position_hl_commander.py | 386 ++ .../crazyradio/test/utils/test_multiranger.py | 262 ++ .../dfall_pkg/crazyradio/tools/build/sys-test | 16 + .../src/dfall_pkg/crazyradio/tools/build/test | 2 +- dfall_ws/src/dfall_pkg/crazyradio/tox.ini | 4 +- web_interface/install_dfall_server_WIP.sh | 42 + 144 files changed, 13806 insertions(+), 8744 deletions(-) create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/CONTRIBUTING.md delete mode 100755 dfall_ws/src/dfall_pkg/crazyradio/TestCF.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/__init__.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/__init__.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/boottypes.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/cloader.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/__init__.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/commander.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/console.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/extpos.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/localization.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/log.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/mem.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/param.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/platformservice.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/swarm.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncLogger.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toc.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toccache.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/__init__.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpdriver.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpstack.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/debugdriver.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/exceptions.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/radiodriver.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/serialdriver.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/udpdriver.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/usbdriver.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/cfusb.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/crazyradio.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/utils/callbacks.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/__init__.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/lopoanchor.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_swarm.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncLogger.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crtp/__init__.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crtp/test_crtpstack.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/support/__init__.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/support/asyncCallbackCaller.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/utils/__init__.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/utils/test_callbacks.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/PKG-INFO delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/SOURCES.txt delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/dependency_links.txt delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/requires.txt delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/top_level.txt create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/high_level_commander.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/prrtdriver.py rename dfall_ws/src/dfall_pkg/crazyradio/{build/lib/cflib/utils => cflib/positioning}/__init__.py (86%) create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/cflib/positioning/motion_commander.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/cflib/positioning/position_hl_commander.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/multiranger.py delete mode 100644 dfall_ws/src/dfall_pkg/crazyradio/dist/cflib-0.1.3-py3.5.egg create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/docs/_data/menu.yml create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/docs/crazyradio_lib.md create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/docs/eeprom.md create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/docs/index.md create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/docs/install_from_source.md create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/docs/matlab.md create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/docs/python_api.md create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/docs/testing.md create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/docs/usb_permissions.md create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/autonomous_sequence_high_level.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/basicLedmemSync.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/basicLedparamSync.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/cache/.gitkeep create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/cache/AB949641.json create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/cache/CA011AD2.json create mode 100755 dfall_ws/src/dfall_pkg/crazyradio/examples/cfbridge.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_grab.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_grab_color.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_multigrab.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/read-geometry-mem.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/write-geometry-mem.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/motion_commander_demo.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/multiranger_pointcloud.py create mode 100755 dfall_ws/src/dfall_pkg/crazyradio/examples/multiranger_push.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/position_commander_demo.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/bezier_trajectory.py rename dfall_ws/src/dfall_pkg/crazyradio/examples/{swarmSequence.py => positioning/initial_position.py} (60%) create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/matrix_light_printer.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/monalisa.png create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/qualisys/qualisys_hl_commander.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/hl-commander-swarm.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/swarmSequence.py rename dfall_ws/src/dfall_pkg/crazyradio/examples/{ => swarm}/swarmSequenceCircle.py (96%) create mode 100755 dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/synchronizedSequence.py rename dfall_ws/src/dfall_pkg/crazyradio/{build/lib/test => sys_test}/__init__.py (100%) rename dfall_ws/src/dfall_pkg/crazyradio/{build/lib/cflib/drivers => sys_test/swarm_test_rig}/__init__.py (85%) create mode 100755 dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/cload_all_nrf.sh create mode 100755 dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/cload_all_stm.sh create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/rig_support.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_connection.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_logging.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_memory_map.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_response_time.py rename dfall_ws/src/dfall_pkg/crazyradio/{build/lib/test/crazyflie => test/positioning}/__init__.py (100%) create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/test/positioning/test_motion_commander.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/test/positioning/test_position_hl_commander.py create mode 100644 dfall_ws/src/dfall_pkg/crazyradio/test/utils/test_multiranger.py create mode 100755 dfall_ws/src/dfall_pkg/crazyradio/tools/build/sys-test diff --git a/dfall_ws/src/dfall_pkg/crazyradio/CONTRIBUTING.md b/dfall_ws/src/dfall_pkg/crazyradio/CONTRIBUTING.md new file mode 100644 index 00000000..1ace13f4 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/CONTRIBUTING.md @@ -0,0 +1,55 @@ +Contribution guide +================== + +ðŸ‘🎉 Thanks a lot for considering contributing 🎉👠+ +We welcome and encourage contribution. There is many way to contribute: you can +write bug report, contribute code or documentation. +You can also go to the [bitcraze forum](https://forum.bitcraze.io) and help others. + +## Reporting issues + +When reporting issues the more information you can supply the better. +Since the lib runs on many different OSes, can connect to multiple versions of the Crazyflie and you could use our official releases or clone directly from Git, it can be hard to figure out what's happening. + + - **Information about the environment:** + - What OS are your running on + - What version of Python are you using + - If relevant, what version of the Crazyflie firmware are you using + - **How to reproduce the issue:** Step-by-step guide on how the issue can be reproduced (or at least how you reproduce it). + Include everything you think might be useful, the more information the better. + +## Improvements request and proposal + +We and the community are continuously working to improve the lib. +Feel free to make an issue to request a new functionality. + +## Contributing code/Pull-Request + +We welcome code contribution, this can be done by starting a pull-request. + +If the change is big, typically if the change span to more than one file, consider starting an issue first to discuss the improvement. +This will makes it much easier to make the change fit well into the lib. + +There is some basic requirement for us to merge a pull request: + - Describe the change + - Refer to any issues it effects + - Separate one pull request per functionality: if you start writing "and" in the feature description consider if it could be separated in two pull requests. + - The pull request must pass the automated test (see test section bellow) + +In your code: +- Don't include name, date or information about the change in the code. That's what Git is for. +- CamelCase classes, but not functions and variables +- Private variables and functions should start with _ +- 4 spaces indentation +- When catching exceptions try to make it as specific as possible, it makes it harder for bugs to hide +- Short variable and function names are OK if the scope is small +- The code should pass flake8 + +### Run test + +In order to run the tests you can run: +``` +python tools/build/build +python3 tools/build/build +``` diff --git a/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py b/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py index fb0e3cf5..96897d1d 100755 --- a/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py @@ -45,7 +45,7 @@ from std_msgs.msg import Int32 from dfall_pkg.msg import ControlCommand from dfall_pkg.msg import IntWithHeader from dfall_pkg.msg import FlyingVehicleState -from dfall_pkg.msg import GyroMeasurements +#from dfall_pkg.msg import GyroMeasurements # Import dfall_pkg services from dfall_pkg.srv import IntIntService @@ -287,9 +287,9 @@ class CrazyRadioClient: cfStateEstimate.pitch = -data["stateEstimateZ.pitch"] / 1000.0 cfStateEstimate.yaw = data["stateEstimateZ.yaw"] / 1000.0 # > (roll,pitch,yaw) anglular rates (direct from gryo) - cfStateEstimate.rollRate = data["stateEstimateZ.rateRoll"] / 1000.0 - cfStateEstimate.pitchRate = -data["stateEstimateZ.ratePitch"] / 1000.0 - cfStateEstimate.yawRate = data["stateEstimateZ.rateYaw"] / 1000.0 + #cfStateEstimate.rollRate = data["stateEstimateZ.rateRoll"] / 1000.0 + #cfStateEstimate.pitchRate = -data["stateEstimateZ.ratePitch"] / 1000.0 + #cfStateEstimate.yawRate = data["stateEstimateZ.rateYaw"] / 1000.0 # Print out one value for DEBUGGING #print "[CRAZY RADIO] received (z,vz) = ( %6.3f , %6.3f )" %( cfStateEstimate.z , cfStateEstimate.vz ) @@ -310,23 +310,23 @@ class CrazyRadioClient: - # Initialise the variable for the gyroscope data - gyroMeasurements = GyroMeasurements() + # # Initialise the variable for the gyroscope data + # gyroMeasurements = GyroMeasurements() - # Retrieve the values from the data packet received - # > (roll,pitch,yaw) anglular rates (direct from gryo) - gyroMeasurements.rollrate = data["stateEstimateZ.rateRoll"] / 1000.0 - gyroMeasurements.pitchrate = -data["stateEstimateZ.ratePitch"] / 1000.0 - gyroMeasurements.yawrate = data["stateEstimateZ.rateYaw"] / 1000.0 + # # Retrieve the values from the data packet received + # # > (roll,pitch,yaw) anglular rates (direct from gryo) + # gyroMeasurements.rollrate = data["stateEstimateZ.rateRoll"] / 1000.0 + # gyroMeasurements.pitchrate = -data["stateEstimateZ.ratePitch"] / 1000.0 + # gyroMeasurements.yawrate = data["stateEstimateZ.rateYaw"] / 1000.0 - # Fill in the name - gyroMeasurements.vehicleName = self.crazyflie_name + # # Fill in the name + # gyroMeasurements.vehicleName = self.crazyflie_name - # Print out one value for DEBUGGING - #print "[CRAZY RADIO] gyro (r,p,y) = ( %6.3f , %6.3f , %6.3f )" %( gyroMeasurements.rollrate*RAD_TO_DEG , gyroMeasurements.pitchrate*RAD_TO_DEG , gyroMeasurements.yawrate*RAD_TO_DEG ) + # # Print out one value for DEBUGGING + # #print "[CRAZY RADIO] gyro (r,p,y) = ( %6.3f , %6.3f , %6.3f )" %( gyroMeasurements.rollrate*RAD_TO_DEG , gyroMeasurements.pitchrate*RAD_TO_DEG , gyroMeasurements.yawrate*RAD_TO_DEG ) - # Publish the gyroscope measurements - cfgyroMeasurements_pub.publish(gyroMeasurements) + # # Publish the gyroscope measurements + # cfgyroMeasurements_pub.publish(gyroMeasurements) @@ -337,20 +337,38 @@ class CrazyRadioClient: def _start_logging(self): + # NOTE: that logging can only be started when + # connected to a Crazyflie is becuse "add_config(...)" + # function check that the variables requested are + # available in the onboard TOC (table of contents). + # A "LOGGING GROUP" FOR THE BATTERY VOLTAGE: # Initialise a log config object self.logconf_battery = LogConfig("LoggingBattery", period_in_ms=battery_polling_period) # Add the varaibles to be logged self.logconf_battery.add_variable("pm.vbat", "float"); - # Add the log config to the crazyflie object - self._cf.log.add_config(self.logconf_battery) - if self.logconf_battery.valid: + # + # Try to add the log config to the crazyflie object + try: + self._cf.log.add_config(self.logconf_battery) + # Add the callback for received data self.logconf_battery.data_received_cb.add_callback(self._data_received_battery_callback) + # Add the callback for errors self.logconf_battery.error_cb.add_callback(self._logging_error) - print "[CRAZY RADIO] The log config for the battery voltage is valid" - else: - print "[CRAZY RADIO] The log config for the battery voltage is invalid" + # Check the log config is valid + if self.logconf_battery.valid: + # Start the logging + self.logconf_battery.start() + rospy.loginfo("[CRAZY RADIO] Started the log config for the battery voltage") + else: + rospy.loginfo("[CRAZY RADIO] The log config for the battery voltage is invalid, hence logging has not been started.") + # Handle "key error" exceptions: + except KeyError as e: + rospy.logerr("[CRAZY RADIO] For the battery voltage, the following error occurred while trying to add the log config: %s" % str(e) ) + # Handle "attribution error" exceptions: + except AttributeError: + rospy.logerr("[CRAZY RADIO] The battery voltage log config has a bad configuration.") # A "LOGGING GROUP" FOR THE STATE ESTIMATE: @@ -374,26 +392,30 @@ class CrazyRadioClient: self.logconf_stateEstimate.add_variable("stateEstimateZ.pitch", "int16_t"); self.logconf_stateEstimate.add_variable("stateEstimateZ.yaw", "int16_t"); # > (roll,pitch,yaw) anglular rates (direct from gryo) - self.logconf_stateEstimate.add_variable("stateEstimateZ.rateRoll", "int16_t"); - self.logconf_stateEstimate.add_variable("stateEstimateZ.ratePitch", "int16_t"); - self.logconf_stateEstimate.add_variable("stateEstimateZ.rateYaw", "int16_t"); - # Add the log config to the crazyflie object - self._cf.log.add_config(self.logconf_stateEstimate) - if self.logconf_stateEstimate.valid: + #self.logconf_stateEstimate.add_variable("stateEstimateZ.rateRoll", "int16_t"); + #self.logconf_stateEstimate.add_variable("stateEstimateZ.ratePitch", "int16_t"); + #self.logconf_stateEstimate.add_variable("stateEstimateZ.rateYaw", "int16_t"); + # + # Try to add the log config to the crazyflie object + try: + self._cf.log.add_config(self.logconf_stateEstimate) + # Add the callback for received data self.logconf_stateEstimate.data_received_cb.add_callback(self._data_received_stateEstimate_callback) + # Add the callback for errors self.logconf_stateEstimate.error_cb.add_callback(self._logging_error) - print "[CRAZY RADIO] The log config for the state estimate is valid" - else: - print "[CRAZY RADIO] The log config for the state estimate is invalid" - - - # START THE LOGGING FOR ALL THE "LOGGING GROUPS" ADDED - # > For the battery voltage - self.logconf_battery.start() - print "[CRAZY RADIO] Started the log config for the battery voltage" - # > For the state estimate - self.logconf_stateEstimate.start() - print "[CRAZY RADIO] Started the log config for the state estimate" + # Check the log config is valid + if self.logconf_stateEstimate.valid: + # Start the logging + self.logconf_stateEstimate.start() + rospy.loginfo("[CRAZY RADIO] Started the log config for the state estimate") + else: + rospy.loginfo("[CRAZY RADIO] The log config for the state estimate is invalid, hence logging has not been started.") + # Handle "key error" exceptions: + except KeyError as e: + rospy.logerr("[CRAZY RADIO] For the state estimate, the following error occurred while trying to add the log config: %s" % str(e) ) + # Handle "attribution error" exceptions: + except AttributeError: + rospy.logerr("[CRAZY RADIO] The state estimate log config has a bad configuration.") @@ -605,7 +627,7 @@ class CrazyRadioClient: ): # Call the CrazyRadio function that sets the # paramter for reseting the onboard estimate - self._cf.param.set_value("kalman.resetEstimation", "1") + self._cf.param.set_value("kalman.resetEstimation", 1) # Inform the user #print "[CRAZY RADIO] reqested the Crazyflie to reset the onboard estimate" diff --git a/dfall_ws/src/dfall_pkg/crazyradio/README.md b/dfall_ws/src/dfall_pkg/crazyradio/README.md index 3fbb58ce..48e2db63 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/README.md +++ b/dfall_ws/src/dfall_pkg/crazyradio/README.md @@ -13,26 +13,37 @@ For more info see our [wiki](http://wiki.bitcraze.se/ "Bitcraze Wiki"). * [Fork the cflib](https://help.github.com/articles/fork-a-repo/) * [Clone the cflib](https://help.github.com/articles/cloning-a-repository/), `git clone git@github.com:YOUR-USERNAME/crazyflie-lib-python.git` * [Install the cflib in editable mode](http://pip-python3.readthedocs.org/en/latest/reference/pip_install.html?highlight=editable#editable-installs), `pip install -e path/to/cflib` -* [Uninstall the cflib](http://pip-python3.readthedocs.org/en/latest/reference/pip_uninstall.html), `pip uninstall cflib` -Note: If you are developing for the [cfclient][cfclient] you must use python3. + +* [Uninstall the cflib if you don't want it any more](http://pip-python3.readthedocs.org/en/latest/reference/pip_uninstall.html), `pip uninstall cflib` + +Note: If you are developing for the [cfclient][cfclient] you must use python3. On Ubuntu (16.04, 18.08) use `pip3` instead of `pip`. ### Linux, OSX, Windows -* Build a [virtualenv (local python environment)](https://virtualenv.pypa.io/en/latest/) with package dependencies - * `pip install virtualenv` - * `virtualenv venv` - * `source venv/bin/activate` -* `pip install -r requirements.txt` + +The following should be executed in the root of the crazyflie-lib-python file tree. + +#### Virtualenv +This section contains a very short description of how to use [virtualenv (local python environment)](https://virtualenv.pypa.io/en/latest/) +with package dependencies. If you don't want to use virualenv and don't mind installing cflib dependencies system-wide +you can skip this section. + +* Install virtualenv: `pip install virtualenv` +* create an environment: `virtualenv venv` * Activate the environment: `source venv/bin/activate` -* Connect the crazyflie and run an example: `python -m examples.basiclog` -* Deactivate the virtualenv if you activated it `deactivate` -Note: For systems that support [make](https://www.gnu.org/software/make/manual/html_node/Simple-Makefile.html), the first four steps can be replaced with `make venv` -Note: The first three steps can be skipped if you don't mind installing cflib dependencies system-wide. +* To deactivate the virtualenv when you are done using it `deactivate` + +Note: For systems that support [make](https://www.gnu.org/software/make/manual/html_node/Simple-Makefile.html), you can use `make venv` to +create an environment, activate it and install dependencies. +#### Install cflib dependencies +Install dependencies required by the lib: `pip install -r requirements.txt` -# Testing +To verify the installation, connect the crazyflie and run an example: `python examples/basiclog` + +## Testing ### With docker and the toolbelt For information and installation of the @@ -45,9 +56,12 @@ Note: Docker and the toolbelt is an optional way of running tests and reduces th work needed to maintain your python environmet. ### Native python on Linux, OSX, Windows -* [Tox](http://tox.readthedocs.org/en/latest/) is used for native testing: `pip install tox` + [Tox](http://tox.readthedocs.org/en/latest/) is used for native testing: `pip install tox` +* If test fails after installing tox with `pip install tox`, installing with `sudo apt-get install tox`result a successful test run + * Test package in python2.7 `TOXENV=py27 tox` * Test package in python3.4 `TOXENV=py34 tox` +* Test package in python3.6 `TOXENV=py36 tox` Note: You must have the specific python versions on your machine or tests will fail. (ie. without specifying the TOXENV, `tox` runs tests for python2.7, 3.3, 3.4 and would require all python versions to be installed on the machine.) @@ -62,13 +76,18 @@ The following steps make it possible to use the USB Radio without being root. ``` sudo groupadd plugdev -sudo usermod -a -G plugdev <username> +sudo usermod -a -G plugdev $USER ``` +You will need to log out and log in again in order to be a member of the plugdev group. + Create a file named ```/etc/udev/rules.d/99-crazyradio.rules``` and add the following: ``` +# Crazyradio (normal operation) SUBSYSTEM=="usb", ATTRS{idVendor}=="1915", ATTRS{idProduct}=="7777", MODE="0664", GROUP="plugdev" +# Bootloader +SUBSYSTEM=="usb", ATTRS{idVendor}=="1915", ATTRS{idProduct}=="0101", MODE="0664", GROUP="plugdev" ``` To connect Crazyflie 2.0 via usb, create a file name ```/etc/udev/rules.d/99-crazyflie.rules``` and add the following: @@ -76,6 +95,12 @@ To connect Crazyflie 2.0 via usb, create a file name ```/etc/udev/rules.d/99-cra SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5740", MODE="0664", GROUP="plugdev" ``` +You can reload the udev-rules using the following: +``` +sudo udevadm control --reload-rules +sudo udevadm trigger +``` + [cfclient]: https://www.github.com/bitcraze/crazyflie-clients-python diff --git a/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py b/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py deleted file mode 100755 index 0f3431c9..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py +++ /dev/null @@ -1,244 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- - -# import roslib; roslib.load_manifest('dfall_pkg') -# import rospy -# from dfall_pkg.msg import ControlCommand -# from std_msgs.msg import Int32 - - -# General import -import time, sys -import struct -import logging - -# import rosbag -# from rospkg import RosPack -from std_msgs.msg import Float32 -# from std_msgs.msg import String - -# Add library -#sys.path.append("lib") - -# CrazyFlie client imports -import cflib - -from cflib.crazyflie import Crazyflie -from cflib.crtp.crtpstack import CRTPPacket, CRTPPort - -import cflib.drivers.crazyradio - -# Logging import(* -from cflib.crazyflie.log import LogConfig - -# Logging settings -logging.basicConfig(level=logging.ERROR) - -# Types: - -CF_COMMAND_TYPE_MOTORS = 6 -CF_COMMAND_TYPE_RATE = 7 -CF_COMMAND_TYPE_ANGLE = 8 - -CONTROLLER_MOTOR = 2 -CONTROLLER_ANGLE = 1 -CONTROLLER_RATE = 0 -RAD_TO_DEG = 57.296 - -# CrazyRadio states: -CONNECTED = 0 -CONNECTING = 1 -DISCONNECTED = 2 - -# Commands coming -CMD_RECONNECT = 0 -CMD_DISCONNECT = 1 - - -# rp = RosPack() -# record_file = rp.get_path('dfall_pkg') + '/LoggingOnboard.bag' -# rospy.loginfo('afdsasdfasdfsadfasdfasdfasdfasdfasdfasdf') -# rospy.loginfo(record_file) -# bag = rosbag.Bag(record_file, 'w') - -class CrazyRadioClient: - """ - CrazyRadio client that recieves the commands from the controller and - sends them in a CRTP package to the crazyflie with the specified - address. - """ - def __init__(self): - - # Setpoints to be sent to the CrazyFlie - self.roll = 0.0 - self.pitch = 0.0 - self.yaw = 0.0 - self.motor1cmd = 0.0 - self.motor2cmd = 0.0 - self.motor3cmd = 0.0 - self.motor4cmd = 0.0 - self._status = DISCONNECTED - self.link_uri = "" - - # self.status_pub = rospy.Publisher(node_name + '/CrazyRadioStatus', Int32, queue_size=1) - # self.FlyingAgentClient_command_pub = rospy.Publisher('FlyingAgentClient/Command', Int32, queue_size=1) - time.sleep(1.0) - - # Initialize the CrazyFlie and add callbacks - self._init_cf() - - # Connect to the Crazyflie - self.connect() - - def _init_cf(self): - self._cf = Crazyflie() - - # Add callbacks that get executed depending on the connection _status. - self._cf.connected.add_callback(self._connected) - self._cf.disconnected.add_callback(self._disconnected) - self._cf.connection_failed.add_callback(self._connection_failed) - self._cf.connection_lost.add_callback(self._connection_lost) - - - def get_status(self): - return self._status - - def update_link_uri(self): - self.link_uri = "radio://0/79/2M" - - def connect(self): - # update link from ros params - self.update_link_uri() - - print "Connecting to %s" % self.link_uri - self._cf.open_link(self.link_uri) - - def disconnect(self): - print "Motors OFF" - self._send_to_commander(0, 0, 0, 0, 0, 0, 0, 0, CONTROLLER_MOTOR) - print "Disconnecting from %s" % self.link_uri - self._cf.close_link() - - def _data_received_callback(self, timestamp, data, logconf): - #print "log of stabilizer and battery: [%d][%s]: %s" % (timestamp, logconf.name, data) - batteryVolt = Float32() - stabilizerYaw = Float32() - stabilizerPitch = Float32() - stabilizerRoll = Float32() - batteryVolt.data = data["pm.vbat"] - stabilizerYaw.data = data["stabilizer.yaw"] - stabilizerPitch.data = data["stabilizer.pitch"] - - def _logging_error(self, logconf, msg): - print "Error when logging %s" % logconf.name - - # def _init_logging(self): - - def _start_logging(self): - self.logconf = LogConfig("LoggingTest", 100) # second variable is freq in ms - self.logconf.add_variable("stabilizer.roll", "float"); - self.logconf.add_variable("stabilizer.pitch", "float"); - self.logconf.add_variable("stabilizer.yaw", "float"); - self.logconf.add_variable("pm.vbat", "float"); - - self._cf.log.add_config(self.logconf) - if self.logconf.valid: - self.logconf.data_received_cb.add_callback(self._data_received_callback) - self.logconf.error_cb.add_callback(self._logging_error) - print "logconf valid" - else: - print "logconf invalid" - - self.logconf.start() - print "logconf start" - - def _connected(self, link_uri): - """ - This callback is executed as soon as the connection to the - quadrotor is established. - """ - # cf_client._send_to_commander(15000, 15000, 15000, 15000); - # cf_client._send_to_commander_rate(1000, 0, 1000, 0, 1, 1, 1) - cf_client._send_to_commander_angle(1000, 0, 1000, 0, 1, 1, 1) - print "sent command to commander" - # Config for Logging - self._start_logging() - - - def _connection_failed(self, link_uri, msg): - """Callback when connection initial connection fails (i.e no Crazyflie - at the specified address)""" - rospy.logerr("Connection to %s failed: %s" % (link_uri, msg)) - - def _connection_lost(self, link_uri, msg): - """Callback when disconnected after a connection has been made (i.e - Crazyflie moves out of range)""" - rospy.logerr("Connection to %s lost: %s" % (link_uri, msg)) - - def _disconnected(self, link_uri): - """Callback when the Crazyflie is disconnected (called in all cases)""" - self.logconf.stop() - rospy.loginfo("logconf stopped") - self.logconf.delete() - rospy.loginfo("logconf deleted") - - - def _send_to_commander_motor(self, cmd1, cmd2, cmd3, cmd4): - pk = CRTPPacket() - pk.port = CRTPPort.COMMANDER_GENERIC - pk.data = struct.pack('<BHHHH', CF_COMMAND_TYPE_MOTORS, cmd1, cmd2, cmd3, cmd4) - self._cf.send_packet(pk) - - def _send_to_commander_rate(self, cmd1, cmd2, cmd3, cmd4, roll_rate, pitch_rate, yaw_rate): - pk = CRTPPacket() - pk.port = CRTPPort.COMMANDER_GENERIC - pk.data = struct.pack('<BHHHHfff', CF_COMMAND_TYPE_RATE, cmd1, cmd2, cmd3, cmd4, roll_rate, pitch_rate, yaw_rate) - self._cf.send_packet(pk) - - def _send_to_commander_angle(self, cmd1, cmd2, cmd3, cmd4, roll, pitch, yaw): - pk = CRTPPacket() - pk.port = CRTPPort.COMMANDER_GENERIC - pk.data = struct.pack('<BHHHHfff', CF_COMMAND_TYPE_ANGLE, cmd1, cmd2, cmd3, cmd4, roll, pitch, yaw) - self._cf.send_packet(pk) - -if __name__ == '__main__': - # global node_name - # node_name = "CrazyRadio" - # rospy.init_node(node_name, anonymous=True) - - # Initialize the low-level drivers (don't list the debug drivers) - cflib.crtp.init_drivers(enable_debug_driver=False) - - #wait until address parameter is set by FlyingAgentClient - # while not rospy.has_param("~crazyflieAddress"): - # time.sleep(0.05) - - #use this following two lines to connect without data from CentralManager - # radio_address = "radio://0/72/2M" - # rospy.loginfo("manual address loaded") - - # global cfbattery_pub - # cfbattery_pub = rospy.Publisher(node_name + '/CFBattery', Float32, queue_size=10) - - global cf_client - - cf_client = CrazyRadioClient() - # rospy.Subscriber("FlyingAgentClient/CrazyRadioCommand", Int32, cf_client.crazyRadioCommandCallback) # allows commands from scripts - - # time.sleep(1.0) - - # rospy.Subscriber("FlyingAgentClient/ControlCommand", ControlCommand, controlCommandCallback) - - # rospy.spin() - # rospy.loginfo("Turning off crazyflie") - - - #wait for client to send its commands - # time.sleep(1.0) - - - # bag.close() - # rospy.loginfo("bag closed") - - # cf_client._cf.close_link() - # rospy.loginfo("Link closed") diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/__init__.py deleted file mode 100644 index 516ffc08..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/__init__.py +++ /dev/null @@ -1,54 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -The Crazyflie Micro Quadcopter library API used to communicate with the -Crazyflie Micro Quadcopter via a communication link. - -The API takes care of scanning, opening and closing the communication link -as well as sending/receiving data from the Crazyflie. - -A link is described using an URI of the following format: - <interface>://<interface defined data>. -See each link for the data that can be included in the URI for that interface. - -The two main uses-cases are scanning for Crazyflies available on a -communication link and opening a communication link to a Crazyflie. - -Example of scanning for available Crazyflies on all communication links: -cflib.crtp.init_drivers() -available = cflib.crtp.scan_interfaces() -for i in available: - print "Found Crazyflie on URI [%s] with comment [%s]" - % (available[0], available[1]) - -Example of connecting to a Crazyflie with know URI (radio dongle 0 and -radio channel 125): -cf = Crazyflie() -cf.open_link("radio://0/125") -... -cf.close_link() -""" diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/__init__.py deleted file mode 100644 index d4cd1a6c..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/__init__.py +++ /dev/null @@ -1,386 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Bootloading utilities for the Crazyflie. -""" -import json -import logging -import sys -import time -import zipfile - -from .boottypes import BootVersion -from .boottypes import TargetTypes -from .cloader import Cloader - -logger = logging.getLogger(__name__) - -__author__ = 'Bitcraze AB' -__all__ = ['Bootloader'] - - -class Bootloader: - """Bootloader utility for the Crazyflie""" - - def __init__(self, clink=None): - """Init the communication class by starting to communicate with the - link given. clink is the link address used after resetting to the - bootloader. - - The device is actually considered in firmware mode. - """ - self.clink = clink - self.in_loader = False - - self.page_size = 0 - self.buffer_pages = 0 - self.flash_pages = 0 - self.start_page = 0 - self.cpuid = 'N/A' - self.error_code = 0 - self.protocol_version = 0 - - # Outgoing callbacks for progress - # int - self.progress_cb = None - # msg - self.error_cb = None - # bool - self.in_bootloader_cb = None - # Target - self.dev_info_cb = None - - # self.dev_info_cb.add_callback(self._dev_info) - # self.in_bootloader_cb.add_callback(self._bootloader_info) - - self._boot_plat = None - - self._cload = Cloader(clink, - info_cb=self.dev_info_cb, - in_boot_cb=self.in_bootloader_cb) - - def start_bootloader(self, warm_boot=False): - if warm_boot: - self._cload.open_bootloader_uri(self.clink) - started = self._cload.reset_to_bootloader(TargetTypes.NRF51) - if started: - started = self._cload.check_link_and_get_info() - else: - uri = self._cload.scan_for_bootloader() - - # Workaround for libusb on Windows (open/close too fast) - time.sleep(1) - - if uri: - self._cload.open_bootloader_uri(uri) - started = self._cload.check_link_and_get_info() - else: - started = False - - if started: - self.protocol_version = self._cload.protocol_version - - if (self.protocol_version == BootVersion.CF1_PROTO_VER_0 or - self.protocol_version == BootVersion.CF1_PROTO_VER_1): - # Nothing more to do - pass - elif self.protocol_version == BootVersion.CF2_PROTO_VER: - self._cload.request_info_update(TargetTypes.NRF51) - else: - print('Bootloader protocol 0x{:X} not ' - 'supported!'.self.protocol_version) - - return started - - def get_target(self, target_id): - return self._cload.request_info_update(target_id) - - def read_cf1_config(self): - """Read a flash page from the specified target""" - target = self._cload.targets[0xFF] - config_page = target.flash_pages - 1 - - return self._cload.read_flash(addr=0xFF, page=config_page) - - def write_cf1_config(self, data): - target = self._cload.targets[0xFF] - config_page = target.flash_pages - 1 - - to_flash = {'target': target, 'data': data, 'type': 'CF1 config', - 'start_page': config_page} - - self._internal_flash(target=to_flash) - - def flash(self, filename, targets): - for target in targets: - if TargetTypes.from_string(target) not in self._cload.targets: - print('Target {} not found by bootloader'.format(target)) - return False - - files_to_flash = () - if zipfile.is_zipfile(filename): - # Read the manifest (don't forget to check so there is one!) - try: - zf = zipfile.ZipFile(filename) - js = zf.read('manifest.json').decode('UTF-8') - j = json.loads(js) - files = j['files'] - platform_id = self._get_platform_id() - files_for_platform = self._filter_platform(files, platform_id) - if len(targets) == 0: - targets = self._extract_targets_from_manifest_files( - files_for_platform) - - zip_targets = self._extract_zip_targets(files_for_platform) - except KeyError as e: - print(e) - print('No manifest.json in {}'.format(filename)) - return - - try: - # Match and create targets - for target in targets: - t = targets[target] - for type in t: - file_to_flash = {} - current_target = '{}-{}'.format(target, type) - file_to_flash['type'] = type - # Read the data, if this fails we bail - file_to_flash['target'] = self._cload.targets[ - TargetTypes.from_string(target)] - file_to_flash['data'] = zf.read( - zip_targets[target][type]['filename']) - file_to_flash['start_page'] = file_to_flash[ - 'target'].start_page - files_to_flash += (file_to_flash,) - except KeyError as e: - print('Could not find a file for {} in {}'.format( - current_target, filename)) - return False - - else: - if len(targets) != 1: - print('Not an archive, must supply one target to flash') - else: - file_to_flash = {} - file_to_flash['type'] = 'binary' - f = open(filename, 'rb') - for t in targets: - file_to_flash['target'] = self._cload.targets[ - TargetTypes.from_string(t)] - file_to_flash['type'] = targets[t][0] - file_to_flash['start_page'] = file_to_flash[ - 'target'].start_page - file_to_flash['data'] = f.read() - f.close() - files_to_flash += (file_to_flash,) - - if not self.progress_cb: - print('') - - file_counter = 0 - for target in files_to_flash: - file_counter += 1 - self._internal_flash(target, file_counter, len(files_to_flash)) - - def _filter_platform(self, files, platform_id): - result = {} - for file in files: - file_info = files[file] - file_platform = file_info['platform'] - if platform_id == file_platform: - result[file] = file_info - return result - - def _extract_zip_targets(self, files): - zip_targets = {} - for file in files: - file_name = file - file_info = files[file] - file_target = file_info['target'] - file_type = file_info['type'] - if file_target not in zip_targets: - zip_targets[file_target] = {} - zip_targets[file_target][file_type] = { - 'filename': file_name} - return zip_targets - - def _extract_targets_from_manifest_files(self, files): - targets = {} - for file in files: - file_info = files[file] - file_target = file_info['target'] - file_type = file_info['type'] - if file_target in targets: - targets[file_target] += (file_type,) - else: - targets[file_target] = (file_type,) - - return targets - - def reset_to_firmware(self): - if self._cload.protocol_version == BootVersion.CF2_PROTO_VER: - self._cload.reset_to_firmware(TargetTypes.NRF51) - else: - self._cload.reset_to_firmware(TargetTypes.STM32) - - def close(self): - if self._cload: - self._cload.close() - - def _internal_flash(self, target, current_file_number=1, total_files=1): - - image = target['data'] - t_data = target['target'] - - start_page = target['start_page'] - - # If used from a UI we need some extra things for reporting progress - factor = (100.0 * t_data.page_size) / len(image) - progress = 0 - - if self.progress_cb: - self.progress_cb( - '({}/{}) Starting...'.format(current_file_number, total_files), - int(progress)) - else: - sys.stdout.write( - 'Flashing {} of {} to {} ({}): '.format( - current_file_number, total_files, - TargetTypes.to_string(t_data.id), target['type'])) - sys.stdout.flush() - - if len(image) > ((t_data.flash_pages - start_page) * - t_data.page_size): - if self.progress_cb: - self.progress_cb( - 'Error: Not enough space to flash the image file.', - int(progress)) - else: - print('Error: Not enough space to flash the image file.') - raise Exception() - - if not self.progress_cb: - logger.info(('%d bytes (%d pages) ' % ( - (len(image) - 1), int(len(image) / t_data.page_size) + 1))) - sys.stdout.write(('%d bytes (%d pages) ' % ( - (len(image) - 1), int(len(image) / t_data.page_size) + 1))) - sys.stdout.flush() - - # For each page - ctr = 0 # Buffer counter - for i in range(0, int((len(image) - 1) / t_data.page_size) + 1): - # Load the buffer - if ((i + 1) * t_data.page_size) > len(image): - self._cload.upload_buffer( - t_data.addr, ctr, 0, image[i * t_data.page_size:]) - else: - self._cload.upload_buffer( - t_data.addr, ctr, 0, - image[i * t_data.page_size: (i + 1) * t_data.page_size]) - - ctr += 1 - - if self.progress_cb: - progress += factor - self.progress_cb('({}/{}) Uploading buffer to {}...'.format( - current_file_number, - total_files, - TargetTypes.to_string(t_data.id)), - - int(progress)) - else: - sys.stdout.write('.') - sys.stdout.flush() - - # Flash when the complete buffers are full - if ctr >= t_data.buffer_pages: - if self.progress_cb: - self.progress_cb('({}/{}) Writing buffer to {}...'.format( - current_file_number, - total_files, - TargetTypes.to_string(t_data.id)), - - int(progress)) - else: - sys.stdout.write('%d' % ctr) - sys.stdout.flush() - if not self._cload.write_flash(t_data.addr, 0, - start_page + i - (ctr - 1), - ctr): - if self.progress_cb: - self.progress_cb( - 'Error during flash operation (code %d)'.format( - self._cload.error_code), - int(progress)) - else: - print('\nError during flash operation (code %d). ' - 'Maybe wrong radio link?' % - self._cload.error_code) - raise Exception() - - ctr = 0 - - if ctr > 0: - if self.progress_cb: - self.progress_cb('({}/{}) Writing buffer to {}...'.format( - current_file_number, - total_files, - TargetTypes.to_string(t_data.id)), - int(progress)) - else: - sys.stdout.write('%d' % ctr) - sys.stdout.flush() - if not self._cload.write_flash( - t_data.addr, 0, - (start_page + (int((len(image) - 1) / t_data.page_size)) - - (ctr - 1)), ctr): - if self.progress_cb: - self.progress_cb( - 'Error during flash operation (code %d)'.format( - self._cload.error_code), - int(progress)) - else: - print('\nError during flash operation (code %d). Maybe' - ' wrong radio link?' % self._cload.error_code) - raise Exception() - - if self.progress_cb: - self.progress_cb( - '({}/{}) Flashing done!'.format(current_file_number, - total_files), - int(100)) - else: - print('') - - def _get_platform_id(self): - """Get platform identifier used in the zip manifest for curr copter""" - identifier = 'cf1' - if (BootVersion.is_cf2(self.protocol_version)): - identifier = 'cf2' - - return identifier diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/boottypes.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/boottypes.py deleted file mode 100644 index 8a73f254..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/boottypes.py +++ /dev/null @@ -1,96 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Bootloading utilities for the Crazyflie. -""" - -__author__ = 'Bitcraze AB' -__all__ = ['BootVersion', 'TargetTypes', 'Target'] - - -class BootVersion: - CF1_PROTO_VER_0 = 0x00 - CF1_PROTO_VER_1 = 0x01 - CF2_PROTO_VER = 0x10 - - @staticmethod - def to_ver_string(ver): - if (ver == BootVersion.CF1_PROTO_VER_0 or ver == BootVersion. - CF1_PROTO_VER_1): - return 'Crazyflie Nano Quadcopter (1.0)' - if ver == BootVersion.CF2_PROTO_VER: - return 'Crazyflie 2.0' - return 'Unknown' - - @staticmethod - def is_cf2(ver): - return ver == BootVersion.CF2_PROTO_VER - - -class TargetTypes: - STM32 = 0xFF - NRF51 = 0xFE - - @staticmethod - def to_string(target): - if target == TargetTypes.STM32: - return 'stm32' - if target == TargetTypes.NRF51: - return 'nrf51' - return 'Unknown' - - @staticmethod - def from_string(name): - if name == 'stm32': - return TargetTypes.STM32 - if name == 'nrf51': - return TargetTypes.NRF51 - return 0 - - -class Target: - - def __init__(self, id): - self.id = id - self.protocol_version = 0xFF - self.page_size = 0 - self.buffer_pages = 0 - self.flash_pages = 0 - self.start_page = 0 - self.cpuid = '' - self.data = None - - def __str__(self): - ret = '' - ret += 'Target info: {} (0x{:X})\n'.format( - TargetTypes.to_string(self.id), self.id) - ret += 'Flash pages: %d | Page size: %d | Buffer pages: %d |' \ - ' Start page: %d\n' % (self.flash_pages, self.page_size, - self.buffer_pages, self.start_page) - ret += '%d KBytes of flash available for firmware image.' % ( - (self.flash_pages - self.start_page) * self.page_size / 1024) - return ret diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/cloader.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/cloader.py deleted file mode 100644 index 716a344b..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/cloader.py +++ /dev/null @@ -1,389 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Crazyflie radio bootloader for flashing firmware. -""" -import binascii -import logging -import math -import struct -import time - -import cflib.crtp -from .boottypes import Target -from .boottypes import TargetTypes -from cflib.crtp.crtpstack import CRTPPacket -from cflib.crtp.crtpstack import CRTPPort - -__author__ = 'Bitcraze AB' -__all__ = ['Cloader'] - -logger = logging.getLogger(__name__) - - -class Cloader: - """Bootloader utility for the Crazyflie""" - - def __init__(self, link, info_cb=None, in_boot_cb=None): - """Init the communication class by starting to communicate with the - link given. clink is the link address used after resetting to the - bootloader. - - The device is actually considered in firmware mode. - """ - self.link = None - self.uri = link - self.in_loader = False - - self.page_size = 0 - self.buffer_pages = 0 - self.flash_pages = 0 - self.start_page = 0 - self.cpuid = 'N/A' - self.error_code = 0 - self.protocol_version = 0xFF - - self._info_cb = info_cb - self._in_boot_cb = in_boot_cb - - self.targets = {} - self.mapping = None - self._available_boot_uri = ('radio://0/110/2M', 'radio://0/0/2M') - - def close(self): - """ Close the link """ - if self.link: - self.link.close() - - def scan_for_bootloader(self): - link = cflib.crtp.get_link_driver('radio://0') - ts = time.time() - res = () - while len(res) == 0 and (time.time() - ts) < 10: - res = link.scan_selected(self._available_boot_uri) - - link.close() - - if len(res) > 0: - return res[0] - return None - - def reset_to_bootloader(self, target_id): - retry_counter = 5 - pk = CRTPPacket() - pk.set_header(0xFF, 0xFF) - pk.data = (target_id, 0xFF) - self.link.send_packet(pk) - - pk = self.link.receive_packet(1) - - while ((not pk or pk.header != 0xFF or - struct.unpack('<BB', pk.data[0:2]) != (target_id, 0xFF) - ) and retry_counter >= 0): - pk = self.link.receive_packet(1) - retry_counter -= 1 - - if pk: - new_address = (0xb1,) + struct.unpack('<BBBB', pk.data[2:6][::-1]) - - pk = CRTPPacket() - pk.set_header(0xFF, 0xFF) - pk.data = (target_id, 0xF0, 0x00) - self.link.send_packet(pk) - - addr = int(binascii.hexlify( - struct.pack('B' * 5, *new_address)), 16) - - time.sleep(0.2) - self.link.close() - time.sleep(0.2) - self.link = cflib.crtp.get_link_driver( - 'radio://0/0/2M/{:X}'.format(addr)) - - return True - else: - return False - - def reset_to_bootloader1(self, cpu_id): - """ Reset to the bootloader - The parameter cpuid shall correspond to the device to reset. - - Return true if the reset has been done and the contact with the - bootloader is established. - """ - # Send an echo request and wait for the answer - # Mainly aim to bypass a bug of the crazyflie firmware that prevents - # reset before normal CRTP communication - pk = CRTPPacket() - pk.port = CRTPPort.LINKCTRL - pk.data = (1, 2, 3) + cpu_id - self.link.send_packet(pk) - - pk = None - while True: - pk = self.link.receive_packet(2) - if not pk: - return False - - if pk.port == CRTPPort.LINKCTRL: - break - - # Send the reset to bootloader request - pk = CRTPPacket() - pk.set_header(0xFF, 0xFF) - pk.data = (0xFF, 0xFE) + cpu_id - self.link.send_packet(pk) - - # Wait to ack the reset ... - pk = None - while True: - pk = self.link.receive_packet(2) - if not pk: - return False - - if pk.port == 0xFF and tuple(pk.data) == (0xFF, 0xFE) + cpu_id: - pk.data = (0xFF, 0xF0) + cpu_id - self.link.send_packet(pk) - break - - time.sleep(0.1) - self.link.close() - self.link = cflib.crtp.get_link_driver(self.clink_address) - # time.sleep(0.1) - - return self._update_info() - - def reset_to_firmware(self, target_id): - """ Reset to firmware - The parameter cpuid shall correspond to the device to reset. - - Return true if the reset has been done - """ - # The fake CPU ID is legacy from the Crazyflie 1.0 - # In order to reset the CPU id had to be sent, but this - # was removed before launching it. But the length check is - # still in the bootloader. So to work around this bug so - # some extra data needs to be sent. - fake_cpu_id = (1, 2, 4, 5, 6, 7, 8, 9, 10, 11, 12) - # Send the reset to bootloader request - pk = CRTPPacket() - pk.set_header(0xFF, 0xFF) - pk.data = (target_id, 0xFF) + fake_cpu_id - self.link.send_packet(pk) - - # Wait to ack the reset ... - pk = None - while True: - pk = self.link.receive_packet(2) - if not pk: - return False - - if (pk.header == 0xFF and struct.unpack( - 'B' * len(pk.data), pk.data)[:2] == (target_id, 0xFF)): - # Difference in CF1 and CF2 (CPU ID) - if target_id == 0xFE: - pk.data = (target_id, 0xF0, 0x01) - else: - pk.data = (target_id, 0xF0) + fake_cpu_id - self.link.send_packet(pk) - break - - time.sleep(0.1) - - def open_bootloader_uri(self, uri=None): - if self.link: - self.link.close() - if uri: - self.link = cflib.crtp.get_link_driver(uri) - else: - self.link = cflib.crtp.get_link_driver(self.clink_address) - - def check_link_and_get_info(self, target_id=0xFF): - """Try to get a connection with the bootloader by requesting info - 5 times. This let roughly 10 seconds to boot the copter ...""" - for _ in range(0, 5): - if self._update_info(target_id): - if self._in_boot_cb: - self._in_boot_cb.call(True, self.targets[ - target_id].protocol_version) - if self._info_cb: - self._info_cb.call(self.targets[target_id]) - return True - return False - - def request_info_update(self, target_id): - if target_id not in self.targets: - self._update_info(target_id) - if self._info_cb: - self._info_cb.call(self.targets[target_id]) - return self.targets[target_id] - - def _update_info(self, target_id): - """ Call the command getInfo and fill up the information received in - the fields of the object - """ - - # Call getInfo ... - pk = CRTPPacket() - pk.set_header(0xFF, 0xFF) - pk.data = (target_id, 0x10) - self.link.send_packet(pk) - - # Wait for the answer - pk = self.link.receive_packet(2) - - if (pk and pk.header == 0xFF and struct.unpack('<BB', pk.data[0:2]) == - (target_id, 0x10)): - tab = struct.unpack('BBHHHH', pk.data[0:10]) - cpuid = struct.unpack('B' * 12, pk.data[10:22]) - if target_id not in self.targets: - self.targets[target_id] = Target(target_id) - self.targets[target_id].addr = target_id - if len(pk.data) > 22: - self.targets[target_id].protocol_version = pk.datat[22] - self.protocol_version = pk.datat[22] - self.targets[target_id].page_size = tab[2] - self.targets[target_id].buffer_pages = tab[3] - self.targets[target_id].flash_pages = tab[4] - self.targets[target_id].start_page = tab[5] - self.targets[target_id].cpuid = '%02X' % cpuid[0] - for i in cpuid[1:]: - self.targets[target_id].cpuid += ':%02X' % i - - if (self.protocol_version == 0x10 and - target_id == TargetTypes.STM32): - self._update_mapping(target_id) - - return True - - return False - - def _update_mapping(self, target_id): - pk = CRTPPacket() - pk.set_header(0xff, 0xff) - pk.data = (target_id, 0x12) - self.link.send_packet(pk) - - pk = self.link.receive_packet(2) - - if (pk and pk.header == 0xFF and struct.unpack('<BB', pk.data[0:2]) == - (target_id, 0x12)): - m = pk.datat[2:] - - if (len(m) % 2) != 0: - raise Exception('Malformed flash mapping packet') - - self.mapping = [] - page = 0 - for i in range(int(len(m) / 2)): - for j in range(m[2 * i]): - self.mapping.append(page) - page += m[(2 * i) + 1] - - def upload_buffer(self, target_id, page, address, buff): - """Upload data into a buffer on the Crazyflie""" - # print len(buff) - count = 0 - pk = CRTPPacket() - pk.set_header(0xFF, 0xFF) - pk.data = struct.pack('=BBHH', target_id, 0x14, page, address) - - for i in range(0, len(buff)): - pk.data.append(buff[i]) - - count += 1 - - if count > 24: - self.link.send_packet(pk) - count = 0 - pk = CRTPPacket() - pk.set_header(0xFF, 0xFF) - pk.data = struct.pack('=BBHH', target_id, 0x14, page, - i + address + 1) - - self.link.send_packet(pk) - - def read_flash(self, addr=0xFF, page=0x00): - """Read back a flash page from the Crazyflie and return it""" - buff = bytearray() - - page_size = self.targets[addr].page_size - - for i in range(0, int(math.ceil(page_size / 25.0))): - pk = None - retry_counter = 5 - while ((not pk or pk.header != 0xFF or - struct.unpack('<BB', pk.data[0:2]) != (addr, 0x1C)) and - retry_counter >= 0): - pk = CRTPPacket() - pk.set_header(0xFF, 0xFF) - pk.data = struct.pack('<BBHH', addr, 0x1C, page, (i * 25)) - self.link.send_packet(pk) - - pk = self.link.receive_packet(1) - retry_counter -= 1 - if (retry_counter < 0): - return None - else: - buff += pk.data[6:] - - # For some reason we get one byte extra here... - return buff[0:page_size] - - def write_flash(self, addr, page_buffer, target_page, page_count): - """Initiate flashing of data in the buffer to flash.""" - # print "Write page", flashPage - # print "Writing page [%d] and [%d] forward" % (flashPage, nPage) - pk = None - retry_counter = 5 - # print "Flasing to 0x{:X}".format(addr) - while ((not pk or pk.header != 0xFF or - struct.unpack('<BB', pk.data[0:2]) != (addr, 0x18)) and - retry_counter >= 0): - pk = CRTPPacket() - pk.set_header(0xFF, 0xFF) - pk.data = struct.pack('<BBHHH', addr, 0x18, page_buffer, - target_page, page_count) - self.link.send_packet(pk) - pk = self.link.receive_packet(1) - retry_counter -= 1 - - if retry_counter < 0: - self.error_code = -1 - return False - - self.error_code = pk.data[3] - - return pk.data[2] == 1 - - def decode_cpu_id(self, cpuid): - """Decode the CPU id into a string""" - ret = () - for i in cpuid.split(':'): - ret += (eval('0x' + i),) - - return ret diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/__init__.py deleted file mode 100644 index 1623825b..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/__init__.py +++ /dev/null @@ -1,400 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -The Crazyflie module is used to easily connect/send/receive data -from a Crazyflie. - -Each function in the Crazyflie has a class in the module that can be used -to access that functionality. The same design is then used in the Crazyflie -firmware which makes the mapping 1:1 in most cases. -""" -import datetime -import logging -import time -from collections import namedtuple -from threading import Lock -from threading import Thread -from threading import Timer - -import cflib.crtp -from .commander import Commander -from .console import Console -from .extpos import Extpos -from .localization import Localization -from .log import Log -from .mem import Memory -from .param import Param -from .platformservice import PlatformService -from .toccache import TocCache -from cflib.utils.callbacks import Caller - -__author__ = 'Bitcraze AB' -__all__ = ['Crazyflie'] - -logger = logging.getLogger(__name__) - - -class State: - """Stat of the connection procedure""" - DISCONNECTED = 0 - INITIALIZED = 1 - CONNECTED = 2 - SETUP_FINISHED = 3 - - -class Crazyflie(): - """The Crazyflie class""" - - def __init__(self, link=None, ro_cache=None, rw_cache=None): - """ - Create the objects from this module and register callbacks. - - ro_cache -- Path to read-only cache (string) - rw_cache -- Path to read-write cache (string) - """ - - # Called on disconnect, no matter the reason - self.disconnected = Caller() - # Called on unintentional disconnect only - self.connection_lost = Caller() - # Called when the first packet in a new link is received - self.link_established = Caller() - # Called when the user requests a connection - self.connection_requested = Caller() - # Called when the link is established and the TOCs (that are not - # cached) have been downloaded - self.connected = Caller() - # Called if establishing of the link fails (i.e times out) - self.connection_failed = Caller() - # Called for every packet received - self.packet_received = Caller() - # Called for every packet sent - self.packet_sent = Caller() - # Called when the link driver updates the link quality measurement - self.link_quality_updated = Caller() - - self.state = State.DISCONNECTED - - self.link = link - self._toc_cache = TocCache(ro_cache=ro_cache, - rw_cache=rw_cache) - - self.incoming = _IncomingPacketHandler(self) - self.incoming.setDaemon(True) - self.incoming.start() - - self.commander = Commander(self) - self.loc = Localization(self) - self.extpos = Extpos(self) - self.log = Log(self) - self.console = Console(self) - self.param = Param(self) - self.mem = Memory(self) - self.platform = PlatformService(self) - - self.link_uri = '' - - # Used for retry when no reply was sent back - self.packet_received.add_callback(self._check_for_initial_packet_cb) - self.packet_received.add_callback(self._check_for_answers) - - self._answer_patterns = {} - - self._send_lock = Lock() - - self.connected_ts = None - - # Connect callbacks to logger - self.disconnected.add_callback( - lambda uri: logger.info('Callback->Disconnected from [%s]', uri)) - self.disconnected.add_callback(self._disconnected) - self.link_established.add_callback( - lambda uri: logger.info('Callback->Connected to [%s]', uri)) - self.connection_lost.add_callback( - lambda uri, errmsg: logger.info( - 'Callback->Connection lost to [%s]: %s', uri, errmsg)) - self.connection_failed.add_callback( - lambda uri, errmsg: logger.info( - 'Callback->Connected failed to [%s]: %s', uri, errmsg)) - self.connection_requested.add_callback( - lambda uri: logger.info( - 'Callback->Connection initialized[%s]', uri)) - self.connected.add_callback( - lambda uri: logger.info( - 'Callback->Connection setup finished [%s]', uri)) - - def _disconnected(self, link_uri): - """ Callback when disconnected.""" - self.connected_ts = None - - def _start_connection_setup(self): - """Start the connection setup by refreshing the TOCs""" - logger.info('We are connected[%s], request connection setup', - self.link_uri) - self.log.refresh_toc(self._log_toc_updated_cb, self._toc_cache) - - def _param_toc_updated_cb(self): - """Called when the param TOC has been fully updated""" - logger.info('Param TOC finished updating') - self.connected_ts = datetime.datetime.now() - self.connected.call(self.link_uri) - # Trigger the update for all the parameters - self.param.request_update_of_all_params() - - def _mems_updated_cb(self): - """Called when the memories have been identified""" - logger.info('Memories finished updating') - self.param.refresh_toc(self._param_toc_updated_cb, self._toc_cache) - - def _log_toc_updated_cb(self): - """Called when the log TOC has been fully updated""" - logger.info('Log TOC finished updating') - self.mem.refresh(self._mems_updated_cb) - - def _link_error_cb(self, errmsg): - """Called from the link driver when there's an error""" - logger.warning('Got link error callback [%s] in state [%s]', - errmsg, self.state) - if (self.link is not None): - self.link.close() - self.link = None - if (self.state == State.INITIALIZED): - self.connection_failed.call(self.link_uri, errmsg) - if (self.state == State.CONNECTED or - self.state == State.SETUP_FINISHED): - self.disconnected.call(self.link_uri) - self.connection_lost.call(self.link_uri, errmsg) - self.state = State.DISCONNECTED - - def _link_quality_cb(self, percentage): - """Called from link driver to report link quality""" - self.link_quality_updated.call(percentage) - - def _check_for_initial_packet_cb(self, data): - """ - Called when first packet arrives from Crazyflie. - - This is used to determine if we are connected to something that is - answering. - """ - self.state = State.CONNECTED - self.link_established.call(self.link_uri) - self.packet_received.remove_callback(self._check_for_initial_packet_cb) - - def open_link(self, link_uri): - """ - Open the communication link to a copter at the given URI and setup the - connection (download log/parameter TOC). - """ - self.connection_requested.call(link_uri) - self.state = State.INITIALIZED - self.link_uri = link_uri - try: - self.link = cflib.crtp.get_link_driver( - link_uri, self._link_quality_cb, self._link_error_cb) - - if not self.link: - message = 'No driver found or malformed URI: {}' \ - .format(link_uri) - logger.warning(message) - self.connection_failed.call(link_uri, message) - else: - # Add a callback so we can check that any data is coming - # back from the copter - self.packet_received.add_callback( - self._check_for_initial_packet_cb) - - self._start_connection_setup() - except Exception as ex: # pylint: disable=W0703 - # We want to catch every possible exception here and show - # it in the user interface - import traceback - - logger.error("Couldn't load link driver: %s\n\n%s", - ex, traceback.format_exc()) - exception_text = "Couldn't load link driver: %s\n\n%s" % ( - ex, traceback.format_exc()) - if self.link: - self.link.close() - self.link = None - self.connection_failed.call(link_uri, exception_text) - - def close_link(self): - """Close the communication link.""" - logger.info('Closing link') - if (self.link is not None): - self.commander.send_setpoint(0, 0, 0, 0) - if (self.link is not None): - self.link.close() - self.link = None - self._answer_patterns = {} - self.disconnected.call(self.link_uri) - - def add_port_callback(self, port, cb): - """Add a callback to cb on port""" - self.incoming.add_port_callback(port, cb) - - def remove_port_callback(self, port, cb): - """Remove the callback cb on port""" - self.incoming.remove_port_callback(port, cb) - - def _no_answer_do_retry(self, pk, pattern): - """Resend packets that we have not gotten answers to""" - logger.info('Resending for pattern %s', pattern) - # Set the timer to None before trying to send again - self.send_packet(pk, expected_reply=pattern, resend=True) - - def _check_for_answers(self, pk): - """ - Callback called for every packet received to check if we are - waiting for an answer on this port. If so, then cancel the retry - timer. - """ - longest_match = () - if len(self._answer_patterns) > 0: - data = (pk.header,) + tuple(pk.data) - for p in list(self._answer_patterns.keys()): - logger.debug('Looking for pattern match on %s vs %s', p, data) - if len(p) <= len(data): - if p == data[0:len(p)]: - match = data[0:len(p)] - if len(match) >= len(longest_match): - logger.debug('Found new longest match %s', match) - longest_match = match - if len(longest_match) > 0: - self._answer_patterns[longest_match].cancel() - del self._answer_patterns[longest_match] - - def send_packet(self, pk, expected_reply=(), resend=False, timeout=0.2): - """ - Send a packet through the link interface. - - pk -- Packet to send - expect_answer -- True if a packet from the Crazyflie is expected to - be sent back, otherwise false - - """ - self._send_lock.acquire() - if self.link is not None: - if len(expected_reply) > 0 and not resend and \ - self.link.needs_resending: - pattern = (pk.header,) + expected_reply - logger.debug( - 'Sending packet and expecting the %s pattern back', - pattern) - new_timer = Timer(timeout, - lambda: self._no_answer_do_retry(pk, - pattern)) - self._answer_patterns[pattern] = new_timer - new_timer.start() - elif resend: - # Check if we have gotten an answer, if not try again - pattern = expected_reply - if pattern in self._answer_patterns: - logger.debug('We want to resend and the pattern is there') - if self._answer_patterns[pattern]: - new_timer = Timer(timeout, - lambda: - self._no_answer_do_retry( - pk, pattern)) - self._answer_patterns[pattern] = new_timer - new_timer.start() - else: - logger.debug('Resend requested, but no pattern found: %s', - self._answer_patterns) - self.link.send_packet(pk) - self.packet_sent.call(pk) - self._send_lock.release() - - -_CallbackContainer = namedtuple('CallbackConstainer', - 'port port_mask channel channel_mask callback') - - -class _IncomingPacketHandler(Thread): - """Handles incoming packets and sends the data to the correct receivers""" - - def __init__(self, cf): - Thread.__init__(self) - self.cf = cf - self.cb = [] - - def add_port_callback(self, port, cb): - """Add a callback for data that comes on a specific port""" - logger.debug('Adding callback on port [%d] to [%s]', port, cb) - self.add_header_callback(cb, port, 0, 0xff, 0x0) - - def remove_port_callback(self, port, cb): - """Remove a callback for data that comes on a specific port""" - logger.debug('Removing callback on port [%d] to [%s]', port, cb) - for port_callback in self.cb: - if port_callback.port == port and port_callback.callback == cb: - self.cb.remove(port_callback) - - def add_header_callback(self, cb, port, channel, port_mask=0xFF, - channel_mask=0xFF): - """ - Add a callback for a specific port/header callback with the - possibility to add a mask for channel and port for multiple - hits for same callback. - """ - self.cb.append(_CallbackContainer(port, port_mask, - channel, channel_mask, cb)) - - def run(self): - while True: - if self.cf.link is None: - time.sleep(1) - continue - pk = self.cf.link.receive_packet(1) - - if pk is None: - continue - - # All-packet callbacks - self.cf.packet_received.call(pk) - - found = False - for cb in (cb for cb in self.cb - if cb.port == (pk.port & cb.port_mask) and - cb.channel == (pk.channel & cb.channel_mask)): - try: - cb.callback(pk) - except Exception: # pylint: disable=W0703 - # Disregard pylint warning since we want to catch all - # exceptions and we can't know what will happen in - # the callbacks. - import traceback - - logger.error('Exception while doing callback on port' - ' [%d]\n\n%s', pk.port, - traceback.format_exc()) - if cb.port != 0xFF: - found = True - - if not found: - pass diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/commander.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/commander.py deleted file mode 100644 index 75238955..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/commander.py +++ /dev/null @@ -1,129 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Used for sending control setpoints to the Crazyflie -""" -import struct - -from cflib.crtp.crtpstack import CRTPPacket -from cflib.crtp.crtpstack import CRTPPort - -__author__ = 'Bitcraze AB' -__all__ = ['Commander'] - -TYPE_STOP = 0 -TYPE_VELOCITY_WORLD = 1 -TYPE_ZDISTANCE = 2 -TYPE_HOVER = 5 - - -class Commander(): - """ - Used for sending control setpoints to the Crazyflie - """ - - def __init__(self, crazyflie=None): - """ - Initialize the commander object. By default the commander is in - +-mode (not x-mode). - """ - self._cf = crazyflie - self._x_mode = False - - def set_client_xmode(self, enabled): - """ - Enable/disable the client side X-mode. When enabled this recalculates - the setpoints before sending them to the Crazyflie. - """ - self._x_mode = enabled - - def send_setpoint(self, roll, pitch, yaw, thrust): - """ - Send a new control setpoint for roll/pitch/yaw/thrust to the copter - - The arguments roll/pitch/yaw/trust is the new setpoints that should - be sent to the copter - """ - if thrust > 0xFFFF or thrust < 0: - raise ValueError('Thrust must be between 0 and 0xFFFF') - - if self._x_mode: - roll, pitch = 0.707 * (roll - pitch), 0.707 * (roll + pitch) - - pk = CRTPPacket() - pk.port = CRTPPort.COMMANDER - pk.data = struct.pack('<fffH', roll, -pitch, yaw, thrust) - self._cf.send_packet(pk) - - def send_stop_setpoint(self): - """ - Send STOP setpoing, stopping the motors and (potentially) falling. - """ - pk = CRTPPacket() - pk.port = CRTPPort.COMMANDER_GENERIC - pk.data = struct.pack('<B', TYPE_STOP) - self._cf.send_packet(pk) - - def send_velocity_world_setpoint(self, vx, vy, vz, yawrate): - """ - Send Velocity in the world frame of reference setpoint. - - vx, vy, vz are in m/s - yawrate is in degrees/s - """ - pk = CRTPPacket() - pk.port = CRTPPort.COMMANDER_GENERIC - pk.data = struct.pack('<Bffff', TYPE_VELOCITY_WORLD, - vx, vy, vz, yawrate) - self._cf.send_packet(pk) - - def send_zdistance_setpoint(self, roll, pitch, yawrate, zdistance): - """ - Control mode where the height is send as an absolute setpoint (intended - to be the distance to the surface under the Crazflie). - - Roll, pitch, yawrate are defined as degrees, degrees, degrees/s - """ - pk = CRTPPacket() - pk.port = CRTPPort.COMMANDER_GENERIC - pk.data = struct.pack('<Bffff', TYPE_ZDISTANCE, - roll, pitch, yawrate, zdistance) - self._cf.send_packet(pk) - - def send_hover_setpoint(self, vx, vy, yawrate, zdistance): - """ - Control mode where the height is send as an absolute setpoint (intended - to be the distance to the surface under the Crazflie). - - vx and vy are in m/s - yawrate is in degrees/s - """ - pk = CRTPPacket() - pk.port = CRTPPort.COMMANDER_GENERIC - pk.data = struct.pack('<Bffff', TYPE_HOVER, - vx, vy, yawrate, zdistance) - self._cf.send_packet(pk) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/console.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/console.py deleted file mode 100644 index 696b9ae8..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/console.py +++ /dev/null @@ -1,61 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Crazyflie console is used to receive characters printed using printf -from the firmware. -""" -from cflib.crtp.crtpstack import CRTPPort -from cflib.utils.callbacks import Caller - -__author__ = 'Bitcraze AB' -__all__ = ['Console'] - - -class Console: - """ - Crazyflie console is used to receive characters printed using printf - from the firmware. - """ - - def __init__(self, crazyflie): - """ - Initialize the console and register it to receive data from the copter. - """ - - self.receivedChar = Caller() - - self.cf = crazyflie - self.cf.add_port_callback(CRTPPort.CONSOLE, self.incoming) - - def incoming(self, packet): - """ - Callback for data received from the copter. - """ - # This might be done prettier ;-) - console_text = packet.data.decode('UTF-8') - - self.receivedChar.call(console_text) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/extpos.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/extpos.py deleted file mode 100644 index 53486dff..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/extpos.py +++ /dev/null @@ -1,52 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Used for sending external position to the Crazyflie -""" - -__author__ = 'Bitcraze AB' -__all__ = ['Extpos'] - - -class Extpos(): - """ - Used for sending its position to the Crazyflie - """ - - def __init__(self, crazyflie=None): - """ - Initialize the Extpos object. - """ - self._cf = crazyflie - - def send_extpos(self, x, y, z): - """ - Send the current Crazyflie X, Y, Z position. This is going to be - forwarded to the Crazyflie's position estimator. - """ - - self._cf.loc.send_extpos([x, y, z]) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/localization.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/localization.py deleted file mode 100644 index 7b3bd053..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/localization.py +++ /dev/null @@ -1,122 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2017 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Subsytem handling localization-related data communication -""" -import collections -import logging -import struct - -from cflib.crtp.crtpstack import CRTPPacket -from cflib.crtp.crtpstack import CRTPPort -from cflib.utils.callbacks import Caller - -__author__ = 'Bitcraze AB' -__all__ = ['Localization', 'LocalizationPacket'] - -logger = logging.getLogger(__name__) - -# A generic location packet contains type and data. When received the data -# may be decoded by the lib. -LocalizationPacket = collections.namedtuple('localizationPacket', - ['type', 'raw_data', 'data']) - - -class Localization(): - """ - Handle localization-related data communication with the Crazyflie - """ - - # Implemented channels - POSITION_CH = 0 - GENERIC_CH = 1 - - # Location message types for generig channel - RANGE_STREAM_REPORT = 0x00 - RANGE_STREAM_REPORT_FP16 = 0x01 - LPS_SHORT_LPP_PACKET = 0x02 - - def __init__(self, crazyflie=None): - """ - Initialize the Extpos object. - """ - self._cf = crazyflie - - self.receivedLocationPacket = Caller() - self._cf.add_port_callback(CRTPPort.LOCALIZATION, self._incoming) - - def _incoming(self, packet): - """ - Callback for data received from the copter. - """ - if len(packet.data) < 1: - logger.warning('Localization packet received with incorrect' + - 'length (length is {})'.format(len(packet.data))) - return - - pk_type = struct.unpack('<B', packet.data[:1])[0] - data = packet.data[1:] - - # Decoding the known packet types - # TODO: more generic decoding scheme? - decoded_data = None - if pk_type == self.RANGE_STREAM_REPORT: - if len(data) % 5 != 0: - logger.error('Wrong range stream report data lenght') - return - decoded_data = {} - raw_data = data - for i in range(int(len(data) / 5)): - anchor_id, distance = struct.unpack('<Bf', raw_data[:5]) - decoded_data[anchor_id] = distance - raw_data = raw_data[5:] - - pk = LocalizationPacket(pk_type, data, decoded_data) - self.receivedLocationPacket.call(pk) - - def send_extpos(self, pos): - """ - Send the current Crazyflie X, Y, Z position. This is going to be - forwarded to the Crazyflie's position estimator. - """ - - pk = CRTPPacket() - pk.port = CRTPPort.LOCALIZATION - pk.channel = self.POSITION_CH - pk.data = struct.pack('<fff', pos[0], pos[1], pos[2]) - self._cf.send_packet(pk) - - def send_short_lpp_packet(self, dest_id, data): - """ - Send ultra-wide-band LPP packet to dest_id - """ - - pk = CRTPPacket() - pk.port = CRTPPort.LOCALIZATION - pk.channel = self.GENERIC_CH - pk.data = struct.pack('<BB', self.LPS_SHORT_LPP_PACKET, dest_id) + data - self._cf.send_packet(pk) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/log.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/log.py deleted file mode 100644 index 9cf32443..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/log.py +++ /dev/null @@ -1,558 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Enables logging of variables from the Crazyflie. - -When a Crazyflie is connected it's possible to download a TableOfContent of all -the variables that can be logged. Using this it's possible to add logging -configurations where selected variables are sent to the client at a -specified period. - -Terminology: - Log configuration - A configuration with a period and a number of variables - that are present in the TOC. - Stored as - The size and type of the variable as declared in the - Crazyflie firmware - Fetch as - The size and type that a variable should be fetched as. - This does not have to be the same as the size and type - it's stored as. - -States of a configuration: - Created on host - When a configuration is created the contents is checked - so that all the variables are present in the TOC. If not - then the configuration cannot be created. - Created on CF - When the configuration is deemed valid it is added to the - Crazyflie. At this time the memory constraint is checked - and the status returned. - Started on CF - Any added block that is not started can be started. Once - started the Crazyflie will send back logdata periodically - according to the specified period when it's created. - Stopped on CF - Any started configuration can be stopped. The memory taken - by the configuration on the Crazyflie is NOT freed, the - only effect is that the Crazyflie will stop sending - logdata back to the host. - Deleted on CF - Any block that is added can be deleted. When this is done - the memory taken by the configuration is freed on the - Crazyflie. The configuration will have to be re-added to - be used again. -""" -import errno -import logging -import struct - -from .toc import Toc -from .toc import TocFetcher -from cflib.crtp.crtpstack import CRTPPacket -from cflib.crtp.crtpstack import CRTPPort -from cflib.utils.callbacks import Caller - -__author__ = 'Bitcraze AB' -__all__ = ['Log', 'LogTocElement'] - -# Channels used for the logging port -CHAN_TOC = 0 -CHAN_SETTINGS = 1 -CHAN_LOGDATA = 2 - -# Commands used when accessing the Table of Contents -CMD_TOC_ELEMENT = 0 -CMD_TOC_INFO = 1 - -# Commands used when accessing the Log configurations -CMD_CREATE_BLOCK = 0 -CMD_APPEND_BLOCK = 1 -CMD_DELETE_BLOCK = 2 -CMD_START_LOGGING = 3 -CMD_STOP_LOGGING = 4 -CMD_RESET_LOGGING = 5 - -# Possible states when receiving TOC -IDLE = 'IDLE' -GET_TOC_INF = 'GET_TOC_INFO' -GET_TOC_ELEMENT = 'GET_TOC_ELEMENT' - -# The max size of a CRTP packet payload -MAX_LOG_DATA_PACKET_SIZE = 30 - - -logger = logging.getLogger(__name__) - - -class LogVariable(): - """A logging variable""" - - TOC_TYPE = 0 - MEM_TYPE = 1 - - def __init__(self, name='', fetchAs='uint8_t', varType=TOC_TYPE, - storedAs='', address=0): - self.name = name - self.fetch_as = LogTocElement.get_id_from_cstring(fetchAs) - if (len(storedAs) == 0): - self.stored_as = self.fetch_as - else: - self.stored_as = LogTocElement.get_id_from_cstring(storedAs) - self.address = address - self.type = varType - self.stored_as_string = storedAs - self.fetch_as_string = fetchAs - - def is_toc_variable(self): - """ - Return true if the variable should be in the TOC, false if raw memory - variable - """ - return self.type == LogVariable.TOC_TYPE - - def get_storage_and_fetch_byte(self): - """Return what the variable is stored as and fetched as""" - return (self.fetch_as | (self.stored_as << 4)) - - def __str__(self): - return ('LogVariable: name=%s, store=%s, fetch=%s' % - (self.name, LogTocElement.get_cstring_from_id(self.stored_as), - LogTocElement.get_cstring_from_id(self.fetch_as))) - - -class LogConfig(object): - """Representation of one log configuration that enables logging - from the Crazyflie""" - - def __init__(self, name, period_in_ms): - """Initialize the entry""" - self.data_received_cb = Caller() - self.error_cb = Caller() - self.started_cb = Caller() - self.added_cb = Caller() - self.err_no = 0 - - self.id = 0 - self.cf = None - self.period = int(period_in_ms / 10) - self.period_in_ms = period_in_ms - self._added = False - self._started = False - self.valid = False - self.variables = [] - self.default_fetch_as = [] - self.name = name - - def add_variable(self, name, fetch_as=None): - """Add a new variable to the configuration. - - name - Complete name of the variable in the form group.name - fetch_as - String representation of the type the variable should be - fetched as (i.e uint8_t, float, FP16, etc) - - If no fetch_as type is supplied, then the stored as type will be used - (i.e the type of the fetched variable is the same as it's stored in the - Crazyflie).""" - if fetch_as: - self.variables.append(LogVariable(name, fetch_as)) - else: - # We cannot determine the default type until we have connected. So - # save the name and we will add these once we are connected. - self.default_fetch_as.append(name) - - def add_memory(self, name, fetch_as, stored_as, address): - """Add a raw memory position to log. - - name - Arbitrary name of the variable - fetch_as - String representation of the type of the data the memory - should be fetch as (i.e uint8_t, float, FP16) - stored_as - String representation of the type the data is stored as - in the Crazyflie - address - The address of the data - """ - self.variables.append(LogVariable(name, fetch_as, LogVariable.MEM_TYPE, - stored_as, address)) - - def _set_added(self, added): - if added != self._added: - self.added_cb.call(self, added) - self._added = added - - def _get_added(self): - return self._added - - def _set_started(self, started): - if started != self._started: - self.started_cb.call(self, started) - self._started = started - - def _get_started(self): - return self._started - - added = property(_get_added, _set_added) - started = property(_get_started, _set_started) - - def create(self): - """Save the log configuration in the Crazyflie""" - pk = CRTPPacket() - pk.set_header(5, CHAN_SETTINGS) - pk.data = (CMD_CREATE_BLOCK, self.id) - for var in self.variables: - if (var.is_toc_variable() is False): # Memory location - logger.debug('Logging to raw memory %d, 0x%04X', - var.get_storage_and_fetch_byte(), var.address) - pk.data.append(struct.pack('<B', - var.get_storage_and_fetch_byte())) - pk.data.append(struct.pack('<I', var.address)) - else: # Item in TOC - logger.debug('Adding %s with id=%d and type=0x%02X', - var.name, - self.cf.log.toc.get_element_id( - var.name), var.get_storage_and_fetch_byte()) - pk.data.append(var.get_storage_and_fetch_byte()) - pk.data.append(self.cf.log.toc.get_element_id(var.name)) - logger.debug('Adding log block id {}'.format(self.id)) - self.cf.send_packet(pk, expected_reply=(CMD_CREATE_BLOCK, self.id)) - - def start(self): - """Start the logging for this entry""" - if (self.cf.link is not None): - if (self._added is False): - self.create() - logger.debug('First time block is started, add block') - else: - logger.debug('Block already registered, starting logging' - ' for id=%d', self.id) - pk = CRTPPacket() - pk.set_header(5, CHAN_SETTINGS) - pk.data = (CMD_START_LOGGING, self.id, self.period) - self.cf.send_packet(pk, expected_reply=( - CMD_START_LOGGING, self.id)) - - def stop(self): - """Stop the logging for this entry""" - if (self.cf.link is not None): - if (self.id is None): - logger.warning('Stopping block, but no block registered') - else: - logger.debug('Sending stop logging for block id=%d', self.id) - pk = CRTPPacket() - pk.set_header(5, CHAN_SETTINGS) - pk.data = (CMD_STOP_LOGGING, self.id) - self.cf.send_packet( - pk, expected_reply=(CMD_STOP_LOGGING, self.id)) - - def delete(self): - """Delete this entry in the Crazyflie""" - if (self.cf.link is not None): - if (self.id is None): - logger.warning('Delete block, but no block registered') - else: - logger.debug('LogEntry: Sending delete logging for block id=%d' - % self.id) - pk = CRTPPacket() - pk.set_header(5, CHAN_SETTINGS) - pk.data = (CMD_DELETE_BLOCK, self.id) - self.cf.send_packet( - pk, expected_reply=(CMD_DELETE_BLOCK, self.id)) - - def unpack_log_data(self, log_data, timestamp): - """Unpack received logging data so it represent real values according - to the configuration in the entry""" - ret_data = {} - data_index = 0 - for var in self.variables: - size = LogTocElement.get_size_from_id(var.fetch_as) - name = var.name - unpackstring = LogTocElement.get_unpack_string_from_id( - var.fetch_as) - value = struct.unpack( - unpackstring, log_data[data_index:data_index + size])[0] - data_index += size - ret_data[name] = value - self.data_received_cb.call(timestamp, ret_data, self) - - -class LogTocElement: - """An element in the Log TOC.""" - types = {0x01: ('uint8_t', '<B', 1), - 0x02: ('uint16_t', '<H', 2), - 0x03: ('uint32_t', '<L', 4), - 0x04: ('int8_t', '<b', 1), - 0x05: ('int16_t', '<h', 2), - 0x06: ('int32_t', '<i', 4), - 0x08: ('FP16', '<h', 2), - 0x07: ('float', '<f', 4)} - - @staticmethod - def get_id_from_cstring(name): - """Return variable type id given the C-storage name""" - for key in list(LogTocElement.types.keys()): - if (LogTocElement.types[key][0] == name): - return key - raise KeyError('Type [%s] not found in LogTocElement.types!' % name) - - @staticmethod - def get_cstring_from_id(ident): - """Return the C-storage name given the variable type id""" - try: - return LogTocElement.types[ident][0] - except KeyError: - raise KeyError('Type [%d] not found in LogTocElement.types' - '!' % ident) - - @staticmethod - def get_size_from_id(ident): - """Return the size in bytes given the variable type id""" - try: - return LogTocElement.types[ident][2] - except KeyError: - raise KeyError('Type [%d] not found in LogTocElement.types' - '!' % ident) - - @staticmethod - def get_unpack_string_from_id(ident): - """Return the Python unpack string given the variable type id""" - try: - return LogTocElement.types[ident][1] - except KeyError: - raise KeyError( - 'Type [%d] not found in LogTocElement.types!' % ident) - - def __init__(self, data=None): - """TocElement creator. Data is the binary payload of the element.""" - - if (data): - naming = data[2:] - zt = bytearray((0, )) - self.group = naming[:naming.find(zt)].decode('ISO-8859-1') - self.name = naming[naming.find(zt) + 1:-1].decode('ISO-8859-1') - - self.ident = data[0] - - self.ctype = LogTocElement.get_cstring_from_id(data[1]) - self.pytype = LogTocElement.get_unpack_string_from_id(data[1]) - - self.access = data[1] & 0x10 - - -class Log(): - """Create log configuration""" - - # These codes can be decoded using os.stderror, but - # some of the text messages will look very strange - # in the UI, so they are redefined here - _err_codes = { - errno.ENOMEM: 'No more memory available', - errno.ENOEXEC: 'Command not found', - errno.ENOENT: 'No such block id', - errno.E2BIG: 'Block too large', - errno.EEXIST: 'Block already exists' - } - - def __init__(self, crazyflie=None): - self.log_blocks = [] - # Called with newly created blocks - self.block_added_cb = Caller() - - self.cf = crazyflie - self.toc = None - self.cf.add_port_callback(CRTPPort.LOGGING, self._new_packet_cb) - - self.toc_updated = Caller() - self.state = IDLE - self.fake_toc_crc = 0xDEADBEEF - - self._refresh_callback = None - self._toc_cache = None - - self._config_id_counter = 1 - - def add_config(self, logconf): - """Add a log configuration to the logging framework. - - When doing this the contents of the log configuration will be validated - and listeners for new log configurations will be notified. When - validating the configuration the variables are checked against the TOC - to see that they actually exist. If they don't then the configuration - cannot be used. Since a valid TOC is required, a Crazyflie has to be - connected when calling this method, otherwise it will fail.""" - - if not self.cf.link: - logger.error('Cannot add configs without being connected to a ' - 'Crazyflie!') - return - - # If the log configuration contains variables that we added without - # type (i.e we want the stored as type for fetching as well) then - # resolve this now and add them to the block again. - for name in logconf.default_fetch_as: - var = self.toc.get_element_by_complete_name(name) - if not var: - logger.warning( - '%s not in TOC, this block cannot be used!', name) - logconf.valid = False - raise KeyError('Variable {} not in TOC'.format(name)) - # Now that we know what type this variable has, add it to the log - # config again with the correct type - logconf.add_variable(name, var.ctype) - - # Now check that all the added variables are in the TOC and that - # the total size constraint of a data packet with logging data is - # not - size = 0 - for var in logconf.variables: - size += LogTocElement.get_size_from_id(var.fetch_as) - # Check that we are able to find the variable in the TOC so - # we can return error already now and not when the config is sent - if var.is_toc_variable(): - if (self.toc.get_element_by_complete_name(var.name) is None): - logger.warning( - 'Log: %s not in TOC, this block cannot be used!', - var.name) - logconf.valid = False - raise KeyError('Variable {} not in TOC'.format(var.name)) - - if (size <= MAX_LOG_DATA_PACKET_SIZE and - (logconf.period > 0 and logconf.period < 0xFF)): - logconf.valid = True - logconf.cf = self.cf - logconf.id = self._config_id_counter - self._config_id_counter = (self._config_id_counter + 1) % 255 - self.log_blocks.append(logconf) - self.block_added_cb.call(logconf) - else: - logconf.valid = False - raise AttributeError( - 'The log configuration is too large or has an invalid ' - 'parameter') - - def refresh_toc(self, refresh_done_callback, toc_cache): - """Start refreshing the table of loggale variables""" - - self._toc_cache = toc_cache - self._refresh_callback = refresh_done_callback - self.toc = None - - pk = CRTPPacket() - pk.set_header(CRTPPort.LOGGING, CHAN_SETTINGS) - pk.data = (CMD_RESET_LOGGING,) - self.cf.send_packet(pk, expected_reply=(CMD_RESET_LOGGING,)) - - def _find_block(self, id): - for block in self.log_blocks: - if block.id == id: - return block - return None - - def _new_packet_cb(self, packet): - """Callback for newly arrived packets with TOC information""" - chan = packet.channel - cmd = packet.data[0] - payload = packet.data[1:] - - if (chan == CHAN_SETTINGS): - id = payload[0] - error_status = payload[1] - block = self._find_block(id) - if (cmd == CMD_CREATE_BLOCK): - if (block is not None): - if error_status == 0 or error_status == errno.EEXIST: - if not block.added: - logger.debug('Have successfully added id=%d', id) - - pk = CRTPPacket() - pk.set_header(5, CHAN_SETTINGS) - pk.data = (CMD_START_LOGGING, id, block.period) - self.cf.send_packet(pk, expected_reply=( - CMD_START_LOGGING, id)) - block.added = True - else: - msg = self._err_codes[error_status] - logger.warning('Error %d when adding id=%d (%s)', - error_status, id, msg) - block.err_no = error_status - block.added_cb.call(False) - block.error_cb.call(block, msg) - - else: - logger.warning('No LogEntry to assign block to !!!') - if (cmd == CMD_START_LOGGING): - if (error_status == 0x00): - logger.info('Have successfully started logging for id=%d', - id) - if block: - block.started = True - - else: - msg = self._err_codes[error_status] - logger.warning('Error %d when starting id=%d (%s)', - error_status, id, msg) - if block: - block.err_no = error_status - block.started_cb.call(self, False) - # This is a temporary fix, we are adding a new issue - # for this. For some reason we get an error back after - # the block has been started and added. This will show - # an error in the UI, but everything is still working. - # block.error_cb.call(block, msg) - - if (cmd == CMD_STOP_LOGGING): - if (error_status == 0x00): - logger.info('Have successfully stopped logging for id=%d', - id) - if block: - block.started = False - - if (cmd == CMD_DELETE_BLOCK): - # Accept deletion of a block that isn't added. This could - # happen due to timing (i.e add/start/delete in fast sequence) - if error_status == 0x00 or error_status == errno.ENOENT: - logger.info('Have successfully deleted id=%d', id) - if block: - block.started = False - block.added = False - - if (cmd == CMD_RESET_LOGGING): - # Guard against multiple responses due to re-sending - if not self.toc: - logger.debug('Logging reset, continue with TOC download') - self.log_blocks = [] - - self.toc = Toc() - toc_fetcher = TocFetcher(self.cf, LogTocElement, - CRTPPort.LOGGING, - self.toc, self._refresh_callback, - self._toc_cache) - toc_fetcher.start() - - if (chan == CHAN_LOGDATA): - chan = packet.channel - id = packet.data[0] - block = self._find_block(id) - timestamps = struct.unpack('<BBB', packet.data[1:4]) - timestamp = ( - timestamps[0] | timestamps[1] << 8 | timestamps[2] << 16) - logdata = packet.data[4:] - if (block is not None): - block.unpack_log_data(logdata, timestamp) - else: - logger.warning('Error no LogEntry to handle id=%d', id) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/mem.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/mem.py deleted file mode 100644 index 071b3f0f..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/mem.py +++ /dev/null @@ -1,950 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2014 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Enables flash access to the Crazyflie. - -""" -import errno -import logging -import struct -import sys -from array import array -from binascii import crc32 -from functools import reduce -from threading import Lock - -from cflib.crtp.crtpstack import CRTPPacket -from cflib.crtp.crtpstack import CRTPPort -from cflib.utils.callbacks import Caller - -__author__ = 'Bitcraze AB' -__all__ = ['Memory', 'MemoryElement'] - -# Channels used for the logging port -CHAN_INFO = 0 -CHAN_READ = 1 -CHAN_WRITE = 2 - -# Commands used when accessing the Settings port -CMD_INFO_VER = 0 -CMD_INFO_NBR = 1 -CMD_INFO_DETAILS = 2 - -# The max size of a CRTP packet payload -MAX_LOG_DATA_PACKET_SIZE = 30 - -if sys.version_info < (3,): - EEPROM_TOKEN = '0xBC' -else: - EEPROM_TOKEN = b'0xBC' - -logger = logging.getLogger(__name__) - - -class MemoryElement(object): - """A memory """ - - TYPE_I2C = 0 - TYPE_1W = 1 - TYPE_DRIVER_LED = 0x10 - TYPE_LOCO = 0x11 - - def __init__(self, id, type, size, mem_handler): - """Initialize the element with default values""" - self.id = id - self.type = type - self.size = size - self.mem_handler = mem_handler - - @staticmethod - def type_to_string(t): - """Get string representation of memory type""" - if t == MemoryElement.TYPE_I2C: - return 'I2C' - if t == MemoryElement.TYPE_1W: - return '1-wire' - if t == MemoryElement.TYPE_DRIVER_LED: - return 'LED driver' - if t == MemoryElement.TYPE_LOCO: - return 'Loco Positioning' - return 'Unknown' - - def new_data(self, mem, addr, data): - logger.info('New data, but not OW mem') - - def __str__(self): - """Generate debug string for memory""" - return ('Memory: id={}, type={}, size={}'.format( - self.id, MemoryElement.type_to_string(self.type), self.size)) - - -class LED: - """Used to set color/intensity of one LED in the LED-ring""" - - def __init__(self): - """Initialize to off""" - self.r = 0 - self.g = 0 - self.b = 0 - self.intensity = 100 - - def set(self, r, g, b, intensity=None): - """Set the R/G/B and optionally intensity in one call""" - self.r = r - self.g = g - self.b = b - if intensity: - self.intensity = intensity - - -class LEDDriverMemory(MemoryElement): - """Memory interface for using the LED-ring mapped memory for setting RGB - values for all the LEDs in the ring""" - - def __init__(self, id, type, size, mem_handler): - """Initialize with 12 LEDs""" - super(LEDDriverMemory, self).__init__(id=id, type=type, size=size, - mem_handler=mem_handler) - self._update_finished_cb = None - self._write_finished_cb = None - - self.leds = [] - for i in range(12): - self.leds.append(LED()) - - def new_data(self, mem, addr, data): - """Callback for when new memory data has been fetched""" - if mem.id == self.id: - logger.info("Got new data from the LED driver, but we don't care.") - - def write_data(self, write_finished_cb): - """Write the saved LED-ring data to the Crazyflie""" - self._write_finished_cb = write_finished_cb - data = bytearray() - for led in self.leds: - # In order to fit all the LEDs in one radio packet RGB565 is used - # to compress the colors. The calculations below converts 3 bytes - # RGB into 2 bytes RGB565. Then shifts the value of each color to - # LSB, applies the intensity and shifts them back for correct - # alignment on 2 bytes. - R5 = ((int)((((int(led.r) & 0xFF) * 249 + 1014) >> 11) & 0x1F) * - led.intensity / 100) - G6 = ((int)((((int(led.g) & 0xFF) * 253 + 505) >> 10) & 0x3F) * - led.intensity / 100) - B5 = ((int)((((int(led.b) & 0xFF) * 249 + 1014) >> 11) & 0x1F) * - led.intensity / 100) - tmp = (int(R5) << 11) | (int(G6) << 5) | (int(B5) << 0) - data += bytearray((tmp >> 8, tmp & 0xFF)) - self.mem_handler.write(self, 0x00, data, flush_queue=True) - - def update(self, update_finished_cb): - """Request an update of the memory content""" - if not self._update_finished_cb: - self._update_finished_cb = update_finished_cb - self.valid = False - logger.info('Updating content of memory {}'.format(self.id)) - # Start reading the header - self.mem_handler.read(self, 0, 16) - - def write_done(self, mem, addr): - if self._write_finished_cb and mem.id == self.id: - logger.info('Write to LED driver done') - self._write_finished_cb(self, addr) - self._write_finished_cb = None - - def disconnect(self): - self._update_finished_cb = None - self._write_finished_cb = None - - -class I2CElement(MemoryElement): - - def __init__(self, id, type, size, mem_handler): - super(I2CElement, self).__init__(id=id, type=type, size=size, - mem_handler=mem_handler) - self._update_finished_cb = None - self._write_finished_cb = None - self.elements = {} - self.valid = False - - def new_data(self, mem, addr, data): - """Callback for when new memory data has been fetched""" - if mem.id == self.id: - if addr == 0: - done = False - # Check for header - if data[0:4] == EEPROM_TOKEN: - logger.info('Got new data: {}'.format(data)) - [self.elements['version'], - self.elements['radio_channel'], - self.elements['radio_speed'], - self.elements['pitch_trim'], - self.elements['roll_trim']] = struct.unpack('<BBBff', - data[4:15]) - if self.elements['version'] == 0: - done = True - elif self.elements['version'] == 1: - self.datav0 = data - self.mem_handler.read(self, 16, 5) - else: - self.valid = False - if self._update_finished_cb: - self._update_finished_cb(self) - self._update_finished_cb = None - - if addr == 16: - [radio_address_upper, radio_address_lower] = struct.unpack( - '<BI', self.datav0[15:16] + data[0:4]) - self.elements['radio_address'] = int( - radio_address_upper) << 32 | radio_address_lower - - logger.info(self.elements) - data = self.datav0 + data - done = True - - if done: - if self._checksum256(data[:len(data) - 1]) == \ - data[len(data) - 1]: - self.valid = True - if self._update_finished_cb: - self._update_finished_cb(self) - self._update_finished_cb = None - - def _checksum256(self, st): - return reduce(lambda x, y: x + y, list(st)) % 256 - - def write_data(self, write_finished_cb): - image = bytearray() - if self.elements['version'] == 0: - data = ( - 0x00, self.elements['radio_channel'], - self.elements['radio_speed'], - self.elements['pitch_trim'], self.elements['roll_trim']) - image += struct.pack('<BBBff', *data) - elif self.elements['version'] == 1: - data = ( - 0x01, self.elements['radio_channel'], - self.elements['radio_speed'], - self.elements['pitch_trim'], self.elements['roll_trim'], - self.elements['radio_address'] >> 32, - self.elements['radio_address'] & 0xFFFFFFFF) - image += struct.pack('<BBBffBI', *data) - # Adding some magic: - image = EEPROM_TOKEN + image - image += struct.pack('B', self._checksum256(image)) - - self._write_finished_cb = write_finished_cb - - self.mem_handler.write(self, 0x00, - struct.unpack('B' * len(image), image)) - - def update(self, update_finished_cb): - """Request an update of the memory content""" - if not self._update_finished_cb: - self._update_finished_cb = update_finished_cb - self.valid = False - logger.info('Updating content of memory {}'.format(self.id)) - # Start reading the header - self.mem_handler.read(self, 0, 16) - - def write_done(self, mem, addr): - if self._write_finished_cb and mem.id == self.id: - self._write_finished_cb(self, addr) - self._write_finished_cb = None - - def disconnect(self): - self._update_finished_cb = None - self._write_finished_cb = None - - -class OWElement(MemoryElement): - """Memory class with extra functionality for 1-wire memories""" - - element_mapping = { - 1: 'Board name', - 2: 'Board revision', - 3: 'Custom' - } - - def __init__(self, id, type, size, addr, mem_handler): - """Initialize the memory with good defaults""" - super(OWElement, self).__init__(id=id, type=type, size=size, - mem_handler=mem_handler) - self.addr = addr - - self.valid = False - - self.vid = None - self.pid = None - self.name = None - self.pins = None - self.elements = {} - - self._update_finished_cb = None - self._write_finished_cb = None - - self._rev_element_mapping = {} - for key in list(OWElement.element_mapping.keys()): - self._rev_element_mapping[OWElement.element_mapping[key]] = key - - def new_data(self, mem, addr, data): - """Callback for when new memory data has been fetched""" - if mem.id == self.id: - if addr == 0: - if self._parse_and_check_header(data[0:8]): - if self._parse_and_check_elements(data[9:11]): - self.valid = True - self._update_finished_cb(self) - self._update_finished_cb = None - else: - # We need to fetch the elements, find out the length - (elem_ver, elem_len) = struct.unpack('BB', data[8:10]) - self.mem_handler.read(self, 8, elem_len + 3) - else: - # Call the update if the CRC check of the header fails, - # we're done here - if self._update_finished_cb: - self._update_finished_cb(self) - self._update_finished_cb = None - elif addr == 0x08: - if self._parse_and_check_elements(data): - self.valid = True - if self._update_finished_cb: - self._update_finished_cb(self) - self._update_finished_cb = None - - def _parse_and_check_elements(self, data): - """ - Parse and check the CRC and length of the elements part of the memory - """ - crc = data[-1] - test_crc = crc32(data[:-1]) & 0x0ff - elem_data = data[2:-1] - if test_crc == crc: - while len(elem_data) > 0: - (eid, elen) = struct.unpack('BB', elem_data[:2]) - self.elements[self.element_mapping[eid]] = \ - elem_data[2:2 + elen].decode('ISO-8859-1') - elem_data = elem_data[2 + elen:] - return True - return False - - def write_done(self, mem, addr): - if self._write_finished_cb: - self._write_finished_cb(self, addr) - self._write_finished_cb = None - - def write_data(self, write_finished_cb): - # First generate the header part - header_data = struct.pack('<BIBB', 0xEB, self.pins, self.vid, self.pid) - header_crc = crc32(header_data) & 0x0ff - header_data += struct.pack('B', header_crc) - - # Now generate the elements part - elem = bytearray() - logger.info(list(self.elements.keys())) - for element in reversed(list(self.elements.keys())): - elem_string = self.elements[element] - # logger.info(">>>> {}".format(elem_string)) - key_encoding = self._rev_element_mapping[element] - elem += struct.pack('BB', key_encoding, len(elem_string)) - elem += bytearray(elem_string.encode('ISO-8859-1')) - - elem_data = struct.pack('BB', 0x00, len(elem)) - elem_data += elem - elem_crc = crc32(elem_data) & 0x0ff - elem_data += struct.pack('B', elem_crc) - - data = header_data + elem_data - - self.mem_handler.write(self, 0x00, - struct.unpack('B' * len(data), data)) - - self._write_finished_cb = write_finished_cb - - def erase(self, write_finished_cb): - erase_data = array('B', [0xFF] * 112) - self.mem_handler.write(self, 0x00, - struct.unpack('B' * len(erase_data), - erase_data)) - - self._write_finished_cb = write_finished_cb - - def update(self, update_finished_cb): - """Request an update of the memory content""" - if not self._update_finished_cb: - self._update_finished_cb = update_finished_cb - self.valid = False - logger.info('Updating content of memory {}'.format(self.id)) - # Start reading the header - self.mem_handler.read(self, 0, 11) - - def _parse_and_check_header(self, data): - """Parse and check the CRC of the header part of the memory""" - # logger.info("Should parse header: {}".format(data)) - (start, self.pins, self.vid, self.pid, crc) = struct.unpack('<BIBBB', - data) - test_crc = crc32(data[:-1]) & 0x0ff - if start == 0xEB and crc == test_crc: - return True - return False - - def __str__(self): - """Generate debug string for memory""" - return ('OW {} ({:02X}:{:02X}): {}'.format( - self.addr, self.vid, self.pid, self.elements)) - - def disconnect(self): - self._update_finished_cb = None - self._write_finished_cb = None - - -class AnchorData: - - def __init__(self, position=(0.0, 0.0, 0.0), is_valid=False): - self.position = position - self.is_valid = is_valid - - def set_from_mem_data(self, data): - x, y, z, self.is_valid = struct.unpack('<fff?', data) - self.position = (x, y, z) - - -class LocoMemory(MemoryElement): - """Memory interface for accessing data from the Loco Positioning system""" - - SIZE_OF_FLOAT = 4 - MEM_LOCO_INFO = 0x0000 - MEM_LOCO_INFO_LEN = 1 - MEM_LOCO_ANCHOR_BASE = 0x1000 - MEM_LOCO_ANCHOR_PAGE_SIZE = 0x0100 - MEM_LOCO_PAGE_LEN = (3 * SIZE_OF_FLOAT) + 1 - - def __init__(self, id, type, size, mem_handler): - super(LocoMemory, self).__init__(id=id, type=type, size=size, - mem_handler=mem_handler) - self._update_finished_cb = None - - self.anchor_data = [] - self.nr_of_anchors = 0 - self.valid = False - - def new_data(self, mem, addr, data): - """Callback for when new memory data has been fetched""" - done = False - if mem.id == self.id: - if addr == LocoMemory.MEM_LOCO_INFO: - self.nr_of_anchors = data[0] - if self.nr_of_anchors == 0: - done = True - else: - self.anchor_data = \ - [AnchorData() for _ in range(self.nr_of_anchors)] - self._request_page(0) - else: - page = int((addr - LocoMemory.MEM_LOCO_ANCHOR_BASE) / - LocoMemory.MEM_LOCO_ANCHOR_PAGE_SIZE) - - self.anchor_data[page].set_from_mem_data(data) - - next_page = page + 1 - if next_page < self.nr_of_anchors: - self._request_page(next_page) - else: - done = True - - if done: - self.valid = True - if self._update_finished_cb: - self._update_finished_cb(self) - self._update_finished_cb = None - - def update(self, update_finished_cb): - """Request an update of the memory content""" - if not self._update_finished_cb: - self._update_finished_cb = update_finished_cb - self.anchor_data = [] - self.nr_of_anchors = 0 - self.valid = False - logger.info('Updating content of memory {}'.format(self.id)) - - # Start reading the header - self.mem_handler.read(self, LocoMemory.MEM_LOCO_INFO, - LocoMemory.MEM_LOCO_INFO_LEN) - - def disconnect(self): - self._update_finished_cb = None - - def _request_page(self, page): - addr = LocoMemory.MEM_LOCO_ANCHOR_BASE + \ - LocoMemory.MEM_LOCO_ANCHOR_PAGE_SIZE * page - self.mem_handler.read(self, addr, LocoMemory.MEM_LOCO_PAGE_LEN) - - -class _ReadRequest: - """ - Class used to handle memory reads that will split up the read in multiple - packets if necessary - """ - MAX_DATA_LENGTH = 20 - - def __init__(self, mem, addr, length, cf): - """Initialize the object with good defaults""" - self.mem = mem - self.addr = addr - self._bytes_left = length - self.data = bytearray() - self.cf = cf - - self._current_addr = addr - - def start(self): - """Start the fetching of the data""" - self._request_new_chunk() - - def resend(self): - logger.info('Sending write again...') - self._request_new_chunk() - - def _request_new_chunk(self): - """ - Called to request a new chunk of data to be read from the Crazyflie - """ - # Figure out the length of the next request - new_len = self._bytes_left - if new_len > _ReadRequest.MAX_DATA_LENGTH: - new_len = _ReadRequest.MAX_DATA_LENGTH - - logger.info('Requesting new chunk of {}bytes at 0x{:X}'.format( - new_len, self._current_addr)) - - # Request the data for the next address - pk = CRTPPacket() - pk.set_header(CRTPPort.MEM, CHAN_READ) - pk.data = struct.pack('<BIB', self.mem.id, self._current_addr, new_len) - reply = struct.unpack('<BBBBB', pk.data[:-1]) - self.cf.send_packet(pk, expected_reply=reply, timeout=1) - - def add_data(self, addr, data): - """Callback when data is received from the Crazyflie""" - data_len = len(data) - if not addr == self._current_addr: - logger.warning( - 'Address did not match when adding data to read request!') - return - - # Add the data and calculate the next address to fetch - self.data += data - self._bytes_left -= data_len - self._current_addr += data_len - - if self._bytes_left > 0: - self._request_new_chunk() - return False - else: - return True - - -class _WriteRequest: - """ - Class used to handle memory reads that will split up the read in multiple - packets in necessary - """ - MAX_DATA_LENGTH = 25 - - def __init__(self, mem, addr, data, cf): - """Initialize the object with good defaults""" - self.mem = mem - self.addr = addr - self._bytes_left = len(data) - self._data = data - self.data = bytearray() - self.cf = cf - - self._current_addr = addr - - self._sent_packet = None - self._sent_reply = None - - self._addr_add = 0 - - def start(self): - """Start the fetching of the data""" - self._write_new_chunk() - - def resend(self): - logger.info('Sending write again...') - self.cf.send_packet( - self._sent_packet, expected_reply=self._sent_reply, timeout=1) - - def _write_new_chunk(self): - """ - Called to request a new chunk of data to be read from the Crazyflie - """ - # Figure out the length of the next request - new_len = len(self._data) - if new_len > _WriteRequest.MAX_DATA_LENGTH: - new_len = _WriteRequest.MAX_DATA_LENGTH - - logger.info('Writing new chunk of {}bytes at 0x{:X}'.format( - new_len, self._current_addr)) - - data = self._data[:new_len] - self._data = self._data[new_len:] - - pk = CRTPPacket() - pk.set_header(CRTPPort.MEM, CHAN_WRITE) - pk.data = struct.pack('<BI', self.mem.id, self._current_addr) - # Create a tuple used for matching the reply using id and address - reply = struct.unpack('<BBBBB', pk.data) - self._sent_reply = reply - # Add the data - pk.data += struct.pack('B' * len(data), *data) - self._sent_packet = pk - self.cf.send_packet(pk, expected_reply=reply, timeout=1) - - self._addr_add = len(data) - - def write_done(self, addr): - """Callback when data is received from the Crazyflie""" - if not addr == self._current_addr: - logger.warning( - 'Address did not match when adding data to read request!') - return - - if len(self._data) > 0: - self._current_addr += self._addr_add - self._write_new_chunk() - return False - else: - logger.info('This write request is done') - return True - - -class Memory(): - """Access memories on the Crazyflie""" - - # These codes can be decoded using os.stderror, but - # some of the text messages will look very strange - # in the UI, so they are redefined here - _err_codes = { - errno.ENOMEM: 'No more memory available', - errno.ENOEXEC: 'Command not found', - errno.ENOENT: 'No such block id', - errno.E2BIG: 'Block too large', - errno.EEXIST: 'Block already exists' - } - - def __init__(self, crazyflie=None): - """Instantiate class and connect callbacks""" - self.mems = [] - # Called when new memories have been added - self.mem_added_cb = Caller() - # Called when new data has been read - self.mem_read_cb = Caller() - - self.mem_write_cb = Caller() - - self.cf = crazyflie - self.cf.add_port_callback(CRTPPort.MEM, self._new_packet_cb) - self.cf.disconnected.add_callback(self._disconnected) - - self._refresh_callback = None - self._fetch_id = 0 - self.nbr_of_mems = 0 - self._ow_mem_fetch_index = 0 - self._elem_data = () - self._read_requests = {} - self._read_requests_lock = Lock() - self._write_requests = {} - self._write_requests_lock = Lock() - self._ow_mems_left_to_update = [] - - self._getting_count = False - - def _mem_update_done(self, mem): - """ - Callback from each individual memory (only 1-wire) when reading of - header/elements are done - """ - if mem.id in self._ow_mems_left_to_update: - self._ow_mems_left_to_update.remove(mem.id) - - logger.info(mem) - - if len(self._ow_mems_left_to_update) == 0: - if self._refresh_callback: - self._refresh_callback() - self._refresh_callback = None - - def get_mem(self, id): - """Fetch the memory with the supplied id""" - for m in self.mems: - if m.id == id: - return m - - return None - - def get_mems(self, type): - """Fetch all the memories of the supplied type""" - ret = () - for m in self.mems: - if m.type == type: - ret += (m,) - - return ret - - def ow_search(self, vid=0xBC, pid=None, name=None): - """Search for specific memory id/name and return it""" - for m in self.get_mems(MemoryElement.TYPE_1W): - if pid and m.pid == pid or name and m.name == name: - return m - - return None - - def write(self, memory, addr, data, flush_queue=False): - """Write the specified data to the given memory at the given address""" - wreq = _WriteRequest(memory, addr, data, self.cf) - if memory.id not in self._write_requests: - self._write_requests[memory.id] = [] - - # Workaround until we secure the uplink and change messages for - # mems to non-blocking - self._write_requests_lock.acquire() - if flush_queue: - self._write_requests[memory.id] = self._write_requests[ - memory.id][:1] - self._write_requests[memory.id].insert(len(self._write_requests), wreq) - if len(self._write_requests[memory.id]) == 1: - wreq.start() - self._write_requests_lock.release() - - return True - - def read(self, memory, addr, length): - """ - Read the specified amount of bytes from the given memory at the given - address - """ - if memory.id in self._read_requests: - logger.warning('There is already a read operation ongoing for ' - 'memory id {}'.format(memory.id)) - return False - - rreq = _ReadRequest(memory, addr, length, self.cf) - self._read_requests[memory.id] = rreq - - rreq.start() - - return True - - def refresh(self, refresh_done_callback): - """Start fetching all the detected memories""" - self._refresh_callback = refresh_done_callback - self._fetch_id = 0 - for m in self.mems: - try: - self.mem_read_cb.remove_callback(m.new_data) - m.disconnect() - except Exception as e: - logger.info( - 'Error when removing memory after update: {}'.format(e)) - self.mems = [] - - self.nbr_of_mems = 0 - self._getting_count = False - - logger.info('Requesting number of memories') - pk = CRTPPacket() - pk.set_header(CRTPPort.MEM, CHAN_INFO) - pk.data = (CMD_INFO_NBR,) - self.cf.send_packet(pk, expected_reply=(CMD_INFO_NBR,)) - - def _disconnected(self, uri): - """The link to the Crazyflie has been broken. Reset state""" - for m in self.mems: - try: - m.disconnect() - except Exception as e: - logger.info( - 'Error when resetting after disconnect: {}'.format(e)) - - def _new_packet_cb(self, packet): - """Callback for newly arrived packets for the memory port""" - chan = packet.channel - cmd = packet.data[0] - payload = packet.data[1:] - - if chan == CHAN_INFO: - if cmd == CMD_INFO_NBR: - self.nbr_of_mems = payload[0] - logger.info('{} memories found'.format(self.nbr_of_mems)) - - # Start requesting information about the memories, - # if there are any... - if self.nbr_of_mems > 0: - if not self._getting_count: - self._getting_count = True - logger.info('Requesting first id') - pk = CRTPPacket() - pk.set_header(CRTPPort.MEM, CHAN_INFO) - pk.data = (CMD_INFO_DETAILS, 0) - self.cf.send_packet(pk, expected_reply=( - CMD_INFO_DETAILS, 0)) - else: - self._refresh_callback() - - if cmd == CMD_INFO_DETAILS: - - # Did we get a good reply, otherwise try again: - if len(payload) < 5: - # Workaround for 1-wire bug when memory is detected - # but updating the info crashes the communication with - # the 1-wire. Fail by saying we only found 1 memory - # (the I2C). - logger.error( - '-------->Got good count, but no info on mem!') - self.nbr_of_mems = 1 - if self._refresh_callback: - self._refresh_callback() - self._refresh_callback = None - return - - # Create information about a new memory - # Id - 1 byte - mem_id = payload[0] - # Type - 1 byte - mem_type = payload[1] - # Size 4 bytes (as addr) - mem_size = struct.unpack('I', payload[2:6])[0] - # Addr (only valid for 1-wire?) - mem_addr_raw = struct.unpack('B' * 8, payload[6:14]) - mem_addr = '' - for m in mem_addr_raw: - mem_addr += '{:02X}'.format(m) - - if (not self.get_mem(mem_id)): - if mem_type == MemoryElement.TYPE_1W: - mem = OWElement(id=mem_id, type=mem_type, - size=mem_size, - addr=mem_addr, mem_handler=self) - self.mem_read_cb.add_callback(mem.new_data) - self.mem_write_cb.add_callback(mem.write_done) - self._ow_mems_left_to_update.append(mem.id) - elif mem_type == MemoryElement.TYPE_I2C: - mem = I2CElement(id=mem_id, type=mem_type, - size=mem_size, - mem_handler=self) - self.mem_read_cb.add_callback(mem.new_data) - self.mem_write_cb.add_callback(mem.write_done) - elif mem_type == MemoryElement.TYPE_DRIVER_LED: - mem = LEDDriverMemory(id=mem_id, type=mem_type, - size=mem_size, mem_handler=self) - logger.info(mem) - self.mem_read_cb.add_callback(mem.new_data) - self.mem_write_cb.add_callback(mem.write_done) - elif mem_type == MemoryElement.TYPE_LOCO: - mem = LocoMemory(id=mem_id, type=mem_type, - size=mem_size, mem_handler=self) - logger.info(mem) - self.mem_read_cb.add_callback(mem.new_data) - else: - mem = MemoryElement(id=mem_id, type=mem_type, - size=mem_size, mem_handler=self) - logger.info(mem) - self.mems.append(mem) - self.mem_added_cb.call(mem) - # logger.info(mem) - - self._fetch_id = mem_id + 1 - - if self.nbr_of_mems - 1 >= self._fetch_id: - logger.info( - 'Requesting information about memory {}'.format( - self._fetch_id)) - pk = CRTPPacket() - pk.set_header(CRTPPort.MEM, CHAN_INFO) - pk.data = (CMD_INFO_DETAILS, self._fetch_id) - self.cf.send_packet(pk, expected_reply=( - CMD_INFO_DETAILS, self._fetch_id)) - else: - logger.info( - 'Done getting all the memories, start reading the OWs') - ows = self.get_mems(MemoryElement.TYPE_1W) - # If there are any OW mems start reading them, otherwise - # we are done - for ow_mem in ows: - ow_mem.update(self._mem_update_done) - if len(ows) == 0: - if self._refresh_callback: - self._refresh_callback() - self._refresh_callback = None - - if chan == CHAN_WRITE: - id = cmd - (addr, status) = struct.unpack('<IB', payload[0:5]) - logger.info( - 'WRITE: Mem={}, addr=0x{:X}, status=0x{}'.format( - id, addr, status)) - # Find the read request - if id in self._write_requests: - self._write_requests_lock.acquire() - wreq = self._write_requests[id][0] - if status == 0: - if wreq.write_done(addr): - # self._write_requests.pop(id, None) - # Remove the first item - self._write_requests[id].pop(0) - self.mem_write_cb.call(wreq.mem, wreq.addr) - - # Get a new one to start (if there are any) - if len(self._write_requests[id]) > 0: - self._write_requests[id][0].start() - else: - logger.info('Status {}: write resending...'.format(status)) - wreq.resend() - self._write_requests_lock.release() - - if chan == CHAN_READ: - id = cmd - (addr, status) = struct.unpack('<IB', payload[0:5]) - data = struct.unpack('B' * len(payload[5:]), payload[5:]) - logger.info('READ: Mem={}, addr=0x{:X}, status=0x{}, ' - 'data={}'.format(id, addr, status, data)) - # Find the read request - if id in self._read_requests: - logger.info( - 'READING: We are still interested in request for ' - 'mem {}'.format(id)) - rreq = self._read_requests[id] - if status == 0: - if rreq.add_data(addr, payload[5:]): - self._read_requests.pop(id, None) - self.mem_read_cb.call(rreq.mem, rreq.addr, rreq.data) - else: - logger.info('Status {}: resending...'.format(status)) - rreq.resend() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/param.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/param.py deleted file mode 100644 index a04ef035..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/param.py +++ /dev/null @@ -1,340 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Enables reading/writing of parameter values to/from the Crazyflie. - -When a Crazyflie is connected it's possible to download a TableOfContent of all -the parameters that can be written/read. - -""" -import logging -import struct -import sys -from threading import Lock -from threading import Thread - -from .toc import Toc -from .toc import TocFetcher -from cflib.crtp.crtpstack import CRTPPacket -from cflib.crtp.crtpstack import CRTPPort -from cflib.utils.callbacks import Caller -if sys.version_info < (3,): - from Queue import Queue -else: - from queue import Queue - - -__author__ = 'Bitcraze AB' -__all__ = ['Param', 'ParamTocElement'] - -logger = logging.getLogger(__name__) - -# Possible states -IDLE = 0 -WAIT_TOC = 1 -WAIT_READ = 2 -WAIT_WRITE = 3 - -TOC_CHANNEL = 0 -READ_CHANNEL = 1 -WRITE_CHANNEL = 2 - -# TOC access command -TOC_RESET = 0 -TOC_GETNEXT = 1 -TOC_GETCRC32 = 2 - - -# One element entry in the TOC -class ParamTocElement: - """An element in the Log TOC.""" - - RW_ACCESS = 0 - RO_ACCESS = 1 - - types = {0x08: ('uint8_t', '<B'), - 0x09: ('uint16_t', '<H'), - 0x0A: ('uint32_t', '<L'), - 0x0B: ('uint64_t', '<Q'), - 0x00: ('int8_t', '<b'), - 0x01: ('int16_t', '<h'), - 0x02: ('int32_t', '<i'), - 0x03: ('int64_t', '<q'), - 0x05: ('FP16', ''), - 0x06: ('float', '<f'), - 0x07: ('double', '<d')} - - def __init__(self, data=None): - """TocElement creator. Data is the binary payload of the element.""" - if (data): - strs = struct.unpack('s' * len(data[2:]), data[2:]) - if sys.version_info < (3,): - strs = ('{}' * len(strs)).format(*strs).split('\0') - else: - s = '' - for ch in strs: - s += ch.decode('ISO-8859-1') - strs = s.split('\x00') - self.group = strs[0] - self.name = strs[1] - - if type(data[0]) == str: - self.ident = ord(data[0]) - else: - self.ident = data[0] - - metadata = data[1] - if type(metadata) == str: - metadata = ord(metadata) - - self.ctype = self.types[metadata & 0x0F][0] - self.pytype = self.types[metadata & 0x0F][1] - if ((metadata & 0x40) != 0): - self.access = ParamTocElement.RO_ACCESS - else: - self.access = ParamTocElement.RW_ACCESS - - def get_readable_access(self): - if (self.access == ParamTocElement.RO_ACCESS): - return 'RO' - return 'RW' - - -class Param(): - """ - Used to read and write parameter values in the Crazyflie. - """ - - def __init__(self, crazyflie): - self.toc = Toc() - - self.cf = crazyflie - self.param_update_callbacks = {} - self.group_update_callbacks = {} - self.all_update_callback = Caller() - self.param_updater = None - - self.param_updater = _ParamUpdater(self.cf, self._param_updated) - self.param_updater.start() - - self.cf.disconnected.add_callback(self._disconnected) - - self.all_updated = Caller() - self.is_updated = False - - self.values = {} - - def request_update_of_all_params(self): - """Request an update of all the parameters in the TOC""" - for group in self.toc.toc: - for name in self.toc.toc[group]: - complete_name = '%s.%s' % (group, name) - self.request_param_update(complete_name) - - def _check_if_all_updated(self): - """Check if all parameters from the TOC has at least been fetched - once""" - for g in self.toc.toc: - if g not in self.values: - return False - for n in self.toc.toc[g]: - if n not in self.values[g]: - return False - - return True - - def _param_updated(self, pk): - """Callback with data for an updated parameter""" - var_id = pk.data[0] - element = self.toc.get_element_by_id(var_id) - if element: - s = struct.unpack(element.pytype, pk.data[1:])[0] - s = s.__str__() - complete_name = '%s.%s' % (element.group, element.name) - - # Save the value for synchronous access - if element.group not in self.values: - self.values[element.group] = {} - self.values[element.group][element.name] = s - - logger.debug('Updated parameter [%s]' % complete_name) - if complete_name in self.param_update_callbacks: - self.param_update_callbacks[complete_name].call( - complete_name, s) - if element.group in self.group_update_callbacks: - self.group_update_callbacks[element.group].call( - complete_name, s) - self.all_update_callback.call(complete_name, s) - - # Once all the parameters are updated call the - # callback for "everything updated" (after all the param - # updated callbacks) - if self._check_if_all_updated() and not self.is_updated: - self.is_updated = True - self.all_updated.call() - else: - logger.debug('Variable id [%d] not found in TOC', var_id) - - def remove_update_callback(self, group, name=None, cb=None): - """Remove the supplied callback for a group or a group.name""" - if not cb: - return - - if not name: - if group in self.group_update_callbacks: - self.group_update_callbacks[group].remove_callback(cb) - else: - paramname = '{}.{}'.format(group, name) - if paramname in self.param_update_callbacks: - self.param_update_callbacks[paramname].remove_callback(cb) - - def add_update_callback(self, group=None, name=None, cb=None): - """ - Add a callback for a specific parameter name. This callback will be - executed when a new value is read from the Crazyflie. - """ - if not group and not name: - self.all_update_callback.add_callback(cb) - elif not name: - if group not in self.group_update_callbacks: - self.group_update_callbacks[group] = Caller() - self.group_update_callbacks[group].add_callback(cb) - else: - paramname = '{}.{}'.format(group, name) - if paramname not in self.param_update_callbacks: - self.param_update_callbacks[paramname] = Caller() - self.param_update_callbacks[paramname].add_callback(cb) - - def refresh_toc(self, refresh_done_callback, toc_cache): - """ - Initiate a refresh of the parameter TOC. - """ - toc_fetcher = TocFetcher(self.cf, ParamTocElement, - CRTPPort.PARAM, self.toc, - refresh_done_callback, toc_cache) - toc_fetcher.start() - - def _disconnected(self, uri): - """Disconnected callback from Crazyflie API""" - self.param_updater.close() - self.is_updated = False - # Clear all values from the previous Crazyflie - self.toc = Toc() - self.values = {} - - def request_param_update(self, complete_name): - """ - Request an update of the value for the supplied parameter. - """ - self.param_updater.request_param_update( - self.toc.get_element_id(complete_name)) - - def set_value(self, complete_name, value): - """ - Set the value for the supplied parameter. - """ - element = self.toc.get_element_by_complete_name(complete_name) - - if not element: - logger.warning("Cannot set value for [%s], it's not in the TOC!", - complete_name) - raise KeyError('{} not in param TOC'.format(complete_name)) - elif element.access == ParamTocElement.RO_ACCESS: - logger.debug('[%s] is read only, no trying to set value', - complete_name) - raise AttributeError('{} is read-only!'.format(complete_name)) - else: - varid = element.ident - pk = CRTPPacket() - pk.set_header(CRTPPort.PARAM, WRITE_CHANNEL) - pk.data = struct.pack('<B', varid) - pk.data += struct.pack(element.pytype, eval(value)) - self.param_updater.request_param_setvalue(pk) - - -class _ParamUpdater(Thread): - """This thread will update params through a queue to make sure that we - get back values""" - - def __init__(self, cf, updated_callback): - """Initialize the thread""" - Thread.__init__(self) - self.setDaemon(True) - self.wait_lock = Lock() - self.cf = cf - self.updated_callback = updated_callback - self.request_queue = Queue() - self.cf.add_port_callback(CRTPPort.PARAM, self._new_packet_cb) - self._should_close = False - self._req_param = -1 - - def close(self): - # First empty the queue from all packets - while not self.request_queue.empty(): - self.request_queue.get() - # Then force an unlock of the mutex if we are waiting for a packet - # we didn't get back due to a disconnect for example. - try: - self.wait_lock.release() - except: - pass - - def request_param_setvalue(self, pk): - """Place a param set value request on the queue. When this is sent to - the Crazyflie it will answer with the update param value. """ - self.request_queue.put(pk) - - def _new_packet_cb(self, pk): - """Callback for newly arrived packets""" - if pk.channel == READ_CHANNEL or pk.channel == WRITE_CHANNEL: - var_id = pk.data[0] - if (pk.channel != TOC_CHANNEL and self._req_param == var_id and - pk is not None): - self.updated_callback(pk) - self._req_param = -1 - try: - self.wait_lock.release() - except: - pass - - def request_param_update(self, var_id): - """Place a param update request on the queue""" - pk = CRTPPacket() - pk.set_header(CRTPPort.PARAM, READ_CHANNEL) - pk.data = struct.pack('<B', var_id) - logger.debug('Requesting request to update param [%d]', var_id) - self.request_queue.put(pk) - - def run(self): - while not self._should_close: - pk = self.request_queue.get() # Wait for request update - self.wait_lock.acquire() - if self.cf.link: - self._req_param = pk.data[0] - self.cf.send_packet(pk, expected_reply=(tuple(pk.data[0:2]))) - else: - self.wait_lock.release() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/platformservice.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/platformservice.py deleted file mode 100644 index ad922db1..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/platformservice.py +++ /dev/null @@ -1,56 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Used for sending control setpoints to the Crazyflie -""" -from cflib.crtp.crtpstack import CRTPPacket -from cflib.crtp.crtpstack import CRTPPort - -__author__ = 'Bitcraze AB' -__all__ = ['PlatformService'] - - -class PlatformService(): - """ - Used for sending control setpoints to the Crazyflie - """ - - def __init__(self, crazyflie=None): - """ - Initialize the platform object. - """ - self._cf = crazyflie - - def set_continous_wave(self, enabled): - """ - Enable/disable the client side X-mode. When enabled this recalculates - the setpoints before sending them to the Crazyflie. - """ - pk = CRTPPacket() - pk.set_header(CRTPPort.PLATFORM, 0) - pk.data = (0, enabled) - self._cf.send_packet(pk) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/swarm.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/swarm.py deleted file mode 100644 index 7bd53373..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/swarm.py +++ /dev/null @@ -1,192 +0,0 @@ -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2016 Bitcraze AB -# -# 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. -from threading import Thread - -from cflib.crazyflie.syncCrazyflie import SyncCrazyflie - - -class _Factory: - - def construct(self, uri): - return SyncCrazyflie(uri) - - -class Swarm: - """ - Runs a swarm of Crazyflies. It implements a functional-ish style of - sequential or parallel actions on all individuals of the swarm. - - When the swarm is connected, a link is opened to each Crazyflie through - SyncCrazyflie instances. The instances are maintained by the class and are - passed in as the first argument in swarm wide actions. - """ - - def __init__(self, uris, factory=_Factory()): - """ - Constructs a Swarm instance and instances used to connect to the - Crazyflies - - :param uris: A set of uris to use when connecting to the Crazyflies in - the swarm - :param factory: A factory class used to create the instances that are - used to open links to the Crazyflies. Mainly used for unit testing. - """ - self._cfs = {} - self._is_open = False - - for uri in uris: - self._cfs[uri] = factory.construct(uri) - - def open_links(self): - """ - Open links to all individuals in the swarm - """ - if self._is_open: - raise Exception('Already opened') - - try: - self.parallel_safe(lambda scf: scf.open_link()) - self._is_open = True - except Exception as e: - self.close_links() - raise e - - def close_links(self): - """ - Close all open links - """ - for uri, cf in self._cfs.items(): - cf.close_link() - - self._is_open = False - - def __enter__(self): - self.open_links() - return self - - def __exit__(self, exc_type, exc_val, exc_tb): - self.close_links() - - def sequential(self, func, args_dict=None): - """ - Execute a function for all Crazyflies in the swarm, in sequence. - - The first argument of the function that is passed in will be a - SyncCrazyflie instance connected to the Crazyflie to operate on. - A list of optional parameters (per Crazyflie) may follow defined by - the args_dict. The dictionary is keyed on URI. - - Example: - def my_function(scf, optional_param0, optional_param1) - ... - - args_dict = { - URI0: [optional_param0_cf0, optional_param1_cf0], - URI1: [optional_param0_cf1, optional_param1_cf1], - ... - } - - - self.sequential(my_function, args_dict) - - :param func: the function to execute - :param args_dict: parameters to pass to the function - """ - for uri, cf in self._cfs.items(): - args = self._process_args_dict(cf, uri, args_dict) - func(*args) - - def parallel(self, func, args_dict=None): - """ - Execute a function for all Crazyflies in the swarm, in parallel. - One thread per Crazyflie is started to execute the function. The - threads are joined at the end. Exceptions raised by the threads are - ignored. - - For a description of the arguments, see sequential() - - :param func: - :param args_dict: - """ - try: - self.parallel_safe(func, args_dict) - except Exception: - pass - - def parallel_safe(self, func, args_dict=None): - """ - Execute a function for all Crazyflies in the swarm, in parallel. - One thread per Crazyflie is started to execute the function. The - threads are joined at the end and if one or more of the threads raised - an exception this function will also raise an exception. - - For a description of the arguments, see sequential() - - :param func: - :param args_dict: - """ - threads = [] - reporter = self.Reporter() - - for uri, scf in self._cfs.items(): - args = [func, reporter] + \ - self._process_args_dict(scf, uri, args_dict) - - thread = Thread(target=self._thread_function_wrapper, args=args) - threads.append(thread) - thread.start() - - for thread in threads: - thread.join() - - if reporter.is_error_reported(): - raise Exception('One or more threads raised an exception when ' - 'executing parallel task') - - def _thread_function_wrapper(self, *args): - try: - func = args[0] - reporter = args[1] - func(*args[2:]) - except Exception: - reporter.report_error() - - def _process_args_dict(self, scf, uri, args_dict): - args = [scf] - - if args_dict: - args += args_dict[uri] - - return args - - class Reporter: - - def __init__(self): - self.error_reported = False - - def report_error(self): - self.error_reported = True - - def is_error_reported(self): - return self.error_reported diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py deleted file mode 100644 index 12dfdcef..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py +++ /dev/null @@ -1,97 +0,0 @@ -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2016 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -The syncronous Crazyflie class is a wrapper around the "normal" Crazyflie -class. It handles the asynchronous nature of the Crazyflie API and turns it -into blocking function. It is useful for simple scripts that performs tasks -as a sequence of events. -""" -from threading import Event - -from cflib.crazyflie import Crazyflie - - -class SyncCrazyflie: - - def __init__(self, link_uri, cf=None): - """ Create a synchronous Crazyflie instance with the specified - link_uri """ - - if cf: - self.cf = cf - else: - self.cf = Crazyflie() - - self._link_uri = link_uri - self._connect_event = Event() - self._is_link_open = False - self._error_message = None - - self.cf.connected.add_callback(self._connected) - self.cf.connection_failed.add_callback(self._connection_failed) - self.cf.disconnected.add_callback(self._disconnected) - - def open_link(self): - if (self.is_link_open()): - raise Exception('Link already open') - - print('Connecting to %s' % self._link_uri) - self.cf.open_link(self._link_uri) - self._connect_event.wait() - if not self._is_link_open: - raise Exception(self._error_message) - - def __enter__(self): - self.open_link() - return self - - def close_link(self): - self.cf.close_link() - self._is_link_open = False - - def __exit__(self, exc_type, exc_val, exc_tb): - self.close_link() - - def is_link_open(self): - return self._is_link_open - - def _connected(self, link_uri): - """ This callback is called form the Crazyflie API when a Crazyflie - has been connected and the TOCs have been downloaded.""" - print('Connected to %s' % link_uri) - self._is_link_open = True - self._connect_event.set() - - def _connection_failed(self, link_uri, msg): - """Callback when connection initial connection fails (i.e no Crazyflie - at the specified address)""" - print('Connection to %s failed: %s' % (link_uri, msg)) - self._is_link_open = False - self._error_message = msg - self._connect_event.set() - - def _disconnected(self, link_uri): - self._is_link_open = False diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncLogger.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncLogger.py deleted file mode 100644 index 3bf6560d..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncLogger.py +++ /dev/null @@ -1,115 +0,0 @@ -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2016 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -This class provides synchronous access to log data from the Crazyflie. - -It acts as an iterator and returns the next value on each iteration. -If no value is available it blocks until log data is available again. -""" -import sys - -from cflib.crazyflie.syncCrazyflie import SyncCrazyflie - -if sys.version_info < (3,): - from Queue import Queue -else: - from queue import Queue - - -class SyncLogger: - DISCONNECT_EVENT = 'DISCONNECT_EVENT' - - def __init__(self, crazyflie, log_config): - """ - Construct an instance of a SyncLogger - - Takes an Crazyflie or SyncCrazyflie instance and a log configuration - """ - if isinstance(crazyflie, SyncCrazyflie): - self._cf = crazyflie.cf - else: - self._cf = crazyflie - - self._log_config = log_config - self._cf.log.add_config(self._log_config) - - self._queue = Queue() - - self._is_connected = False - - def connect(self): - if self._is_connected: - raise Exception('Already connected') - - self._cf.disconnected.add_callback(self._disconnected) - self._log_config.data_received_cb.add_callback(self._log_callback) - self._log_config.start() - - self._is_connected = True - - def disconnect(self): - if self._is_connected: - self._log_config.stop() - self._log_config.delete() - - self._log_config.data_received_cb.remove_callback( - self._log_callback) - self._cf.disconnected.remove_callback(self._disconnected) - - self._queue.empty() - - self._is_connected = False - - def is_connected(self): - return self._is_connected - - def __iter__(self): - return self - - def __next__(self): - if not self._is_connected: - raise StopIteration - - data = self._queue.get() - - if data == self.DISCONNECT_EVENT: - raise StopIteration - - return data - - def __enter__(self): - self.connect() - return self - - def __exit__(self, exc_type, exc_val, exc_tb): - self.disconnect() - - def _log_callback(self, ts, data, logblock): - self._queue.put((ts, data, logblock)) - - def _disconnected(self, link_uri): - self._queue.put(self.DISCONNECT_EVENT) - self.disconnect() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toc.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toc.py deleted file mode 100644 index d722e32a..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toc.py +++ /dev/null @@ -1,189 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -A generic TableOfContents module that is used to fetch, store and minipulate -a TOC for logging or parameters. -""" -import logging -import struct - -from cflib.crtp.crtpstack import CRTPPacket - -__author__ = 'Bitcraze AB' -__all__ = ['Toc', 'TocFetcher'] - -logger = logging.getLogger(__name__) - -TOC_CHANNEL = 0 - -# Commands used when accessing the Table of Contents -CMD_TOC_ELEMENT = 0 -CMD_TOC_INFO = 1 - -# Possible states when receiving TOC -IDLE = 'IDLE' -GET_TOC_INFO = 'GET_TOC_INFO' -GET_TOC_ELEMENT = 'GET_TOC_ELEMENT' - - -class Toc: - """Container for TocElements.""" - - def __init__(self): - self.toc = {} - - def clear(self): - """Clear the TOC""" - self.toc = {} - - def add_element(self, element): - """Add a new TocElement to the TOC container.""" - try: - self.toc[element.group][element.name] = element - except KeyError: - self.toc[element.group] = {} - self.toc[element.group][element.name] = element - - def get_element_by_complete_name(self, complete_name): - """Get a TocElement element identified by complete name from the - container.""" - try: - return self.get_element_by_id(self.get_element_id(complete_name)) - except ValueError: - # Item not found - return None - - def get_element_id(self, complete_name): - """Get the TocElement element id-number of the element with the - supplied name.""" - [group, name] = complete_name.split('.') - element = self.get_element(group, name) - if element: - return element.ident - else: - logger.warning('Unable to find variable [%s]', complete_name) - return None - - def get_element(self, group, name): - """Get a TocElement element identified by name and group from the - container.""" - try: - return self.toc[group][name] - except KeyError: - return None - - def get_element_by_id(self, ident): - """Get a TocElement element identified by index number from the - container.""" - for group in list(self.toc.keys()): - for name in list(self.toc[group].keys()): - if self.toc[group][name].ident == ident: - return self.toc[group][name] - return None - - -class TocFetcher: - """Fetches TOC entries from the Crazyflie""" - - def __init__(self, crazyflie, element_class, port, toc_holder, - finished_callback, toc_cache): - self.cf = crazyflie - self.port = port - self._crc = 0 - self.requested_index = None - self.nbr_of_items = None - self.state = None - self.toc = toc_holder - self._toc_cache = toc_cache - self.finished_callback = finished_callback - self.element_class = element_class - - def start(self): - """Initiate fetching of the TOC.""" - logger.debug('[%d]: Start fetching...', self.port) - # Register callback in this class for the port - self.cf.add_port_callback(self.port, self._new_packet_cb) - - # Request the TOC CRC - self.state = GET_TOC_INFO - pk = CRTPPacket() - pk.set_header(self.port, TOC_CHANNEL) - pk.data = (CMD_TOC_INFO,) - self.cf.send_packet(pk, expected_reply=(CMD_TOC_INFO,)) - - def _toc_fetch_finished(self): - """Callback for when the TOC fetching is finished""" - self.cf.remove_port_callback(self.port, self._new_packet_cb) - logger.debug('[%d]: Done!', self.port) - self.finished_callback() - - def _new_packet_cb(self, packet): - """Handle a newly arrived packet""" - chan = packet.channel - if (chan != 0): - return - payload = packet.data[1:] - - if (self.state == GET_TOC_INFO): - [self.nbr_of_items, self._crc] = struct.unpack('<BI', payload[:5]) - logger.debug('[%d]: Got TOC CRC, %d items and crc=0x%08X', - self.port, self.nbr_of_items, self._crc) - - cache_data = self._toc_cache.fetch(self._crc) - if (cache_data): - self.toc.toc = cache_data - logger.info('TOC for port [%s] found in cache' % self.port) - self._toc_fetch_finished() - else: - self.state = GET_TOC_ELEMENT - self.requested_index = 0 - self._request_toc_element(self.requested_index) - - elif (self.state == GET_TOC_ELEMENT): - # Always add new element, but only request new if it's not the - # last one. - if self.requested_index != payload[0]: - return - self.toc.add_element(self.element_class(payload)) - logger.debug('Added element [%s]', - self.element_class(payload).ident) - if (self.requested_index < (self.nbr_of_items - 1)): - logger.debug('[%d]: More variables, requesting index %d', - self.port, self.requested_index + 1) - self.requested_index = self.requested_index + 1 - self._request_toc_element(self.requested_index) - else: # No more variables in TOC - self._toc_cache.insert(self._crc, self.toc.toc) - self._toc_fetch_finished() - - def _request_toc_element(self, index): - """Request information about a specific item in the TOC""" - logger.debug('Requesting index %d on port %d', index, self.port) - pk = CRTPPacket() - pk.set_header(self.port, TOC_CHANNEL) - pk.data = (CMD_TOC_ELEMENT, index) - self.cf.send_packet(pk, expected_reply=(CMD_TOC_ELEMENT, index)) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toccache.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toccache.py deleted file mode 100644 index 2bd8602d..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toccache.py +++ /dev/null @@ -1,123 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Access the TOC cache for reading/writing. It supports both user -cache and dist cache. -""" -import json -import logging -import os -from glob import glob - -from .log import LogTocElement # noqa -from .param import ParamTocElement # noqa - -__author__ = 'Bitcraze AB' -__all__ = ['TocCache'] - -logger = logging.getLogger(__name__) - - -class TocCache(): - """ - Access to TOC cache. To turn of the cache functionality - don't supply any directories. - """ - - def __init__(self, ro_cache=None, rw_cache=None): - self._cache_files = [] - if (ro_cache): - self._cache_files += glob(ro_cache + '/*.json') - if (rw_cache): - self._cache_files += glob(rw_cache + '/*.json') - if not os.path.exists(rw_cache): - os.makedirs(rw_cache) - - self._rw_cache = rw_cache - - def fetch(self, crc): - """ Try to get a hit in the cache, return None otherwise """ - cache_data = None - pattern = '%08X.json' % crc - hit = None - - for name in self._cache_files: - if (name.endswith(pattern)): - hit = name - - if (hit): - try: - cache = open(hit) - cache_data = json.load(cache, - object_hook=self._decoder) - cache.close() - except Exception as exp: - logger.warning('Error while parsing cache file [%s]:%s', - hit, str(exp)) - - return cache_data - - def insert(self, crc, toc): - """ Save a new cache to file """ - if self._rw_cache: - try: - filename = '%s/%08X.json' % (self._rw_cache, crc) - cache = open(filename, 'w') - cache.write(json.dumps(toc, indent=2, - default=self._encoder)) - cache.close() - logger.info('Saved cache to [%s]', filename) - self._cache_files += [filename] - except Exception as exp: - logger.warning('Could not save cache to file [%s]: %s', - filename, str(exp)) - else: - logger.warning('Could not save cache, no writable directory') - - def _encoder(self, obj): - """ Encode a toc element leaf-node """ - return {'__class__': obj.__class__.__name__, - 'ident': obj.ident, - 'group': obj.group, - 'name': obj.name, - 'ctype': obj.ctype, - 'pytype': obj.pytype, - 'access': obj.access} - raise TypeError(repr(obj) + ' is not JSON serializable') - - def _decoder(self, obj): - """ Decode a toc element leaf-node """ - if '__class__' in obj: - elem = eval(obj['__class__'])() - elem.ident = obj['ident'] - elem.group = str(obj['group']) - elem.name = str(obj['name']) - elem.ctype = str(obj['ctype']) - elem.pytype = str(obj['pytype']) - elem.access = obj['access'] - return elem - return obj diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/__init__.py deleted file mode 100644 index 9f7ce32e..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/__init__.py +++ /dev/null @@ -1,96 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -"""Scans and creates communication interfaces.""" -import logging - -from .debugdriver import DebugDriver -from .exceptions import WrongUriType -from .radiodriver import RadioDriver -from .serialdriver import SerialDriver -from .udpdriver import UdpDriver -from .usbdriver import UsbDriver - -__author__ = 'Bitcraze AB' -__all__ = [] - -logger = logging.getLogger(__name__) - - -DRIVERS = [RadioDriver, SerialDriver, UdpDriver, DebugDriver, UsbDriver] -CLASSES = [] - - -def init_drivers(enable_debug_driver=False): - """Initialize all the drivers.""" - for driver in DRIVERS: - try: - if driver != DebugDriver or enable_debug_driver: - CLASSES.append(driver) - except Exception: # pylint: disable=W0703 - continue - - -def scan_interfaces(address=None): - """ Scan all the interfaces for available Crazyflies """ - available = [] - found = [] - for driverClass in CLASSES: - try: - logger.debug('Scanning: %s', driverClass) - instance = driverClass() - found = instance.scan_interface(address) - available += found - except Exception: - raise - return available - - -def get_interfaces_status(): - """Get the status of all the interfaces""" - status = {} - for driverClass in CLASSES: - try: - instance = driverClass() - status[instance.get_name()] = instance.get_status() - except Exception: - raise - return status - - -def get_link_driver(uri, link_quality_callback=None, link_error_callback=None): - """Return the link driver for the given URI. Returns None if no driver - was found for the URI or the URI was not well formatted for the matching - driver.""" - for driverClass in CLASSES: - try: - instance = driverClass() - instance.connect(uri, link_quality_callback, link_error_callback) - return instance - except WrongUriType: - continue - - return None diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpdriver.py deleted file mode 100644 index 7d9f7d8c..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpdriver.py +++ /dev/null @@ -1,94 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -CRTP Driver main class. -""" - -__author__ = 'Bitcraze AB' -__all__ = ['CRTPDriver'] - - -class CRTPDriver: - """ CTRP Driver main class - - This class in inherited by all the CRTP link drivers. - """ - - def __init__(self): - """Driver constructor. Throw an exception if the driver is unable to - open the URI - """ - self.needs_resending = True - - def connect(self, uri, link_quality_callback, link_error_callback): - """Connect the driver to a specified URI - - @param uri Uri of the link to open - @param link_quality_callback Callback to report link quality in percent - @param link_error_callback Callback to report errors (will result in - disconnection) - """ - - def send_packet(self, pk): - """Send a CRTP packet""" - - def receive_packet(self, wait=0): - """Receive a CRTP packet. - - @param wait The time to wait for a packet in second. -1 means forever - - @return One CRTP packet or None if no packet has been received. - """ - - def get_status(self): - """ - Return a status string from the interface. - """ - - def get_name(self): - """ - Return a human readable name of the interface. - """ - - def scan_interface(self, address=None): - """ - Scan interface for available Crazyflie quadcopters and return a list - with them. - """ - - def enum(self): - """Enumerate, and return a list, of the available link URI on this - system - """ - - def get_help(self): - """return the help message on how to form the URI for this driver - None means no help - """ - - def close(self): - """Close the link""" diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpstack.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpstack.py deleted file mode 100644 index dca9e67f..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpstack.py +++ /dev/null @@ -1,152 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -CRTP packet and ports. -""" -import logging -import sys - -__author__ = 'Bitcraze AB' -__all__ = ['CRTPPort', 'CRTPPacket'] - -logger = logging.getLogger(__name__) - - -class CRTPPort: - """ - Lists the available ports for the CRTP. - """ - CONSOLE = 0x00 - PARAM = 0x02 - COMMANDER = 0x03 - MEM = 0x04 - LOGGING = 0x05 - LOCALIZATION = 0x06 - COMMANDER_GENERIC = 0x07 - PLATFORM = 0x0D - DEBUGDRIVER = 0x0E - LINKCTRL = 0x0F - ALL = 0xFF - - -class CRTPPacket(object): - """ - A packet that can be sent via the CRTP. - """ - - def __init__(self, header=0, data=None): - """ - Create an empty packet with default values. - """ - self.size = 0 - self._data = bytearray() - # The two bits in position 3 and 4 needs to be set for legacy - # support of the bootloader - self.header = header | 0x3 << 2 - self._port = (header & 0xF0) >> 4 - self._channel = header & 0x03 - if data: - self._set_data(data) - - def _get_channel(self): - """Get the packet channel""" - return self._channel - - def _set_channel(self, channel): - """Set the packet channel""" - self._channel = channel - self._update_header() - - def _get_port(self): - """Get the packet port""" - return self._port - - def _set_port(self, port): - """Set the packet port""" - self._port = port - self._update_header() - - def get_header(self): - """Get the header""" - self._update_header() - return self.header - - def set_header(self, port, channel): - """ - Set the port and channel for this packet. - """ - self._port = port - self.channel = channel - self._update_header() - - def _update_header(self): - """Update the header with the port/channel values""" - # The two bits in position 3 and 4 needs to be set for legacy - # support of the bootloader - self.header = ((self._port & 0x0f) << 4 | 3 << 2 | - (self.channel & 0x03)) - - # Some python madness to access different format of the data - def _get_data(self): - """Get the packet data""" - return self._data - - def _set_data(self, data): - """Set the packet data""" - if type(data) == bytearray: - self._data = data - elif type(data) == str: - if sys.version_info < (3,): - self._data = bytearray(data) - else: - self._data = bytearray(data.encode('ISO-8859-1')) - elif type(data) == list or type(data) == tuple: - self._data = bytearray(data) - elif sys.version_info >= (3,) and type(data) == bytes: - self._data = bytearray(data) - else: - raise Exception('Data must be bytearray, string, list or tuple,' - ' not {}'.format(type(data))) - - def _get_data_l(self): - """Get the data in the packet as a list""" - return list(self._get_data_t()) - - def _get_data_t(self): - """Get the data in the packet as a tuple""" - return tuple(self._data) - - def __str__(self): - """Get a string representation of the packet""" - return '{}:{} {}'.format(self._port, self.channel, self.datat) - - data = property(_get_data, _set_data) - datal = property(_get_data_l, _set_data) - datat = property(_get_data_t, _set_data) - datas = property(_get_data, _set_data) - port = property(_get_port, _set_port) - channel = property(_get_channel, _set_channel) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/debugdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/debugdriver.py deleted file mode 100644 index 86e8b3db..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/debugdriver.py +++ /dev/null @@ -1,897 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Fake link driver used to debug the UI without using the Crazyflie. - -The operation of this driver can be controlled in two ways, either by -connecting to different URIs or by sending messages to the DebugDriver port -though CRTP once connected. - -For normal connections a console thread is also started that will send -generated console output via CRTP. -""" -import errno -import logging -import random -import re -import string -import struct -import sys -import time -from datetime import datetime -from threading import Thread - -from .crtpdriver import CRTPDriver -from .crtpstack import CRTPPacket -from .crtpstack import CRTPPort -from .exceptions import WrongUriType -from cflib.crazyflie.log import LogTocElement -from cflib.crazyflie.param import ParamTocElement -if sys.version_info < (3,): - import Queue as queue -else: - import queue - -__author__ = 'Bitcraze AB' -__all__ = ['DebugDriver'] - -logger = logging.getLogger(__name__) - -# This setup is used to debug raw memory logging -memlogging = {0x01: {'min': 0, 'max': 255, 'mod': 1, 'vartype': 1}, - 0x02: {'min': 0, 'max': 65000, 'mod': 100, 'vartype': 2}, - 0x03: {'min': 0, 'max': 100000, 'mod': 1000, 'vartype': 3}, - 0x04: {'min': -100, 'max': 100, 'mod': 1, 'vartype': 4}, - 0x05: {'min': -10000, 'max': 10000, 'mod': 2000, 'vartype': 5}, - 0x06: {'min': -50000, 'max': 50000, 'mod': 1000, 'vartype': 6}, - 0x07: {'min': 0, 'max': 255, 'mod': 1, 'vartype': 1}} - - -class FakeMemory: - TYPE_I2C = 0 - TYPE_1W = 1 - - def __init__(self, type, size, addr, data=None): - self.type = type - self.size = size - self.addr = addr - self.data = [0] * size - if data: - for i in range(len(data)): - self.data[i] = data[i] - - def erase(self): - self.data = [0] * self.size - - -class DebugDriver(CRTPDriver): - """ Debug driver used for debugging UI/communication without using a - Crazyflie""" - - def __init__(self): - self.fakeLoggingThreads = [] - self._fake_mems = [] - self.needs_resending = False - # Fill up the fake logging TOC with values and data - self.fakeLogToc = [] - self.fakeLogToc.append({'varid': 0, 'vartype': 5, 'vargroup': 'imu', - 'varname': 'gyro_x', 'min': -10000, - 'max': 10000, 'mod': 1000}) - self.fakeLogToc.append({'varid': 1, 'vartype': 5, 'vargroup': 'imu', - 'varname': 'gyro_y', 'min': -10000, - 'max': 10000, 'mod': 150}) - self.fakeLogToc.append({'varid': 2, 'vartype': 5, 'vargroup': 'imu', - 'varname': 'gyro_z', 'min': -10000, - 'max': 10000, 'mod': 200}) - self.fakeLogToc.append({'varid': 3, 'vartype': 5, 'vargroup': 'imu', - 'varname': 'acc_x', 'min': -1000, - 'max': 1000, 'mod': 15}) - self.fakeLogToc.append({'varid': 4, 'vartype': 5, 'vargroup': 'imu', - 'varname': 'acc_y', 'min': -1000, - 'max': 1000, 'mod': 10}) - self.fakeLogToc.append({'varid': 5, 'vartype': 5, 'vargroup': 'imu', - 'varname': 'acc_z', 'min': -1000, - 'max': 1000, 'mod': 20}) - self.fakeLogToc.append({'varid': 6, 'vartype': 7, - 'vargroup': 'stabilizer', 'varname': 'roll', - 'min': -90, 'max': 90, 'mod': 2}) - self.fakeLogToc.append({'varid': 7, 'vartype': 7, - 'vargroup': 'stabilizer', 'varname': 'pitch', - 'min': -90, 'max': 90, 'mod': 1.5}) - self.fakeLogToc.append({'varid': 8, 'vartype': 7, - 'vargroup': 'stabilizer', 'varname': 'yaw', - 'min': -90, 'max': 90, 'mod': 2.5}) - self.fakeLogToc.append({'varid': 9, 'vartype': 7, 'vargroup': 'pm', - 'varname': 'vbat', 'min': 3.0, - 'max': 4.2, 'mod': 0.1}) - self.fakeLogToc.append({'varid': 10, 'vartype': 6, 'vargroup': 'motor', - 'varname': 'm1', 'min': 0, 'max': 65000, - 'mod': 1000}) - self.fakeLogToc.append({'varid': 11, 'vartype': 6, 'vargroup': 'motor', - 'varname': 'm2', 'min': 0, 'max': 65000, - 'mod': 1000}) - self.fakeLogToc.append({'varid': 12, 'vartype': 6, 'vargroup': 'motor', - 'varname': 'm3', 'min': 0, 'max': 65000, - 'mod': 1000}) - self.fakeLogToc.append({'varid': 13, 'vartype': 6, 'vargroup': 'motor', - 'varname': 'm4', 'min': 0, 'max': 65000, - 'mod': 1000}) - self.fakeLogToc.append({'varid': 14, 'vartype': 2, - 'vargroup': 'stabilizer', 'varname': 'thrust', - 'min': 0, 'max': 65000, 'mod': 1000}) - self.fakeLogToc.append({'varid': 15, 'vartype': 7, - 'vargroup': 'baro', 'varname': 'asl', - 'min': 540, 'max': 545, 'mod': 0.5}) - self.fakeLogToc.append({'varid': 16, 'vartype': 7, - 'vargroup': 'baro', 'varname': 'aslRaw', - 'min': 540, 'max': 545, 'mod': 1.0}) - self.fakeLogToc.append({'varid': 17, 'vartype': 7, - 'vargroup': 'posEstimatorAlt', - 'varname': 'estimatedZ', - 'min': 540, 'max': 545, 'mod': 0.5}) - self.fakeLogToc.append({'varid': 18, 'vartype': 7, - 'vargroup': 'baro', 'varname': 'temp', - 'min': 26, 'max': 38, 'mod': 1.0}) - self.fakeLogToc.append({'varid': 19, 'vartype': 7, - 'vargroup': 'posCtlAlt', - 'varname': 'targetZ', - 'min': 542, 'max': 543, 'mod': 0.1}) - self.fakeLogToc.append({'varid': 20, 'vartype': 6, - 'vargroup': 'gps', 'varname': 'lat', - 'min': 556112190, 'max': 556112790, - 'mod': 10}) - self.fakeLogToc.append({'varid': 21, 'vartype': 6, - 'vargroup': 'gps', 'varname': 'lon', - 'min': 129945110, 'max': 129945710, - 'mod': 10}) - self.fakeLogToc.append({'varid': 22, 'vartype': 6, - 'vargroup': 'gps', 'varname': 'hMSL', - 'min': 0, 'max': 100000, - 'mod': 1000}) - self.fakeLogToc.append({'varid': 23, 'vartype': 6, - 'vargroup': 'gps', 'varname': 'heading', - 'min': -10000000, 'max': 10000000, - 'mod': 100000}) - self.fakeLogToc.append({'varid': 24, 'vartype': 6, - 'vargroup': 'gps', 'varname': 'gSpeed', - 'min': 0, 'max': 1000, - 'mod': 100}) - self.fakeLogToc.append({'varid': 25, 'vartype': 3, - 'vargroup': 'gps', 'varname': 'hAcc', - 'min': 0, 'max': 5000, - 'mod': 100}) - self.fakeLogToc.append({'varid': 26, 'vartype': 1, - 'vargroup': 'gps', 'varname': 'fixType', - 'min': 0, 'max': 5, - 'mod': 1}) - - # Fill up the fake logging TOC with values and data - self.fakeParamToc = [] - self.fakeParamToc.append({'varid': 0, 'vartype': 0x08, - 'vargroup': 'blah', 'varname': 'p', - 'writable': True, 'value': 100}) - self.fakeParamToc.append({'varid': 1, 'vartype': 0x0A, - 'vargroup': 'info', 'varname': 'cid', - 'writable': False, 'value': 1234}) - self.fakeParamToc.append({'varid': 2, 'vartype': 0x06, - 'vargroup': 'rpid', 'varname': 'prp', - 'writable': True, 'value': 1.5}) - self.fakeParamToc.append({'varid': 3, 'vartype': 0x06, - 'vargroup': 'rpid', 'varname': 'pyaw', - 'writable': True, 'value': 2.5}) - self.fakeParamToc.append({'varid': 4, 'vartype': 0x06, - 'vargroup': 'rpid', 'varname': 'irp', - 'writable': True, 'value': 3.5}) - self.fakeParamToc.append({'varid': 5, 'vartype': 0x06, - 'vargroup': 'rpid', 'varname': 'iyaw', - 'writable': True, 'value': 4.5}) - self.fakeParamToc.append({'varid': 6, 'vartype': 0x06, - 'vargroup': 'pid_attitude', - 'varname': 'pitch_kd', 'writable': True, - 'value': 5.5}) - self.fakeParamToc.append({'varid': 7, 'vartype': 0x06, - 'vargroup': 'rpid', 'varname': 'dyaw', - 'writable': True, 'value': 6.5}) - self.fakeParamToc.append({'varid': 8, 'vartype': 0x06, - 'vargroup': 'apid', 'varname': 'prp', - 'writable': True, 'value': 7.5}) - self.fakeParamToc.append({'varid': 9, 'vartype': 0x06, - 'vargroup': 'apid', 'varname': 'pyaw', - 'writable': True, 'value': 8.5}) - self.fakeParamToc.append({'varid': 10, 'vartype': 0x06, - 'vargroup': 'apid', 'varname': 'irp', - 'writable': True, 'value': 9.5}) - self.fakeParamToc.append({'varid': 11, 'vartype': 0x06, - 'vargroup': 'apid', 'varname': 'iyaw', - 'writable': True, 'value': 10.5}) - self.fakeParamToc.append({'varid': 12, 'vartype': 0x06, - 'vargroup': 'apid', 'varname': 'drp', - 'writable': True, 'value': 11.5}) - self.fakeParamToc.append({'varid': 13, 'vartype': 0x06, - 'vargroup': 'apid', 'varname': 'dyaw', - 'writable': True, 'value': 12.5}) - self.fakeParamToc.append({'varid': 14, 'vartype': 0x08, - 'vargroup': 'flightctrl', - 'varname': 'xmode', 'writable': True, - 'value': 1}) - self.fakeParamToc.append({'varid': 15, 'vartype': 0x08, - 'vargroup': 'flightctrl', - 'varname': 'ratepid', 'writable': True, - 'value': 1}) - self.fakeParamToc.append({'varid': 16, 'vartype': 0x08, - 'vargroup': 'imu_sensors', - 'varname': 'HMC5883L', 'writable': False, - 'value': 1}) - self.fakeParamToc.append({'varid': 17, 'vartype': 0x08, - 'vargroup': 'imu_sensors', - 'varname': 'MS5611', 'writable': False, - 'value': 1}) - self.fakeParamToc.append({'varid': 18, 'vartype': 0x0A, - 'vargroup': 'firmware', - 'varname': 'revision0', 'writable': False, - 'value': 0xdeb}) - self.fakeParamToc.append({'varid': 19, 'vartype': 0x09, - 'vargroup': 'firmware', - 'varname': 'revision1', 'writable': False, - 'value': 0x99}) - self.fakeParamToc.append({'varid': 20, 'vartype': 0x08, - 'vargroup': 'firmware', - 'varname': 'modified', 'writable': False, - 'value': 1}) - self.fakeParamToc.append({'varid': 21, 'vartype': 0x08, - 'vargroup': 'imu_tests', - 'varname': 'MPU6050', 'writable': False, - 'value': 1}) - self.fakeParamToc.append({'varid': 22, 'vartype': 0x08, - 'vargroup': 'imu_tests', - 'varname': 'HMC5883L', 'writable': False, - 'value': 1}) - self.fakeParamToc.append({'varid': 23, 'vartype': 0x08, - 'vargroup': 'imu_tests', - 'varname': 'MS5611', 'writable': False, - 'value': 1}) - - self.fakeflash = {} - self._random_answer_delay = True - self.queue = queue.Queue() - self._packet_handler = _PacketHandlingThread(self.queue, - self.fakeLogToc, - self.fakeParamToc, - self._fake_mems) - self._packet_handler.start() - - def scan_interface(self, address): - return [['debug://0/0', 'Normal connection'], - ['debug://0/1', 'Fail to connect'], - ['debug://0/2', 'Incomplete log TOC download'], - ['debug://0/3', 'Insert random delays on replies'], - ['debug://0/4', - 'Insert random delays on replies and random TOC CRCs'], - ['debug://0/5', 'Normal but random TOC CRCs'], - ['debug://0/6', 'Normal but empty I2C and OW mems']] - - def get_status(self): - return 'Ok' - - def get_name(self): - return 'debug' - - def connect(self, uri, linkQualityCallback, linkErrorCallback): - - if not re.search('^debug://', uri): - raise WrongUriType('Not a debug URI') - - self._packet_handler.linkErrorCallback = linkErrorCallback - self._packet_handler.linkQualityCallback = linkQualityCallback - - # Debug-options for this driver that - # is set by using different connection URIs - self._packet_handler.inhibitAnswers = False - self._packet_handler.doIncompleteLogTOC = False - self._packet_handler.bootloader = False - self._packet_handler._random_answer_delay = False - self._packet_handler._random_toc_crcs = False - - if (re.search('^debug://.*/1\Z', uri)): - self._packet_handler.inhibitAnswers = True - if (re.search('^debug://.*/110\Z', uri)): - self._packet_handler.bootloader = True - if (re.search('^debug://.*/2\Z', uri)): - self._packet_handler.doIncompleteLogTOC = True - if (re.search('^debug://.*/3\Z', uri)): - self._packet_handler._random_answer_delay = True - if (re.search('^debug://.*/4\Z', uri)): - self._packet_handler._random_answer_delay = True - self._packet_handler._random_toc_crcs = True - if (re.search('^debug://.*/5\Z', uri)): - self._packet_handler._random_toc_crcs = True - - if len(self._fake_mems) == 0: - # Add empty EEPROM - self._fake_mems.append(FakeMemory(type=0, size=100, addr=0)) - # Add EEPROM with settings - self._fake_mems.append( - FakeMemory(type=0, size=100, addr=0, - data=[48, 120, 66, 67, 1, 8, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 231, 8, 231, 231, 231, 218])) - # Add 1-wire memory with settings for LED-ring - self._fake_mems.append( - FakeMemory(type=1, size=112, addr=0x1234567890ABCDEF, - data=[0xeb, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, - 0x44, 0x00, 0x0e, - 0x01, 0x09, 0x62, 0x63, 0x4c, 0x65, 0x64, - 0x52, 0x69, 0x6e, - 0x67, 0x02, 0x01, 0x62, 0x55])) - # Add 1-wire memory with settings for LED-ring but bad CRC - self._fake_mems.append( - FakeMemory(type=1, size=112, addr=0x1234567890ABCDEF, - data=[0xeb, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, - 0x44, 0x00, 0x0e, - 0x01, 0x09, 0x62, 0x63, 0x4c, 0x65, 0x64, - 0x52, 0x69, 0x6e, - 0x67, 0x02, 0x01, 0x62, 0x56])) - # Add empty 1-wire memory - self._fake_mems.append( - FakeMemory(type=1, size=112, addr=0x1234567890ABCDEE, - data=[0x00 for a in range(112)])) - - if (re.search('^debug://.*/6\Z', uri)): - logger.info('------------->Erasing memories on connect') - for m in self._fake_mems: - m.erase() - - self.fakeConsoleThread = None - - if (not self._packet_handler.inhibitAnswers and - not self._packet_handler.bootloader): - self.fakeConsoleThread = FakeConsoleThread(self.queue) - self.fakeConsoleThread.start() - - if (self._packet_handler.linkQualityCallback is not None): - self._packet_handler.linkQualityCallback(0) - - def receive_packet(self, time=0): - if time == 0: - try: - return self.queue.get(False) - except queue.Empty: - return None - elif time < 0: - try: - return self.queue.get(True) - except queue.Empty: - return None - else: - try: - return self.queue.get(True, time) - except queue.Empty: - return None - - def send_packet(self, pk): - self._packet_handler.handle_packet(pk) - - def close(self): - logger.info('Closing debugdriver') - for f in self._packet_handler.fakeLoggingThreads: - f.stop() - if self.fakeConsoleThread: - self.fakeConsoleThread.stop() - - -class _PacketHandlingThread(Thread): - """Thread for handling packets asynchronously""" - - def __init__(self, out_queue, fake_log_toc, fake_param_toc, fake_mems): - Thread.__init__(self) - self.setDaemon(True) - self.queue = out_queue - self.fakeLogToc = fake_log_toc - self.fakeParamToc = fake_param_toc - self._fake_mems = fake_mems - self._in_queue = queue.Queue() - - self.inhibitAnswers = False - self.doIncompleteLogTOC = False - self.bootloader = False - self._random_answer_delay = False - self._random_toc_crcs = False - - self.linkErrorCallback = None - self.linkQualityCallback = None - random.seed(None) - self.fakeLoggingThreads = [] - - self._added_blocks = [] - - self.nowAnswerCounter = 4 - - def handle_packet(self, pk): - self._in_queue.put(pk) - - def run(self): - while (True): - pk = self._in_queue.get(True) - if (self.inhibitAnswers): - self.nowAnswerCounter = self.nowAnswerCounter - 1 - logger.debug( - 'Not answering with any data, will send link errori' - ' in %d retries', self.nowAnswerCounter) - if (self.nowAnswerCounter == 0): - self.linkErrorCallback('Nothing is answering, and it' - " shouldn't") - else: - if (pk.port == 0xFF): - self._handle_bootloader(pk) - elif (pk.port == CRTPPort.DEBUGDRIVER): - self._handle_debugmessage(pk) - elif (pk.port == CRTPPort.COMMANDER): - pass - elif (pk.port == CRTPPort.LOGGING): - self._handle_logging(pk) - elif (pk.port == CRTPPort.PARAM): - self.handleParam(pk) - elif (pk.port == CRTPPort.MEM): - self._handle_mem_access(pk) - else: - logger.warning( - 'Not handling incoming packets on port [%d]', - pk.port) - - def _handle_mem_access(self, pk): - chan = pk.channel - cmd = pk.data[0] - payload = pk.data[1:] - - if chan == 0: # Info channel - p_out = CRTPPacket() - p_out.set_header(CRTPPort.MEM, 0) - if cmd == 1: # Request number of memories - p_out.data = (1, len(self._fake_mems)) - if cmd == 2: - id = payload[0] - logger.info('Getting mem {}'.format(id)) - m = self._fake_mems[id] - p_out.data = struct.pack( - '<BBBIQ', 2, id, m.type, m.size, m.addr) - self._send_packet(p_out) - - if chan == 1: # Read channel - id = cmd - addr = struct.unpack('I', payload[0:4])[0] - length = payload[4] - status = 0 - logger.info('MEM: Read {}bytes at 0x{:X} from memory {}'.format( - length, addr, id)) - m = self._fake_mems[id] - p_out = CRTPPacket() - p_out.set_header(CRTPPort.MEM, 1) - p_out.data = struct.pack('<BIB', id, addr, status) - p_out.data += struct.pack('B' * length, - *m.data[addr:addr + length]) - self._send_packet(p_out) - - if chan == 2: # Write channel - id = cmd - addr = struct.unpack('I', payload[0:4])[0] - data = payload[4:] - logger.info('MEM: Write {}bytes at 0x{:X} to memory {}'.format( - len(data), addr, id)) - m = self._fake_mems[id] - - for i in range(len(data)): - m.data[addr + i] = data[i] - - status = 0 - - p_out = CRTPPacket() - p_out.set_header(CRTPPort.MEM, 2) - p_out.data = struct.pack('<BIB', id, addr, status) - self._send_packet(p_out) - - def _handle_bootloader(self, pk): - cmd = pk.data[1] - if (cmd == 0x10): # Request info about copter - p = CRTPPacket() - p.set_header(0xFF, 0xFF) - pageSize = 1024 - buffPages = 10 - flashPages = 100 - flashStart = 1 - p.data = struct.pack('<BBHHHH', 0xFF, 0x10, pageSize, buffPages, - flashPages, flashStart) - p.data += struct.pack('B' * 12, 0xA0A1A2A3A4A5) - self._send_packet(p) - logging.info('Bootloader: Sending info back info') - elif (cmd == 0x14): # Upload buffer - [page, addr] = struct.unpack('<HH', p.data[0:4]) - elif (cmd == 0x18): # Flash page - p = CRTPPacket() - p.set_header(0xFF, 0xFF) - p.data = struct.pack('<BBH', 0xFF, 0x18, 1) - self._send_packet(p) - elif (cmd == 0xFF): # Reset to firmware - logger.info('Bootloader: Got reset command') - else: - logger.warning('Bootloader: Unknown command 0x%02X', cmd) - - def _handle_debugmessage(self, pk): - if (pk.channel == 0): - cmd = struct.unpack('B', pk.data[0])[0] - if (cmd == 0): # Fake link quality - newLinkQuality = struct.unpack('B', pk.data[1])[0] - self.linkQualityCallback(newLinkQuality) - elif (cmd == 1): - self.linkErrorCallback('DebugDriver was forced to disconnect!') - else: - logger.warning('Debug port: Not handling cmd=%d on channel 0', - cmd) - else: - logger.warning('Debug port: Not handling channel=%d', - pk.channel) - - def _handle_toc_access(self, pk): - chan = pk.channel - cmd = pk.data[0] - logger.info('TOC access on port %d', pk.port) - if (chan == 0): # TOC Access - cmd = pk.data[0] - if (cmd == 0): # Reqest variable info - p = CRTPPacket() - p.set_header(pk.port, 0) - varIndex = 0 - if (len(pk.data) > 1): - varIndex = pk.data[1] - logger.debug('TOC[%d]: Requesting ID=%d', pk.port, - varIndex) - else: - logger.debug('TOC[%d]: Requesting first index..surprise,' - ' it 0 !', pk.port) - - if (pk.port == CRTPPort.LOGGING): - l = self.fakeLogToc[varIndex] - if (pk.port == CRTPPort.PARAM): - l = self.fakeParamToc[varIndex] - - vartype = l['vartype'] - if (pk.port == CRTPPort.PARAM and l['writable'] is True): - vartype = vartype | (0x10) - - p.data = struct.pack('<BBB', cmd, l['varid'], vartype) - for ch in l['vargroup']: - p.data.append(ord(ch)) - p.data.append(0) - for ch in l['varname']: - p.data.append(ord(ch)) - p.data.append(0) - if (self.doIncompleteLogTOC is False): - self._send_packet(p) - elif (varIndex < 5): - self._send_packet(p) - else: - logger.info('TOC: Doing incomplete TOC, stopping after' - ' varIndex => 5') - - if (cmd == 1): # TOC CRC32 request - fakecrc = 0 - if (pk.port == CRTPPort.LOGGING): - tocLen = len(self.fakeLogToc) - fakecrc = 0xAAAAAAAA - if (pk.port == CRTPPort.PARAM): - tocLen = len(self.fakeParamToc) - fakecrc = 0xBBBBBBBB - - if self._random_toc_crcs: - fakecrc = int(''.join( - random.choice('ABCDEF' + string.digits) for x in - range(8)), 16) - logger.debug('Generated random TOC CRC: 0x%x', fakecrc) - logger.info('TOC[%d]: Requesting TOC CRC, sending back fake' - ' stuff: %d', pk.port, len(self.fakeLogToc)) - p = CRTPPacket() - p.set_header(pk.port, 0) - p.data = struct.pack('<BBIBB', 1, tocLen, fakecrc, 16, 24) - self._send_packet(p) - - def handleParam(self, pk): - chan = pk.channel - cmd = pk.data[0] - logger.debug('PARAM: Port=%d, Chan=%d, cmd=%d', pk.port, - chan, cmd) - if (chan == 0): # TOC Access - self._handle_toc_access(pk) - elif (chan == 2): # Settings access - varId = pk.data[0] - formatStr = ParamTocElement.types[ - self.fakeParamToc[varId]['vartype']][1] - newvalue = struct.unpack(formatStr, pk.data[1:])[0] - self.fakeParamToc[varId]['value'] = newvalue - logger.info('PARAM: New value [%s] for param [%d]', newvalue, - varId) - # Send back the new value - p = CRTPPacket() - p.set_header(pk.port, 2) - p.data += struct.pack('<B', varId) - p.data += struct.pack(formatStr, self.fakeParamToc[varId]['value']) - self._send_packet(p) - elif (chan == 1): - p = CRTPPacket() - p.set_header(pk.port, 1) - varId = cmd - p.data.append(varId) - formatStr = ParamTocElement.types[ - self.fakeParamToc[varId]['vartype']][1] - p.data += struct.pack(formatStr, self.fakeParamToc[varId]['value']) - logger.info('PARAM: Getting value for %d', varId) - self._send_packet(p) - - def _handle_logging(self, pk): - chan = pk.channel - cmd = pk.data[0] - logger.debug('LOG: Chan=%d, cmd=%d', chan, cmd) - if (chan == 0): # TOC Access - self._handle_toc_access(pk) - elif (chan == 1): # Settings access - if (cmd == 0): - blockId = pk.data[1] - if blockId not in self._added_blocks: - self._added_blocks.append(blockId) - logger.info('LOG:Adding block id=%d', blockId) - listofvars = pk.data[3:] - fakeThread = _FakeLoggingDataThread(self.queue, blockId, - listofvars, - self.fakeLogToc) - self.fakeLoggingThreads.append(fakeThread) - fakeThread.start() - # Anser that everything is ok - p = CRTPPacket() - p.set_header(5, 1) - p.data = struct.pack('<BBB', 0, blockId, 0x00) - self._send_packet(p) - else: - p = CRTPPacket() - p.set_header(5, 1) - p.data = struct.pack('<BBB', 0, blockId, errno.EEXIST) - self._send_packet(p) - if (cmd == 1): - logger.warning('LOG: Appending block not implemented!') - if (cmd == 2): - blockId = pk.data[1] - logger.info('LOG: Should delete block %d', blockId) - success = False - for fb in self.fakeLoggingThreads: - if (fb.blockId == blockId): - fb._disable_logging() - fb.stop() - - p = CRTPPacket() - p.set_header(5, 1) - p.data = struct.pack('<BBB', cmd, blockId, 0x00) - self._send_packet(p) - logger.info('LOG: Deleted block=%d', blockId) - success = True - if (success is False): - logger.warning('LOG: Could not delete block=%d, not found', - blockId) - # TODO: Send back error code - - if (cmd == 3): - blockId = pk.data[1] - period = pk.data[2] * 10 # Sent as multiple of 10 ms - logger.info('LOG:Starting block %d', blockId) - success = False - for fb in self.fakeLoggingThreads: - if (fb.blockId == blockId): - fb._enable_logging() - fb.period = period - p = CRTPPacket() - p.set_header(5, 1) - p.data = struct.pack('<BBB', cmd, blockId, 0x00) - self._send_packet(p) - logger.info('LOG:Started block=%d', blockId) - success = True - if (success is False): - logger.info('LOG:Could not start block=%d, not found', - blockId) - # TODO: Send back error code - if (cmd == 4): - blockId = pk.data[1] - logger.info('LOG:Pausing block %d', blockId) - success = False - for fb in self.fakeLoggingThreads: - if (fb.blockId == blockId): - fb._disable_logging() - p = CRTPPacket() - p.set_header(5, 1) - p.data = struct.pack('<BBB', cmd, blockId, 0x00) - self._send_packet(p) - logger.info('LOG:Pause block=%d', blockId) - success = True - if (success is False): - logger.warning('LOG:Could not pause block=%d, not found', - blockId) - # TODO: Send back error code - if (cmd == 5): - logger.info('LOG: Reset logging, but doing nothing') - p = CRTPPacket() - p.set_header(5, 1) - p.data = struct.pack('<BBB', cmd, 0x00, 0x00) - self._send_packet(p) - - elif (chan > 1): - logger.warning('LOG: Uplink packets with channels > 1 not' - ' supported!') - - def _send_packet(self, pk): - # Do not delay log data - if (self._random_answer_delay and pk.port != 0x05 and - pk.channel != 0x02): - # Calculate a delay between 0ms and 250ms - delay = random.randint(0, 250) / 1000.0 - logger.debug('Delaying answer %.2fms', delay * 1000) - time.sleep(delay) - self.queue.put(pk) - - -class _FakeLoggingDataThread(Thread): - """Thread that will send back fake logging data via CRTP""" - - def __init__(self, outQueue, blockId, listofvars, fakeLogToc): - Thread.__init__(self) - self.starttime = datetime.now() - self.outQueue = outQueue - self.setDaemon(True) - self.mod = 0 - self.blockId = blockId - self.period = 0 - self.listofvars = listofvars - self.shouldLog = False - self.fakeLogToc = fakeLogToc - self.fakeLoggingData = [] - self.setName('Fakelog block=%d' % blockId) - self.shouldQuit = False - - logging.info('FakeDataLoggingThread created for blockid=%d', blockId) - i = 0 - while (i < len(listofvars)): - varType = listofvars[i] - var_stored_as = (varType >> 8) - var_fetch_as = (varType & 0xFF) - if (var_stored_as > 0): - addr = struct.unpack('<I', listofvars[i + 1:i + 5]) - logger.debug('FakeLoggingThread: We should log a memory addr' - ' 0x%04X', addr) - self.fakeLoggingData.append([memlogging[var_fetch_as], - memlogging[var_fetch_as]['min'], - 1]) - i = i + 5 - else: - varId = listofvars[i] - logger.debug('FakeLoggingThread: We should log variable from' - ' TOC: id=%d, type=0x%02X', varId, varType) - for t in self.fakeLogToc: - if (varId == t['varid']): - # Each touple will have var data and current fake value - self.fakeLoggingData.append([t, t['min'], 1]) - i = i + 2 - - def _enable_logging(self): - self.shouldLog = True - logging.info('_FakeLoggingDataThread: Enable thread [%s] at period %d', - self.getName(), self.period) - - def _disable_logging(self): - self.shouldLog = False - logging.info('_FakeLoggingDataThread: Disable thread [%s]', - self.getName()) - - def stop(self): - self.shouldQuit = True - - def run(self): - while (self.shouldQuit is False): - if (self.shouldLog is True): - - p = CRTPPacket() - p.set_header(5, 2) - p.data = struct.pack('<B', self.blockId) - timestamp = int( - (datetime.now() - self.starttime).total_seconds() * 1000) - p.data += struct.pack('BBB', timestamp & 0xff, - (timestamp >> 8) & 0x0ff, - (timestamp >> 16) & 0x0ff) # Timestamp - - for d in self.fakeLoggingData: - # Set new value - d[1] = d[1] + d[0]['mod'] * d[2] - # Obej the limitations - if (d[1] > d[0]['max']): - d[1] = d[0]['max'] # Limit value - d[2] = -1 # Switch direction - if (d[1] < d[0]['min']): - d[1] = d[0]['min'] # Limit value - d[2] = 1 # Switch direction - # Pack value - formatStr = LogTocElement.types[d[0]['vartype']][1] - p.data += struct.pack(formatStr, d[1]) - self.outQueue.put(p) - time.sleep(self.period / 1000.0) # Period in ms here - - -class FakeConsoleThread(Thread): - """Thread that will send back fake console data via CRTP""" - - def __init__(self, outQueue): - Thread.__init__(self) - self.outQueue = outQueue - self.setDaemon(True) - self._should_run = True - - def stop(self): - self._shoud_run = False - - def run(self): - # Temporary hack to test GPS from firmware by sending NMEA string - # on console - long_val = 0 - lat_val = 0 - alt_val = 0 - - while (self._should_run): - long_val += 1 - lat_val += 1 - alt_val += 1.0 - - long_string = '5536.677%d' % (long_val % 99) - lat_string = '01259.645%d' % (lat_val % 99) - alt_string = '%.1f' % (alt_val % 100.0) - - # Copy of what is sent from the module, but note that only - # the GPGGA message is being simulated, the others are fixed... - self._send_text('Time is now %s\n' % datetime.now()) - self._send_text('$GPVTG,,T,,M,0.386,N,0.716,K,A*2E\n') - self._send_text('$GPGGA,135544.0') - self._send_text('0,%s,N,%s,E,1,04,2.62,3.6,M,%s,M,,*58\n' % ( - long_string, lat_string, alt_string)) - self._send_text( - '$GPGSA,A,3,31,20,23,07,,,,,,,,,3.02,2.62,1.52*05\n') - self._send_text('$GPGSV,2,1,07,07,09,181,15,13,63,219,26,16,02,' - '097,,17,05,233,20*7E\n') - self._send_text( - '$GPGSV,2,2,07,20,42,119,35,23,77,097,27,31,12,032,19*47\n') - self._send_text( - '$GPGLL,5536.67734,N,01259.64578,E,135544.00,A,A*68\n') - - time.sleep(2) - - def _send_text(self, message): - p = CRTPPacket() - p.set_header(0, 0) - - # This might be done prettier ;-) - p.data = message - - self.outQueue.put(p) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/exceptions.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/exceptions.py deleted file mode 100644 index 9ccb6af6..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/exceptions.py +++ /dev/null @@ -1,45 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Exception used when the URI is not for the current driver -(ie. radio:// for the serial driver ...) -It basically means that an other driver could do the job -It does NOT means that the URI is good or bad -""" - -__author__ = 'Bitcraze AB' -__all__ = ['WrongUriType', 'CommunicationException'] - - -class WrongUriType(Exception): - """ Wrong type of URI for this interface """ - pass - - -class CommunicationException(Exception): - """ Communication problem when communicating with a Crazyflie """ - pass diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/radiodriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/radiodriver.py deleted file mode 100644 index 8e6f4ebc..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/radiodriver.py +++ /dev/null @@ -1,538 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Crazyradio CRTP link driver. - -This driver is used to communicate with the Crazyflie using the Crazyradio -USB dongle. -""" -import array -import binascii -import collections -import logging -import re -import struct -import sys -import threading - -from .crtpstack import CRTPPacket -from .exceptions import WrongUriType -from cflib.crtp.crtpdriver import CRTPDriver -from cflib.drivers.crazyradio import Crazyradio - -if sys.version_info < (3,): - import Queue as queue -else: - import queue - - -__author__ = 'Bitcraze AB' -__all__ = ['RadioDriver'] - -logger = logging.getLogger(__name__) - -DEFAULT_ADDR_A = [0xe7, 0xe7, 0xe7, 0xe7, 0xe7] -DEFAULT_ADDR = 0xE7E7E7E7E7 - - -class _SharedRadio(): - """ Manages access to one shared radio - """ - - def __init__(self, devid): - self.radio = Crazyradio(devid=devid) - self.lock = threading.Lock() - self.usage_counter = 0 - - -class _RadioManager(): - """ Radio manager helper class - Get a Crazyradio with: - radio_manager = _RadioManager(devid) - Then use your Crazyradio: - with radio_manager as cradio: - # cradio is the Crazyradio driver object, it is locked - Finally close it when finished. - cradio.close() - """ - # Configuration lock. Protects opening and closing Crazyradios - _config_lock = threading.Lock() - - _radios = [] # Hardware Crazyradio objects - - def __init__(self, devid, channel=0, datarate=0, address=DEFAULT_ADDR_A): - self._devid = devid - self._channel = channel - self._datarate = datarate - self._address = address - - with _RadioManager._config_lock: - if len(_RadioManager._radios) <= self._devid or \ - _RadioManager._radios[self._devid] is None: - _RadioManager._radios += ((self._devid + 1) - - len(_RadioManager._radios)) * [None] - _RadioManager._radios[self._devid] = _SharedRadio(self._devid) - - _RadioManager._radios[self._devid].usage_counter += 1 - - def close(self): - with _RadioManager._config_lock: - _RadioManager._radios[self._devid].usage_counter -= 1 - - if _RadioManager._radios[self._devid].usage_counter == 0: - try: - _RadioManager._radios[self._devid].radio.close() - except: - pass - _RadioManager._radios[self._devid] = None - - def __enter__(self): - _RadioManager._radios[self._devid].lock.acquire() - - _RadioManager._radios[self._devid].radio.set_channel(self._channel) - _RadioManager._radios[self._devid].radio.set_data_rate(self._datarate) - _RadioManager._radios[self._devid].radio.set_address(self._address) - - return _RadioManager._radios[self._devid].radio - - def __exit__(self, type, value, traceback): - _RadioManager._radios[self._devid].lock.release() - - -class RadioDriver(CRTPDriver): - """ Crazyradio link driver """ - - def __init__(self): - """ Create the link driver """ - CRTPDriver.__init__(self) - self._radio_manager = None - self.uri = '' - self.link_error_callback = None - self.link_quality_callback = None - self.in_queue = None - self.out_queue = None - self._thread = None - self.needs_resending = True - - def connect(self, uri, link_quality_callback, link_error_callback): - """ - Connect the link driver to a specified URI of the format: - radio://<dongle nbr>/<radio channel>/[250K,1M,2M] - - The callback for linkQuality can be called at any moment from the - driver to report back the link quality in percentage. The - callback from linkError will be called when a error occurs with - an error message. - """ - - # check if the URI is a radio URI - if not re.search('^radio://', uri): - raise WrongUriType('Not a radio URI') - - # Open the USB dongle - if not re.search('^radio://([0-9]+)((/([0-9]+))' - '((/(250K|1M|2M))?(/([A-F0-9]+))?)?)?$', uri): - raise WrongUriType('Wrong radio URI format!') - - uri_data = re.search('^radio://([0-9]+)((/([0-9]+))' - '((/(250K|1M|2M))?(/([A-F0-9]+))?)?)?$', uri) - - self.uri = uri - - channel = 2 - if uri_data.group(4): - channel = int(uri_data.group(4)) - - datarate = Crazyradio.DR_2MPS - if uri_data.group(7) == '250K': - datarate = Crazyradio.DR_250KPS - if uri_data.group(7) == '1M': - datarate = Crazyradio.DR_1MPS - if uri_data.group(7) == '2M': - datarate = Crazyradio.DR_2MPS - - address = DEFAULT_ADDR_A - if uri_data.group(9): - addr = str(uri_data.group(9)) - new_addr = struct.unpack('<BBBBB', binascii.unhexlify(addr)) - address = new_addr - - if self._radio_manager is None: - self._radio_manager = _RadioManager(int(uri_data.group(1)), - channel, - datarate, - address) - else: - raise Exception('Link already open!') - - with self._radio_manager as cradio: - if cradio.version >= 0.4: - cradio.set_arc(10) - else: - logger.warning('Radio version <0.4 will be obsoleted soon!') - - # Prepare the inter-thread communication queue - self.in_queue = queue.Queue() - # Limited size out queue to avoid "ReadBack" effect - self.out_queue = queue.Queue(1) - - # Launch the comm thread - self._thread = _RadioDriverThread(self._radio_manager, - self.in_queue, - self.out_queue, - link_quality_callback, - link_error_callback, - self) - self._thread.start() - - self.link_error_callback = link_error_callback - - def receive_packet(self, time=0): - """ - Receive a packet though the link. This call is blocking but will - timeout and return None if a timeout is supplied. - """ - if time == 0: - try: - return self.in_queue.get(False) - except queue.Empty: - return None - elif time < 0: - try: - return self.in_queue.get(True) - except queue.Empty: - return None - else: - try: - return self.in_queue.get(True, time) - except queue.Empty: - return None - - def send_packet(self, pk): - """ Send the packet pk though the link """ - try: - self.out_queue.put(pk, True, 2) - except queue.Full: - if self.link_error_callback: - self.link_error_callback('RadioDriver: Could not send packet' - ' to copter') - - def pause(self): - self._thread.stop() - self._thread = None - - def restart(self): - if self._thread: - return - - self._thread = _RadioDriverThread(self._radio_manager, self.in_queue, - self.out_queue, - self.link_quality_callback, - self.link_error_callback, - self) - self._thread.start() - - def close(self): - """ Close the link. """ - # Stop the comm thread - self._thread.stop() - - # Close the USB dongle - if self._radio_manager: - self._radio_manager.close() - self._radio_manager = None - - while not self.out_queue.empty(): - self.out_queue.get() - - # Clear callbacks - self.link_error_callback = None - self.link_quality_callback = None - - def _scan_radio_channels(self, cradio, start=0, stop=125): - """ Scan for Crazyflies between the supplied channels. """ - return list(cradio.scan_channels(start, stop, (0xff,))) - - def scan_selected(self, links): - to_scan = () - for l in links: - one_to_scan = {} - uri_data = re.search('^radio://([0-9]+)((/([0-9]+))' - '(/(250K|1M|2M))?)?$', - l) - - one_to_scan['channel'] = int(uri_data.group(4)) - - datarate = Crazyradio.DR_2MPS - if uri_data.group(6) == '250K': - datarate = Crazyradio.DR_250KPS - if uri_data.group(6) == '1M': - datarate = Crazyradio.DR_1MPS - if uri_data.group(6) == '2M': - datarate = Crazyradio.DR_2MPS - - one_to_scan['datarate'] = datarate - - to_scan += (one_to_scan,) - - with self._radio_manager as cradio: - found = cradio.scan_selected(to_scan, (0xFF, 0xFF, 0xFF)) - - ret = () - for f in found: - dr_string = '' - if f['datarate'] == Crazyradio.DR_2MPS: - dr_string = '2M' - if f['datarate'] == Crazyradio.DR_250KPS: - dr_string = '250K' - if f['datarate'] == Crazyradio.DR_1MPS: - dr_string = '1M' - - ret += ('radio://0/{}/{}'.format(f['channel'], dr_string),) - - return ret - - def scan_interface(self, address): - """ Scan interface for Crazyflies """ - - if self._radio_manager is None: - try: - self._radio_manager = _RadioManager(0) - except Exception: - return [] - - with self._radio_manager as cradio: - # FIXME: implements serial number in the Crazyradio driver! - serial = 'N/A' - - logger.info('v%s dongle with serial %s found', cradio.version, - serial) - found = [] - - if address is not None: - addr = '{:X}'.format(address) - new_addr = struct.unpack('<BBBBB', binascii.unhexlify(addr)) - cradio.set_address(new_addr) - - cradio.set_arc(1) - - cradio.set_data_rate(cradio.DR_250KPS) - - if address is None or address == DEFAULT_ADDR: - found += [['radio://0/{}/250K'.format(c), ''] - for c in self._scan_radio_channels(cradio)] - cradio.set_data_rate(cradio.DR_1MPS) - found += [['radio://0/{}/1M'.format(c), ''] - for c in self._scan_radio_channels(cradio)] - cradio.set_data_rate(cradio.DR_2MPS) - found += [['radio://0/{}/2M'.format(c), ''] - for c in self._scan_radio_channels(cradio)] - else: - found += [['radio://0/{}/250K/{:X}'.format(c, address), ''] - for c in self._scan_radio_channels(cradio)] - cradio.set_data_rate(cradio.DR_1MPS) - found += [['radio://0/{}/1M/{:X}'.format(c, address), ''] - for c in self._scan_radio_channels(cradio)] - cradio.set_data_rate(cradio.DR_2MPS) - found += [['radio://0/{}/2M/{:X}'.format(c, address), ''] - for c in self._scan_radio_channels(cradio)] - - self._radio_manager.close() - self._radio_manager = None - - return found - - def get_status(self): - try: - radio_manager = _RadioManager(0) - - with radio_manager as cradio: - ver = cradio.version - - radio_manager.close() - - return 'Crazyradio version {}'.format(ver) - except Exception: - return 'Crazyradio not found' - - def get_name(self): - return 'radio' - - -# Transmit/receive radio thread -class _RadioDriverThread(threading.Thread): - """ - Radio link receiver thread used to read data from the - Crazyradio USB driver. """ - - TRIES_BEFORE_DISCON = 10 - - def __init__(self, radio_manager, inQueue, outQueue, - link_quality_callback, link_error_callback, link): - """ Create the object """ - threading.Thread.__init__(self) - self._radio_manager = radio_manager - self._in_queue = inQueue - self._out_queue = outQueue - self._sp = False - self._link_error_callback = link_error_callback - self._link_quality_callback = link_quality_callback - self._retry_before_disconnect = _RadioDriverThread.TRIES_BEFORE_DISCON - self._retries = collections.deque() - self._retry_sum = 0 - - self._curr_up = 0 - self._curr_down = 1 - - self._has_safelink = False - self._link = link - - def stop(self): - """ Stop the thread """ - self._sp = True - try: - self.join() - except Exception: - pass - - def _send_packet_safe(self, cr, packet): - """ - Adds 1bit counter to CRTP header to guarantee that no ack (downlink) - payload are lost and no uplink packet are duplicated. - The caller should resend packet if not acked (ie. same as with a - direct call to crazyradio.send_packet) - """ - # packet = bytearray(packet) - packet[0] &= 0xF3 - packet[0] |= self._curr_up << 3 | self._curr_down << 2 - resp = cr.send_packet(packet) - if resp and resp.ack and len(resp.data) and \ - (resp.data[0] & 0x04) == (self._curr_down << 2): - self._curr_down = 1 - self._curr_down - if resp and resp.ack: - self._curr_up = 1 - self._curr_up - - return resp - - def run(self): - """ Run the receiver thread """ - dataOut = array.array('B', [0xFF]) - waitTime = 0 - emptyCtr = 0 - - # Try up to 10 times to enable the safelink mode - with self._radio_manager as cradio: - for _ in range(10): - resp = cradio.send_packet((0xff, 0x05, 0x01)) - if resp and resp.data and tuple(resp.data) == ( - 0xff, 0x05, 0x01): - self._has_safelink = True - self._curr_up = 0 - self._curr_down = 0 - break - self._link.needs_resending = not self._has_safelink - - while (True): - if (self._sp): - break - - with self._radio_manager as cradio: - try: - if self._has_safelink: - ackStatus = self._send_packet_safe(cradio, dataOut) - else: - ackStatus = cradio.send_packet(dataOut) - except Exception as e: - import traceback - - self._link_error_callback( - 'Error communicating with crazy radio ,it has ' - 'probably been unplugged!\nException:%s\n\n%s' % ( - e, traceback.format_exc())) - - # Analyse the in data packet ... - if ackStatus is None: - logger.info('Dongle reported ACK status == None') - continue - - if (self._link_quality_callback is not None): - # track the mean of a sliding window of the last N packets - retry = 10 - ackStatus.retry - self._retries.append(retry) - self._retry_sum += retry - if len(self._retries) > 100: - self._retry_sum -= self._retries.popleft() - link_quality = float(self._retry_sum) / len(self._retries) * 10 - self._link_quality_callback(link_quality) - - # If no copter, retry - if ackStatus.ack is False: - self._retry_before_disconnect = \ - self._retry_before_disconnect - 1 - if (self._retry_before_disconnect == 0 and - self._link_error_callback is not None): - self._link_error_callback('Too many packets lost') - continue - self._retry_before_disconnect = \ - _RadioDriverThread.TRIES_BEFORE_DISCON - - data = ackStatus.data - - # If there is a copter in range, the packet is analysed and the - # next packet to send is prepared - if (len(data) > 0): - inPacket = CRTPPacket(data[0], list(data[1:])) - self._in_queue.put(inPacket) - waitTime = 0 - emptyCtr = 0 - else: - emptyCtr += 1 - if (emptyCtr > 10): - emptyCtr = 10 - # Relaxation time if the last 10 packet where empty - waitTime = 0.01 - else: - waitTime = 0 - - # get the next packet to send of relaxation (wait 10ms) - outPacket = None - try: - outPacket = self._out_queue.get(True, waitTime) - except queue.Empty: - outPacket = None - - dataOut = array.array('B') - - if outPacket: - dataOut.append(outPacket.header) - for X in outPacket.data: - if type(X) == int: - dataOut.append(X) - else: - dataOut.append(ord(X)) - else: - dataOut.append(0xFF) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/serialdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/serialdriver.py deleted file mode 100644 index 34c54036..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/serialdriver.py +++ /dev/null @@ -1,59 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -An early serial link driver. This could still be used (after some fixing) to -run high-speed CRTP with the Crazyflie. The UART can be run at 2Mbit. -""" -import re - -from .crtpdriver import CRTPDriver -from .exceptions import WrongUriType - -__author__ = 'Bitcraze AB' -__all__ = ['SerialDriver'] - - -class SerialDriver(CRTPDriver): - - def __init__(self): - None - - def connect(self, uri, linkQualityCallback, linkErrorCallback): - # check if the URI is a serial URI - if not re.search('^serial://', uri): - raise WrongUriType('Not a serial URI') - - # Check if it is a valid serial URI - uriRe = re.search('^serial://([a-z A-Z 0-9]+)/?([0-9]+)?$', uri) - if not uriRe: - raise Exception('Invalid serial URI') - - def get_name(self): - return 'serial' - - def scan_interface(self, address): - return [] diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/udpdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/udpdriver.py deleted file mode 100644 index dfba56d5..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/udpdriver.py +++ /dev/null @@ -1,107 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" CRTP UDP Driver. Work either with the UDP server or with an UDP device -See udpserver.py for the protocol""" -import re -import struct -import sys -from socket import socket - -from .crtpdriver import CRTPDriver -from .crtpstack import CRTPPacket -from .exceptions import WrongUriType -if sys.version_info < (3,): - import Queue as queue -else: - import queue - -__author__ = 'Bitcraze AB' -__all__ = ['UdpDriver'] - - -class UdpDriver(CRTPDriver): - - def __init__(self): - None - - def connect(self, uri, linkQualityCallback, linkErrorCallback): - # check if the URI is a radio URI - if not re.search('^udp://', uri): - raise WrongUriType('Not an UDP URI') - - self.queue = queue.Queue() - self.socket = socket(socket.AF_INET, socket.SOCK_DGRAM) - self.addr = ('localhost', 7777) - self.socket.connect(self.addr) - - # Add this to the server clients list - self.socket.sendto('\xFF\x01\x01\x01', self.addr) - - def receive_packet(self, time=0): - data, addr = self.socket.recvfrom(1024) - - if data: - data = struct.unpack('b' * (len(data) - 1), data[0:len(data) - 1]) - pk = CRTPPacket() - pk.port = data[0] - pk.data = data[1:] - return pk - - try: - if time == 0: - return self.rxqueue.get(False) - elif time < 0: - while True: - return self.rxqueue.get(True, 10) - else: - return self.rxqueue.get(True, time) - except queue.Empty: - return None - - def send_packet(self, pk): - raw = (pk.port,) + struct.unpack('B' * len(pk.data), pk.data) - - cksum = 0 - for i in raw: - cksum += i - - cksum %= 256 - - data = ''.join(chr(v) for v in (raw + (cksum,))) - - # print tuple(data) - self.socket.sendto(data, self.addr) - - def close(self): - # Remove this from the server clients list - self.socket.sendto('\xFF\x01\x02\x02', self.addr) - - def get_name(self): - return 'udp' - - def scan_interface(self, address): - return [] diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/usbdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/usbdriver.py deleted file mode 100644 index 475a70ba..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/usbdriver.py +++ /dev/null @@ -1,257 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Crazyflie USB driver. - -This driver is used to communicate with the Crazyflie using the USB connection. -""" -import logging -import re -import sys -import threading - -from .crtpstack import CRTPPacket -from .exceptions import WrongUriType -from cflib.crtp.crtpdriver import CRTPDriver -from cflib.drivers.cfusb import CfUsb -if sys.version_info < (3,): - import Queue as queue -else: - import queue - -__author__ = 'Bitcraze AB' -__all__ = ['UsbDriver'] - -logger = logging.getLogger(__name__) - - -class UsbDriver(CRTPDriver): - """ Crazyradio link driver """ - - def __init__(self): - """ Create the link driver """ - CRTPDriver.__init__(self) - self.cfusb = None - self.uri = '' - self.link_error_callback = None - self.link_quality_callback = None - self.in_queue = None - self.out_queue = None - self._thread = None - self.needs_resending = False - - def connect(self, uri, link_quality_callback, link_error_callback): - """ - Connect the link driver to a specified URI of the format: - radio://<dongle nbr>/<radio channel>/[250K,1M,2M] - - The callback for linkQuality can be called at any moment from the - driver to report back the link quality in percentage. The - callback from linkError will be called when a error occues with - an error message. - """ - - # check if the URI is a radio URI - if not re.search('^usb://', uri): - raise WrongUriType('Not a radio URI') - - # Open the USB dongle - if not re.search('^usb://([0-9]+)$', - uri): - raise WrongUriType('Wrong radio URI format!') - - uri_data = re.search('^usb://([0-9]+)$', - uri) - - self.uri = uri - - if self.cfusb is None: - self.cfusb = CfUsb(devid=int(uri_data.group(1))) - if self.cfusb.dev: - self.cfusb.set_crtp_to_usb(True) - else: - self.cfusb = None - raise Exception('Could not open {}'.format(self.uri)) - - else: - raise Exception('Link already open!') - - # Prepare the inter-thread communication queue - self.in_queue = queue.Queue() - # Limited size out queue to avoid "ReadBack" effect - self.out_queue = queue.Queue(50) - - # Launch the comm thread - self._thread = _UsbReceiveThread(self.cfusb, self.in_queue, - link_quality_callback, - link_error_callback) - self._thread.start() - - self.link_error_callback = link_error_callback - - def receive_packet(self, time=0): - """ - Receive a packet though the link. This call is blocking but will - timeout and return None if a timeout is supplied. - """ - if time == 0: - try: - return self.in_queue.get(False) - except queue.Empty: - return None - elif time < 0: - try: - return self.in_queue.get(True) - except queue.Empty: - return None - else: - try: - return self.in_queue.get(True, time) - except queue.Empty: - return None - - def send_packet(self, pk): - """ Send the packet pk though the link """ - # if self.out_queue.full(): - # self.out_queue.get() - if (self.cfusb is None): - return - - try: - dataOut = (pk.header,) - dataOut += pk.datat - self.cfusb.send_packet(dataOut) - except queue.Full: - if self.link_error_callback: - self.link_error_callback( - 'UsbDriver: Could not send packet to Crazyflie') - - def pause(self): - self._thread.stop() - self._thread = None - - def restart(self): - if self._thread: - return - - self._thread = _UsbReceiveThread(self.cfusb, self.in_queue, - self.link_quality_callback, - self.link_error_callback) - self._thread.start() - - def close(self): - """ Close the link. """ - # Stop the comm thread - self._thread.stop() - - # Close the USB dongle - try: - if self.cfusb: - self.cfusb.set_crtp_to_usb(False) - self.cfusb.close() - except Exception as e: - # If we pull out the dongle we will not make this call - logger.info('Could not close {}'.format(e)) - pass - self.cfusb = None - - def scan_interface(self, address): - """ Scan interface for Crazyflies """ - if self.cfusb is None: - try: - self.cfusb = CfUsb() - except Exception as e: - logger.warn( - 'Exception while scanning for Crazyflie USB: {}'.format( - str(e))) - return [] - else: - raise Exception('Cannot scan for links while the link is open!') - - # FIXME: implements serial number in the Crazyradio driver! - # serial = "N/A" - - found = self.cfusb.scan() - - self.cfusb.close() - self.cfusb = None - - return found - - def get_status(self): - return 'No information available' - - def get_name(self): - return 'UsbCdc' - - -# Transmit/receive radio thread -class _UsbReceiveThread(threading.Thread): - """ - Radio link receiver thread used to read data from the - Crazyradio USB driver. """ - - # RETRYCOUNT_BEFORE_DISCONNECT = 10 - - def __init__(self, cfusb, inQueue, link_quality_callback, - link_error_callback): - """ Create the object """ - threading.Thread.__init__(self) - self.cfusb = cfusb - self.in_queue = inQueue - self.sp = False - self.link_error_callback = link_error_callback - self.link_quality_callback = link_quality_callback - - def stop(self): - """ Stop the thread """ - self.sp = True - try: - self.join() - except Exception: - pass - - def run(self): - """ Run the receiver thread """ - - while (True): - if (self.sp): - break - try: - # Blocking until USB data available - data = self.cfusb.receive_packet() - if len(data) > 0: - pk = CRTPPacket(data[0], list(data[1:])) - self.in_queue.put(pk) - except Exception as e: - import traceback - - self.link_error_callback( - 'Error communicating with the Crazyflie' - ' ,it has probably been unplugged!\n' - 'Exception:%s\n\n%s' % (e, - traceback.format_exc())) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/cfusb.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/cfusb.py deleted file mode 100644 index 28715eaf..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/cfusb.py +++ /dev/null @@ -1,197 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -USB driver for the Crazyflie. -""" -import logging -import os - -import usb - -__author__ = 'Bitcraze AB' -__all__ = ['CfUsb'] - -logger = logging.getLogger(__name__) - -USB_VID = 0x0483 -USB_PID = 0x5740 - -try: - import usb.core - - pyusb_backend = None - if os.name == 'nt': - import usb.backend.libusb0 as libusb0 - - pyusb_backend = libusb0.get_backend() - pyusb1 = True - -except: - pyusb1 = False - - -def _find_devices(): - """ - Returns a list of CrazyRadio devices currently connected to the computer - """ - ret = [] - - logger.info('Looking for devices....') - - if pyusb1: - for d in usb.core.find(idVendor=USB_VID, idProduct=USB_PID, find_all=1, - backend=pyusb_backend): - ret.append(d) - else: - busses = usb.busses() - for bus in busses: - for device in bus.devices: - if device.idVendor == USB_VID: - if device.idProduct == USB_PID: - ret += [device, ] - - return ret - - -class CfUsb: - """ Used for communication with the Crazyradio USB dongle """ - - def __init__(self, device=None, devid=0): - """ Create object and scan for USB dongle if no device is supplied """ - self.dev = None - self.handle = None - self._last_write = 0 - self._last_read = 0 - - if device is None: - devices = _find_devices() - try: - self.dev = devices[devid] - except Exception: - self.dev = None - - if self.dev: - if (pyusb1 is True): - self.dev.set_configuration(1) - self.handle = self.dev - self.version = float( - '{0:x}.{1:x}'.format(self.dev.bcdDevice >> 8, - self.dev.bcdDevice & 0x0FF)) - else: - self.handle = self.dev.open() - self.handle.setConfiguration(1) - self.handle.claimInterface(0) - self.version = float(self.dev.deviceVersion) - - def get_serial(self): - # The signature for get_string has changed between versions to 1.0.0b1, - # 1.0.0b2 and 1.0.0. Try the old signature first, if that fails try - # the newer one. - try: - return usb.util.get_string(self.dev, 255, self.dev.iSerialNumber) - except (usb.core.USBError, ValueError): - return usb.util.get_string(self.dev, self.dev.iSerialNumber) - - def close(self): - if (pyusb1 is False): - if self.handle: - self.handle.releaseInterface() - self.handle.reset() - else: - if self.dev: - self.dev.reset() - - self.handle = None - self.dev = None - - def scan(self): - # TODO: Currently only supports one device - if self.dev: - return [('usb://0', '')] - return [] - - def set_crtp_to_usb(self, crtp_to_usb): - if crtp_to_usb: - _send_vendor_setup(self.handle, 0x01, 0x01, 1, ()) - else: - _send_vendor_setup(self.handle, 0x01, 0x01, 0, ()) - - # Data transfers - def send_packet(self, dataOut): - """ Send a packet and receive the ack from the radio dongle - The ack contains information about the packet transmition - and a data payload if the ack packet contained any """ - try: - if (pyusb1 is False): - self.handle.bulkWrite(1, dataOut, 20) - else: - self.handle.write(endpoint=1, data=dataOut, timeout=20) - except usb.USBError: - pass - - def receive_packet(self): - dataIn = () - try: - if (pyusb1 is False): - dataIn = self.handle.bulkRead(0x81, 64, 20) - else: - dataIn = self.handle.read(0x81, 64, timeout=20) - except usb.USBError as e: - try: - if e.backend_error_code == -7 or e.backend_error_code == -116: - # Normal, the read was empty - pass - else: - raise IOError('Crazyflie disconnected') - except AttributeError as e: - # pyusb < 1.0 doesn't implement getting the underlying error - # number and it seems as if it's not possible to detect - # if the cable is disconnected. So this detection is not - # supported, but the "normal" case will work. - pass - - return dataIn - - -# Private utility functions -def _send_vendor_setup(handle, request, value, index, data): - if pyusb1: - handle.ctrl_transfer(usb.TYPE_VENDOR, request, wValue=value, - wIndex=index, timeout=1000, data_or_wLength=data) - else: - handle.controlMsg(usb.TYPE_VENDOR, request, data, value=value, - index=index, timeout=1000) - - -def _get_vendor_setup(handle, request, value, index, length): - if pyusb1: - return handle.ctrl_transfer(usb.TYPE_VENDOR | 0x80, request, - wValue=value, wIndex=index, timeout=1000, - data_or_wLength=length) - else: - return handle.controlMsg(usb.TYPE_VENDOR | 0x80, request, length, - value=value, index=index, timeout=1000) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/crazyradio.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/crazyradio.py deleted file mode 100644 index 0fd9e531..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/crazyradio.py +++ /dev/null @@ -1,315 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -USB driver for the Crazyradio USB dongle. -""" -import logging -import os - -import usb - -__author__ = 'Bitcraze AB' -__all__ = ['Crazyradio'] - -logger = logging.getLogger(__name__) - -# USB parameters -CRADIO_VID = 0x1915 -CRADIO_PID = 0x7777 - -# Dongle configuration requests -# See http://wiki.bitcraze.se/projects:crazyradio:protocol for documentation -SET_RADIO_CHANNEL = 0x01 -SET_RADIO_ADDRESS = 0x02 -SET_DATA_RATE = 0x03 -SET_RADIO_POWER = 0x04 -SET_RADIO_ARD = 0x05 -SET_RADIO_ARC = 0x06 -ACK_ENABLE = 0x10 -SET_CONT_CARRIER = 0x20 -SCANN_CHANNELS = 0x21 -LAUNCH_BOOTLOADER = 0xFF - -try: - import usb.core - - pyusb_backend = None - if os.name == 'nt': - import usb.backend.libusb0 as libusb0 - - pyusb_backend = libusb0.get_backend() - pyusb1 = True -except: - pyusb1 = False - - -def _find_devices(): - """ - Returns a list of CrazyRadio devices currently connected to the computer - """ - ret = [] - - if pyusb1: - for d in usb.core.find(idVendor=0x1915, idProduct=0x7777, find_all=1, - backend=pyusb_backend): - ret.append(d) - else: - busses = usb.busses() - for bus in busses: - for device in bus.devices: - if device.idVendor == CRADIO_VID: - if device.idProduct == CRADIO_PID: - ret += [device, ] - - return ret - - -class _radio_ack: - ack = False - powerDet = False - retry = 0 - data = () - - -class Crazyradio: - """ Used for communication with the Crazyradio USB dongle """ - # configuration constants - DR_250KPS = 0 - DR_1MPS = 1 - DR_2MPS = 2 - - P_M18DBM = 0 - P_M12DBM = 1 - P_M6DBM = 2 - P_0DBM = 3 - - def __init__(self, device=None, devid=0): - """ Create object and scan for USB dongle if no device is supplied """ - - self.current_channel = None - self.current_address = None - self.current_datarate = None - - if device is None: - try: - device = _find_devices()[devid] - except Exception: - raise Exception('Cannot find a Crazyradio Dongle') - - self.dev = device - - if (pyusb1 is True): - self.dev.set_configuration(1) - self.handle = self.dev - self.version = float('{0:x}.{1:x}'.format( - self.dev.bcdDevice >> 8, self.dev.bcdDevice & 0x0FF)) - else: - self.handle = self.dev.open() - self.handle.setConfiguration(1) - self.handle.claimInterface(0) - self.version = float(self.dev.deviceVersion) - - if self.version < 0.3: - raise 'This driver requires Crazyradio firmware V0.3+' - - if self.version < 0.4: - logger.warning('You should update to Crazyradio firmware V0.4+') - - # Reset the dongle to power up settings - self.set_data_rate(self.DR_2MPS) - self.set_channel(2) - self.arc = -1 - if self.version >= 0.4: - self.set_cont_carrier(False) - self.set_address((0xE7,) * 5) - self.set_power(self.P_0DBM) - self.set_arc(3) - self.set_ard_bytes(32) - self.set_ack_enable(True) - - def close(self): - if (pyusb1 is False): - if self.handle: - self.handle.releaseInterface() - self.handle.reset() - else: - if self.dev: - self.dev.reset() - - self.handle = None - self.dev = None - - self.current_channel = None - self.current_address = None - self.current_datarate = None - - # Dongle configuration - def set_channel(self, channel): - """ Set the radio channel to be used """ - if channel != self.current_channel: - _send_vendor_setup(self.handle, SET_RADIO_CHANNEL, channel, 0, ()) - self.current_channel = channel - - def set_address(self, address): - """ Set the radio address to be used""" - if len(address) != 5: - raise Exception('Crazyradio: the radio address shall be 5' - ' bytes long') - if address != self.current_address: - _send_vendor_setup(self.handle, SET_RADIO_ADDRESS, 0, 0, address) - self.current_address = address - - def set_data_rate(self, datarate): - """ Set the radio datarate to be used """ - if datarate != self.current_datarate: - _send_vendor_setup(self.handle, SET_DATA_RATE, datarate, 0, ()) - self.current_datarate = datarate - - def set_power(self, power): - """ Set the radio power to be used """ - _send_vendor_setup(self.handle, SET_RADIO_POWER, power, 0, ()) - - def set_arc(self, arc): - """ Set the ACK retry count for radio communication """ - _send_vendor_setup(self.handle, SET_RADIO_ARC, arc, 0, ()) - self.arc = arc - - def set_ard_time(self, us): - """ Set the ACK retry delay for radio communication """ - # Auto Retransmit Delay: - # 0000 - Wait 250uS - # 0001 - Wait 500uS - # 0010 - Wait 750uS - # ........ - # 1111 - Wait 4000uS - - # Round down, to value representing a multiple of 250uS - t = int((us / 250) - 1) - if (t < 0): - t = 0 - if (t > 0xF): - t = 0xF - _send_vendor_setup(self.handle, SET_RADIO_ARD, t, 0, ()) - - def set_ard_bytes(self, nbytes): - _send_vendor_setup(self.handle, SET_RADIO_ARD, 0x80 | nbytes, 0, ()) - - def set_cont_carrier(self, active): - if active: - _send_vendor_setup(self.handle, SET_CONT_CARRIER, 1, 0, ()) - else: - _send_vendor_setup(self.handle, SET_CONT_CARRIER, 0, 0, ()) - - def set_ack_enable(self, enable): - if enable: - _send_vendor_setup(self.handle, ACK_ENABLE, 1, 0, ()) - else: - _send_vendor_setup(self.handle, ACK_ENABLE, 0, 0, ()) - - def _has_fw_scan(self): - # return self.version >= 0.5 - # FIXME: Mitigation for Crazyradio firmware bug #9 - return False - - def scan_selected(self, selected, packet): - result = () - for s in selected: - self.set_channel(s['channel']) - self.set_data_rate(s['datarate']) - status = self.send_packet(packet) - if status and status.ack: - result = result + (s,) - - return result - - def scan_channels(self, start, stop, packet): - if self._has_fw_scan(): # Fast firmware-driven scan - self.current_channel = None - self.current_address = None - self.current_datarate = None - - _send_vendor_setup(self.handle, SCANN_CHANNELS, start, stop, - packet) - return tuple(_get_vendor_setup(self.handle, SCANN_CHANNELS, - 0, 0, 64)) - else: # Slow PC-driven scan - result = tuple() - for i in range(start, stop + 1): - self.set_channel(i) - status = self.send_packet(packet) - if status and status.ack: - result = result + (i,) - return result - - # Data transferts - def send_packet(self, dataOut): - """ Send a packet and receive the ack from the radio dongle - The ack contains information about the packet transmition - and a data payload if the ack packet contained any """ - ackIn = None - data = None - try: - if (pyusb1 is False): - self.handle.bulkWrite(1, dataOut, 1000) - data = self.handle.bulkRead(0x81, 64, 1000) - else: - self.handle.write(endpoint=1, data=dataOut, timeout=1000) - data = self.handle.read(0x81, 64, timeout=1000) - except usb.USBError: - pass - - if data is not None: - ackIn = _radio_ack() - if data[0] != 0: - ackIn.ack = (data[0] & 0x01) != 0 - ackIn.powerDet = (data[0] & 0x02) != 0 - ackIn.retry = data[0] >> 4 - ackIn.data = data[1:] - else: - ackIn.retry = self.arc - - return ackIn - - -# Private utility functions -def _send_vendor_setup(handle, request, value, index, data): - if pyusb1: - handle.ctrl_transfer(usb.TYPE_VENDOR, request, wValue=value, - wIndex=index, timeout=1000, data_or_wLength=data) - else: - handle.controlMsg(usb.TYPE_VENDOR, request, data, value=value, - index=index, timeout=1000) - - -def _get_vendor_setup(handle, request, value, index, length): - if pyusb1: - return handle.ctrl_transfer(usb.TYPE_VENDOR | 0x80, request, - wValue=value, wIndex=index, timeout=1000, - data_or_wLength=length) - else: - return handle.controlMsg(usb.TYPE_VENDOR | 0x80, request, length, - value=value, index=index, timeout=1000) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/utils/callbacks.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/utils/callbacks.py deleted file mode 100644 index 3102bc63..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/utils/callbacks.py +++ /dev/null @@ -1,54 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -""" -Callback objects used in the Crazyflie library -""" - -__author__ = 'Bitcraze AB' -__all__ = ['Caller'] - - -class Caller(): - """ An object were callbacks can be registered and called """ - - def __init__(self): - """ Create the object """ - self.callbacks = [] - - def add_callback(self, cb): - """ Register cb as a new callback. Will not register duplicates. """ - if ((cb in self.callbacks) is False): - self.callbacks.append(cb) - - def remove_callback(self, cb): - """ Un-register cb from the callbacks """ - self.callbacks.remove(cb) - - def call(self, *args): - """ Call the callbacks registered with the arguments args """ - for cb in self.callbacks: - cb(*args) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/__init__.py deleted file mode 100644 index 82be6a10..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/__init__.py +++ /dev/null @@ -1,40 +0,0 @@ -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2017 Bitcraze AB -# -# 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. -""" The LPS lib is an API that is used to communicate with Loco Positioning -anchors. - -The main purpose of the lib is to manage LPP (Loco Positioning Protocol). - -Initially it will use a Crazyflie with a Loco Positioning deck as a bridge to -transfer information to LoPo anchors, but may in the future use other means -of transportation. - -Example: -cf = Crazyflie() -cf.open_link("radio://0/125") - -anchor = LoPoAnchor(cf) -anchor.set_position(1, (1.23, 4.56, 7.89)) - -""" diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/lopoanchor.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/lopoanchor.py deleted file mode 100644 index aa7fb4da..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/lopoanchor.py +++ /dev/null @@ -1,59 +0,0 @@ -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2017 Bitcraze AB -# -# 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. -""" -This class represents the connection to one or more Loco Positioning Anchors -""" -import struct - - -class LoPoAnchor(): - LPP_TYPE_POSITION = 1 - LPP_TYPE_REBOOT = 2 - - REBOOT_TO_BOOTLOADER = 0 - REBOOT_TO_FIRMWARE = 1 - - def __init__(self, crazyflie): - """ - :param crazyflie: A crazyflie object to be used as a bridge to the LoPo - system.""" - self.crazyflie = crazyflie - - def set_position(self, anchor_id, position): - """ - Send a packet with a position to one anchor. - :param anchor_id: The id of the targeted anchor. This is the first byte - of the anchor address. - :param position: The position of the anchor, as an array - """ - x = position[0] - y = position[1] - z = position[2] - data = struct.pack('<Bfff', LoPoAnchor.LPP_TYPE_POSITION, x, y, z) - - self.crazyflie.loc.send_short_lpp_packet(anchor_id, data) - - def reboot(self, anchor_id, mode): - data = struct.pack('<BB', LoPoAnchor.LPP_TYPE_REBOOT, mode) - self.crazyflie.loc.send_short_lpp_packet(anchor_id, data) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_swarm.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_swarm.py deleted file mode 100644 index ef2cdd6c..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_swarm.py +++ /dev/null @@ -1,225 +0,0 @@ -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2016 Bitcraze AB -# -# 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. -import sys -import unittest - -from cflib.crazyflie.swarm import Swarm -from cflib.crazyflie.syncCrazyflie import SyncCrazyflie - -if sys.version_info < (3, 3): - from mock import MagicMock -else: - from unittest.mock import MagicMock - - -class TestSwarm(unittest.TestCase): - URI1 = 'uri1' - URI2 = 'uri2' - URI3 = 'uri3' - - def setUp(self): - self.uris = [self.URI1, self.URI2, self.URI3] - self.factory = MockFactory() - - self.sut = Swarm(self.uris, factory=self.factory) - - def test_that_instances_are_created(self): - # Fixture - - # Test - - # Assert - actual = len(self.factory.mocks) - expected = len(self.uris) - self.assertEqual(expected, actual) - - def test_that_all_links_are_opened(self): - # Fixture - - # Test - self.sut.open_links() - - # Assert - for uri, mock in self.factory.mocks.items(): - mock.open_link.assert_called_once_with() - - def test_open_of_already_opened_swarm_raises_exception(self): - # Fixture - self.sut.open_links() - - # Test - # Assert - with self.assertRaises(Exception): - self.sut.open_links() - - def test_failed_open_of_one_link_closes_all_and_raises_exception(self): - # Fixture - self.factory.mocks[self.URI2].open_link.side_effect = Exception() - - # Test - # Assert - with self.assertRaises(Exception): - self.sut.open_links() - - for uri, mock in self.factory.mocks.items(): - mock.close_link.assert_called_once_with() - - def test_that_all_links_are_closed(self): - # Fixture - self.sut.open_links() - - # Test - self.sut.close_links() - - # Assert - for uri, mock in self.factory.mocks.items(): - mock.close_link.assert_called_once_with() - - def test_open_with_context_management(self): - # Fixture - - # Test - with Swarm(self.uris, factory=self.factory): - pass - - # Assert - for uri, mock in self.factory.mocks.items(): - mock.open_link.assert_called_once_with() - mock.close_link.assert_called_once_with() - - def test_sequential_execution_without_arguments(self): - # Fixture - func = MagicMock() - - # Test - self.sut.sequential(func) - - # Assert - for uri, mock in self.factory.mocks.items(): - func.assert_any_call(mock) - - def test_sequential_execution(self): - # Fixture - func = MagicMock() - args_dict = { - self.URI1: ['cf1-arg1'], - self.URI2: ['cf2-arg1'], - self.URI3: ['cf3-arg1'], - } - - cf1 = self.factory.mocks[self.URI1] - cf2 = self.factory.mocks[self.URI2] - cf3 = self.factory.mocks[self.URI3] - - # Test - self.sut.sequential(func, args_dict=args_dict) - - # Assert - func.assert_any_call(cf1, 'cf1-arg1') - func.assert_any_call(cf2, 'cf2-arg1') - func.assert_any_call(cf3, 'cf3-arg1') - - def test_parallel_execution_without_arguments(self): - # Fixture - func = MagicMock() - - # Test - self.sut.parallel(func) - - # Assert - for uri, mock in self.factory.mocks.items(): - func.assert_any_call(mock) - - def test_parallel_execution(self): - # Fixture - func = MagicMock() - args_dict = { - self.URI1: ['cf1-arg1'], - self.URI2: ['cf2-arg1'], - self.URI3: ['cf3-arg1'], - } - - cf1 = self.factory.mocks[self.URI1] - cf2 = self.factory.mocks[self.URI2] - cf3 = self.factory.mocks[self.URI3] - - # Test - self.sut.parallel(func, args_dict=args_dict) - - # Assert - func.assert_any_call(cf1, 'cf1-arg1') - func.assert_any_call(cf2, 'cf2-arg1') - func.assert_any_call(cf3, 'cf3-arg1') - - def test_parallel_execution_with_exception(self): - # Fixture - func_fail = MagicMock() - func_fail.side_effect = Exception() - args_dict = { - self.URI1: ['cf1-arg1'], - self.URI2: ['cf2-arg1'], - self.URI3: ['cf3-arg1'], - } - - cf1 = self.factory.mocks[self.URI1] - cf2 = self.factory.mocks[self.URI2] - cf3 = self.factory.mocks[self.URI3] - - # Test - self.sut.parallel(func_fail, args_dict=args_dict) - - # Assert - func_fail.assert_any_call(cf1, 'cf1-arg1') - func_fail.assert_any_call(cf2, 'cf2-arg1') - func_fail.assert_any_call(cf3, 'cf3-arg1') - - def test_parallel_safe_execution_with_exception(self): - # Fixture - func_fail = MagicMock() - func_fail.side_effect = Exception() - args_dict = { - self.URI1: ['cf1-arg1'], - self.URI2: ['cf2-arg1'], - self.URI3: ['cf3-arg1'], - } - - # Test - # Assert - with self.assertRaises(Exception): - self.sut.parallel_safe(func_fail, args_dict=args_dict) - - -class MockFactory: - - def __init__(self): - self.mocks = {} - - def construct(self, uri): - mock = MagicMock(spec=SyncCrazyflie, name='CF-' + uri) - self.mocks[uri] = mock - return mock - - -if __name__ == '__main__': - unittest.main() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py deleted file mode 100644 index 9f84a897..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py +++ /dev/null @@ -1,144 +0,0 @@ -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2016 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -import sys -import unittest -from test.support.asyncCallbackCaller import AsyncCallbackCaller - -from cflib.crazyflie import Crazyflie -from cflib.crazyflie.syncCrazyflie import SyncCrazyflie -from cflib.utils.callbacks import Caller - -if sys.version_info < (3, 3): - from mock import MagicMock -else: - from unittest.mock import MagicMock - - -class SyncCrazyflieTest(unittest.TestCase): - - def setUp(self): - self.uri = 'radio://0/60/2M' - - self.cf_mock = MagicMock(spec=Crazyflie) - self.cf_mock.connected = Caller() - self.cf_mock.connection_failed = Caller() - self.cf_mock.disconnected = Caller() - - self.cf_mock.open_link = AsyncCallbackCaller( - cb=self.cf_mock.connected, - args=[self.uri]).trigger - - self.sut = SyncCrazyflie(self.uri, self.cf_mock) - - def test_different_underlying_cf_instances(self): - # Fixture - - # Test - scf1 = SyncCrazyflie('uri 1') - scf2 = SyncCrazyflie('uri 2') - - # Assert - actual1 = scf1.cf - actual2 = scf2.cf - self.assertNotEqual(actual1, actual2) - - def test_open_link(self): - # Fixture - - # Test - self.sut.open_link() - - # Assert - self.assertTrue(self.sut.is_link_open()) - - def test_failed_open_link_raises_exception(self): - # Fixture - expected = 'Some error message' - self.cf_mock.open_link = AsyncCallbackCaller( - cb=self.cf_mock.connection_failed, - args=[self.uri, expected]).trigger - - # Test - try: - self.sut.open_link() - except Exception as e: - actual = e.args[0] - else: - self.fail('Expect exception') - - # Assert - self.assertEqual(expected, actual) - - def test_open_link_of_already_open_link_raises_exception(self): - # Fixture - self.sut.open_link() - - # Test - # Assert - with self.assertRaises(Exception): - self.sut.open_link() - - def test_close_link(self): - # Fixture - self.sut.open_link() - - # Test - self.sut.close_link() - - # Assert - self.cf_mock.close_link.assert_called_once_with() - self.assertFalse(self.sut.is_link_open()) - - def test_close_link_that_is_not_open(self): - # Fixture - - # Test - self.sut.close_link() - - # Assert - self.assertFalse(self.sut.is_link_open()) - - def test_closed_if_connection_is_lost(self): - # Fixture - self.sut.open_link() - - # Test - AsyncCallbackCaller( - cb=self.cf_mock.disconnected, - args=[self.uri]).call_and_wait() - - # Assert - self.assertFalse(self.sut.is_link_open()) - - def test_open_close_with_context_mangement(self): - # Fixture - - # Test - with SyncCrazyflie(self.uri, self.cf_mock) as sut: - self.assertTrue(sut.is_link_open()) - - # Assert - self.cf_mock.close_link.assert_called_once_with() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncLogger.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncLogger.py deleted file mode 100644 index 92ec918d..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncLogger.py +++ /dev/null @@ -1,230 +0,0 @@ -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2016 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -import sys -import unittest -from test.support.asyncCallbackCaller import AsyncCallbackCaller - -from cflib.crazyflie import Crazyflie -from cflib.crazyflie.log import Log -from cflib.crazyflie.log import LogConfig -from cflib.crazyflie.syncCrazyflie import SyncCrazyflie -from cflib.crazyflie.syncLogger import SyncLogger -from cflib.utils.callbacks import Caller - -if sys.version_info < (3, 3): - from mock import MagicMock -else: - from unittest.mock import MagicMock - - -class SyncLoggerTest(unittest.TestCase): - - def setUp(self): - self.cf_mock = MagicMock(spec=Crazyflie) - self.cf_mock.disconnected = Caller() - - self.log_mock = MagicMock(spec=Log) - self.cf_mock.log = self.log_mock - - self.log_config_mock = MagicMock(spec=LogConfig) - self.log_config_mock.data_received_cb = Caller() - - self.sut = SyncLogger(self.cf_mock, self.log_config_mock) - - def test_that_log_configuration_is_added_on_connect(self): - # Fixture - - # Test - self.sut.connect() - - # Assert - self.log_mock.add_config.assert_called_once_with(self.log_config_mock) - - def test_that_logging_is_started_on_connect(self): - # Fixture - - # Test - self.sut.connect() - - # Assert - self.log_config_mock.start.assert_called_once_with() - - def test_connection_status_after_connect(self): - # Fixture - self.sut.connect() - - # Test - actual = self.sut.is_connected() - - # Assert - self.assertTrue(actual) - - def test_that_callbacks_are_removed_on_disconnect(self): - # Fixture - - # Test - self.sut.connect() - self.sut.disconnect() - - # Assert - self.assertEqual(0, len(self.cf_mock.disconnected.callbacks)) - self.assertEqual(0, - len(self.log_config_mock.data_received_cb.callbacks)) - - def test_that_log_config_is_stopped_on_disconnect(self): - # Fixture - self.sut.connect() - - # Test - self.sut.disconnect() - - # Assert - self.log_config_mock.stop.assert_called_once_with() - self.log_config_mock.delete.assert_called_once_with() - - def test_that_data_is_received(self): - # Fixture - self.sut.connect() - - expected = ('Some ts', 'Some data', 'Some logblock') - AsyncCallbackCaller(cb=self.log_config_mock.data_received_cb, - args=[expected[0], expected[1], expected[2]] - ).trigger() - - # Test - actual = self.sut.__next__() - - # Assert - self.assertEqual(expected, actual) - - def test_connection_status_after_disconnect(self): - # Fixture - self.sut.connect() - self.sut.disconnect() - - # Test - actual = self.sut.is_connected() - - # Assert - self.assertFalse(actual) - - def test_that_connect_to_connected_instance_raises_exception(self): - # Fixture - self.sut.connect() - - # Test - # Assert - with self.assertRaises(Exception): - self.sut.connect() - - def test_connect_to_disconnected_instance(self): - # Fixture - self.sut.connect() - self.sut.disconnect() - - # Test - self.sut.connect() - - # Assert - # Nothing here. Just not expecting an exception - - def test_disconnect_from_disconnected_instance(self): - # Fixture - - # Test - self.sut.disconnect() - - # Assert - # Nothing here. Just not expecting an exception - - def test_connect_disconnect_with_context_management(self): - # Fixture - - # Test - with(SyncLogger(self.cf_mock, self.log_config_mock)) as sut: - # Assert - self.assertTrue(sut.is_connected()) - - self.assertFalse(sut.is_connected()) - - def test_that_iterator_is_implemented(self): - # Fixture - - # Test - actual = self.sut.__iter__() - - # Assert - self.assertEqual(self.sut, actual) - - def test_construction_with_sync_crazyflie_instance(self): - # Fixture - scf_mock = MagicMock(spec=SyncCrazyflie) - scf_mock.cf = self.cf_mock - - # Test - sut = SyncLogger(scf_mock, self.log_config_mock) - sut.connect() - - # Assert - # Nothing here. Just not expecting an exception - - def test_getting_data_without_conection_raises_exception(self): - # Fixture - - # Test - with self.assertRaises(StopIteration): - self.sut.__next__() - - # Assert - - def test_lost_connection_in_crazyflie_disconnects(self): - # Fixture - self.sut.connect() - - # Test - AsyncCallbackCaller(cb=self.cf_mock.disconnected, - args=['Some uri'] - ).call_and_wait() - - # Assert - self.assertFalse(self.sut.is_connected()) - - def test_lost_connection_in_crazyflie_raises_exception_in_iterator(self): - # Fixture - self.sut.connect() - - # Note this is not foolproof, the disconnected callback may be called - # before we are waiting on data. It will raise the same exception - # though and will pass - AsyncCallbackCaller(cb=self.cf_mock.disconnected, - delay=0.5, - args=['Some uri'] - ).trigger() - - # Test - # Assert - with self.assertRaises(StopIteration): - self.sut.__next__() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crtp/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crtp/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crtp/test_crtpstack.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crtp/test_crtpstack.py deleted file mode 100644 index 903032da..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crtp/test_crtpstack.py +++ /dev/null @@ -1,104 +0,0 @@ -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -import unittest - -from cflib.crtp.crtpstack import CRTPPacket - - -class CRTPPacketTest(unittest.TestCase): - - def setUp(self): - self.callback_count = 0 - self.sut = CRTPPacket() - - def test_that_port_and_channle_is_encoded_in_header(self): - # Fixture - self.sut.set_header(2, 1) - - # Test - actual = self.sut.get_header() - - # Assert - expected = 0x2d - self.assertEqual(expected, actual) - - def test_that_port_is_truncated_in_header(self): - # Fixture - port = 0xff - self.sut.set_header(port, 0) - - # Test - actual = self.sut.get_header() - - # Assert - expected = 0xfc - self.assertEqual(expected, actual) - - def test_that_channel_is_truncated_in_header(self): - # Fixture - channel = 0xff - self.sut.set_header(0, channel) - - # Test - actual = self.sut.get_header() - - # Assert - expected = 0x0f - self.assertEqual(expected, actual) - - def test_that_port_and_channel_is_encoded_in_header_when_set_separat(self): - # Fixture - self.sut.port = 2 - self.sut.channel = 1 - - # Test - actual = self.sut.get_header() - - # Assert - expected = 0x2d - self.assertEqual(expected, actual) - - def test_that_default_header_is_set_when_constructed(self): - # Fixture - - # Test - actual = self.sut.get_header() - - # Assert - expected = 0x0c - self.assertEqual(expected, actual) - - def test_that_header_is_set_when_constructed(self): - # Fixture - sut = CRTPPacket(header=0x21) - - # Test - actual = sut.get_header() - - # Assert - self.assertEqual(0x2d, actual) - self.assertEqual(2, sut.port) - self.assertEqual(1, sut.channel) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/support/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/support/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/support/asyncCallbackCaller.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/support/asyncCallbackCaller.py deleted file mode 100644 index ecf89643..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/support/asyncCallbackCaller.py +++ /dev/null @@ -1,46 +0,0 @@ -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) 2016 Bitcraze AB -# -# 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. -import time -from threading import Thread - - -class AsyncCallbackCaller: - - def __init__(self, cb=None, delay=0, args=(), kwargs={}): - self.caller = cb - self.delay = delay - self.args = args - self.kwargs = kwargs - - def trigger(self, *args, **kwargs): - Thread(target=self._make_call).start() - - def call_and_wait(self): - thread = Thread(target=self._make_call) - thread.start() - thread.join() - - def _make_call(self): - time.sleep(self.delay) - self.caller.call(*self.args, **self.kwargs) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/utils/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/utils/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/utils/test_callbacks.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/utils/test_callbacks.py deleted file mode 100644 index bd00a080..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/utils/test_callbacks.py +++ /dev/null @@ -1,97 +0,0 @@ -# -*- coding: utf-8 -*- -# -# || ____ _ __ -# +------+ / __ )(_) /_______________ _____ ___ -# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ -# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ -# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ -# -# Copyright (C) Bitcraze AB -# -# Crazyflie Nano Quadcopter Client -# -# 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. -import unittest - -from cflib.utils.callbacks import Caller - - -class CallerTest(unittest.TestCase): - - def setUp(self): - self.callback_count = 0 - self.sut = Caller() - - def test_that_callback_is_added(self): - # Fixture - - # Test - self.sut.add_callback(self._callback) - - # Assert - self.sut.call() - self.assertEqual(1, self.callback_count) - - def test_that_callback_is_added_only_one_time(self): - # Fixture - - # Test - self.sut.add_callback(self._callback) - self.sut.add_callback(self._callback) - - # Assert - self.sut.call() - self.assertEqual(1, self.callback_count) - - def test_that_multiple_callbacks_are_added(self): - # Fixture - - # Test - self.sut.add_callback(self._callback) - self.sut.add_callback(self._callback2) - - # Assert - self.sut.call() - self.assertEqual(2, self.callback_count) - - def test_that_callback_is_removed(self): - # Fixture - self.sut.add_callback(self._callback) - - # Test - self.sut.remove_callback(self._callback) - - # Assert - self.sut.call() - self.assertEqual(0, self.callback_count) - - def test_that_callback_is_called_with_arguments(self): - # Fixture - self.sut.add_callback(self._callback_with_args) - - # Test - self.sut.call('The token') - - # Assert - self.assertEqual('The token', self.callback_token) - - def _callback(self): - self.callback_count += 1 - - def _callback2(self): - self.callback_count += 1 - - def _callback_with_args(self, token): - self.callback_token = token diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/PKG-INFO b/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/PKG-INFO deleted file mode 100644 index c6b32a7b..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/PKG-INFO +++ /dev/null @@ -1,16 +0,0 @@ -Metadata-Version: 1.1 -Name: cflib -Version: 0.1.3 -Summary: Crazyflie python driver -Home-page: https://github.com/bitcraze/crazyflie-lib-python -Author: Bitcraze and contributors -Author-email: contact@bitcraze.io -License: GPLv3 -Description: UNKNOWN -Keywords: driver crazyflie quadcopter -Platform: UNKNOWN -Classifier: Development Status :: 4 - Beta -Classifier: License :: OSI Approved :: GNU General Public License v3 (GPLv3) -Classifier: Topic :: System :: Hardware :: Hardware Drivers -Classifier: Programming Language :: Python :: 2 -Classifier: Programming Language :: Python :: 3 diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/SOURCES.txt b/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/SOURCES.txt deleted file mode 100644 index bed22328..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/SOURCES.txt +++ /dev/null @@ -1,52 +0,0 @@ -setup.cfg -setup.py -cflib/__init__.py -cflib.egg-info/PKG-INFO -cflib.egg-info/SOURCES.txt -cflib.egg-info/dependency_links.txt -cflib.egg-info/requires.txt -cflib.egg-info/top_level.txt -cflib/bootloader/__init__.py -cflib/bootloader/boottypes.py -cflib/bootloader/cloader.py -cflib/crazyflie/__init__.py -cflib/crazyflie/commander.py -cflib/crazyflie/console.py -cflib/crazyflie/extpos.py -cflib/crazyflie/localization.py -cflib/crazyflie/log.py -cflib/crazyflie/mem.py -cflib/crazyflie/param.py -cflib/crazyflie/platformservice.py -cflib/crazyflie/swarm.py -cflib/crazyflie/syncCrazyflie.py -cflib/crazyflie/syncLogger.py -cflib/crazyflie/toc.py -cflib/crazyflie/toccache.py -cflib/crtp/__init__.py -cflib/crtp/crtpdriver.py -cflib/crtp/crtpstack.py -cflib/crtp/debugdriver.py -cflib/crtp/exceptions.py -cflib/crtp/radiodriver.py -cflib/crtp/serialdriver.py -cflib/crtp/udpdriver.py -cflib/crtp/usbdriver.py -cflib/drivers/__init__.py -cflib/drivers/cfusb.py -cflib/drivers/crazyradio.py -cflib/utils/__init__.py -cflib/utils/callbacks.py -lpslib/__init__.py -lpslib/lopoanchor.py -test/__init__.py -test/crazyflie/__init__.py -test/crazyflie/test_swarm.py -test/crazyflie/test_syncCrazyflie.py -test/crazyflie/test_syncLogger.py -test/crtp/__init__.py -test/crtp/test_crtpstack.py -test/support/__init__.py -test/support/asyncCallbackCaller.py -test/utils/__init__.py -test/utils/test_callbacks.py \ No newline at end of file diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/dependency_links.txt b/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/dependency_links.txt deleted file mode 100644 index 8b137891..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/dependency_links.txt +++ /dev/null @@ -1 +0,0 @@ - diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/requires.txt b/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/requires.txt deleted file mode 100644 index 8ba626a4..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/requires.txt +++ /dev/null @@ -1 +0,0 @@ -pyusb>=1.0.0b2 diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/top_level.txt b/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/top_level.txt deleted file mode 100644 index 9ea46da8..00000000 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/top_level.txt +++ /dev/null @@ -1,3 +0,0 @@ -cflib -lpslib -test diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/__init__.py index d4cd1a6c..cde26e9c 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/__init__.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/__init__.py @@ -177,7 +177,7 @@ class Bootloader: file_to_flash['start_page'] = file_to_flash[ 'target'].start_page files_to_flash += (file_to_flash,) - except KeyError as e: + except KeyError: print('Could not find a file for {} in {}'.format( current_target, filename)) return False diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/cloader.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/cloader.py index 716a344b..cdea76ea 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/cloader.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/cloader.py @@ -99,26 +99,32 @@ class Cloader: pk.data = (target_id, 0xFF) self.link.send_packet(pk) - pk = self.link.receive_packet(1) - - while ((not pk or pk.header != 0xFF or - struct.unpack('<BB', pk.data[0:2]) != (target_id, 0xFF) - ) and retry_counter >= 0): + got_answer = False + while(not got_answer and retry_counter >= 0): pk = self.link.receive_packet(1) - retry_counter -= 1 - - if pk: + if pk and pk.header == 0xFF: + try: + data = struct.unpack('<BB', pk.data[0:2]) + got_answer = data == (target_id, 0xFF) + except struct.error: + # Failed unpacking, retry + pass + + if got_answer: new_address = (0xb1,) + struct.unpack('<BBBB', pk.data[2:6][::-1]) - pk = CRTPPacket() - pk.set_header(0xFF, 0xFF) - pk.data = (target_id, 0xF0, 0x00) - self.link.send_packet(pk) + # The reset packet arrival cannot be checked. + # Send it more than one time to increase the chances it makes it. + for _ in range(10): + pk = CRTPPacket() + pk.set_header(0xFF, 0xFF) + pk.data = (target_id, 0xF0, 0x00) + self.link.send_packet(pk) addr = int(binascii.hexlify( struct.pack('B' * 5, *new_address)), 16) - time.sleep(0.2) + time.sleep(1) self.link.close() time.sleep(0.2) self.link = cflib.crtp.get_link_driver( @@ -359,6 +365,12 @@ class Cloader: # print "Write page", flashPage # print "Writing page [%d] and [%d] forward" % (flashPage, nPage) pk = None + + # Flushing downlink ... + pk = self.link.receive_packet(0) + while pk is not None: + pk = self.link.receive_packet(0) + retry_counter = 5 # print "Flasing to 0x{:X}".format(addr) while ((not pk or pk.header != 0xFF or @@ -369,7 +381,14 @@ class Cloader: pk.data = struct.pack('<BBHHH', addr, 0x18, page_buffer, target_page, page_count) self.link.send_packet(pk) - pk = self.link.receive_packet(1) + + # Timeout for writing to flash is raised from 1s (used elsewhere + # in this module) to 2.5s because it may take more than a second + # to erase a page on the STM32F405. + # + # See https://github.com/bitcraze/crazyflie-lib-python/issues/98 + # for more details. + pk = self.link.receive_packet(2.5) retry_counter -= 1 if retry_counter < 0: diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/__init__.py index 1623825b..b504735b 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/__init__.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/__init__.py @@ -50,6 +50,7 @@ from .mem import Memory from .param import Param from .platformservice import PlatformService from .toccache import TocCache +from cflib.crazyflie.high_level_commander import HighLevelCommander from cflib.utils.callbacks import Caller __author__ = 'Bitcraze AB' @@ -105,9 +106,11 @@ class Crazyflie(): self.incoming = _IncomingPacketHandler(self) self.incoming.setDaemon(True) - self.incoming.start() + if self.link: + self.incoming.start() self.commander = Commander(self) + self.high_level_commander = HighLevelCommander(self) self.loc = Localization(self) self.extpos = Extpos(self) self.log = Log(self) @@ -155,6 +158,9 @@ class Crazyflie(): """Start the connection setup by refreshing the TOCs""" logger.info('We are connected[%s], request connection setup', self.link_uri) + self.platform.fetch_platform_informations(self._platform_info_fetched) + + def _platform_info_fetched(self): self.log.refresh_toc(self._log_toc_updated_cb, self._toc_cache) def _param_toc_updated_cb(self): @@ -223,6 +229,8 @@ class Crazyflie(): logger.warning(message) self.connection_failed.call(link_uri, message) else: + if not self.incoming.isAlive(): + self.incoming.start() # Add a callback so we can check that any data is coming # back from the copter self.packet_received.add_callback( @@ -254,6 +262,11 @@ class Crazyflie(): self._answer_patterns = {} self.disconnected.call(self.link_uri) + """Check if the communication link is open or not.""" + + def is_connected(self): + return self.connected_ts is not None + def add_port_callback(self, port, cb): """Add a callback to cb on port""" self.incoming.add_port_callback(port, cb) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/commander.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/commander.py index 75238955..405af8e3 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/commander.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/commander.py @@ -39,6 +39,7 @@ TYPE_STOP = 0 TYPE_VELOCITY_WORLD = 1 TYPE_ZDISTANCE = 2 TYPE_HOVER = 5 +TYPE_POSITION = 7 class Commander(): @@ -127,3 +128,17 @@ class Commander(): pk.data = struct.pack('<Bffff', TYPE_HOVER, vx, vy, yawrate, zdistance) self._cf.send_packet(pk) + + def send_position_setpoint(self, x, y, z, yaw): + """ + Control mode where the position is sent as absolute x,y,z coordinate in + meter and the yaw is the absolute orientation. + + x and y are in m + yaw is in degrees + """ + pk = CRTPPacket() + pk.port = CRTPPort.COMMANDER_GENERIC + pk.data = struct.pack('<Bffff', TYPE_POSITION, + x, y, z, yaw) + self._cf.send_packet(pk) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/extpos.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/extpos.py index 53486dff..cf4ec490 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/extpos.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/extpos.py @@ -7,7 +7,7 @@ # +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ # || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ # -# Copyright (C) 2011-2013 Bitcraze AB +# Copyright (C) 2011-2020 Bitcraze AB # # Crazyflie Nano Quadcopter Client # @@ -50,3 +50,11 @@ class Extpos(): """ self._cf.loc.send_extpos([x, y, z]) + + def send_extpose(self, x, y, z, qx, qy, qz, qw): + """ + Send the current Crazyflie X, Y, Z position and attitude as a + normalized quaternion. This is going to be forwarded to the + Crazyflie's position estimator. + """ + self._cf.loc.send_extpose([x, y, z], [qx, qy, qz, qw]) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/high_level_commander.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/high_level_commander.py new file mode 100644 index 00000000..e36b2b2b --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/high_level_commander.py @@ -0,0 +1,201 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2018-2020 Bitcraze AB +# +# Crazyflie Nano Quadcopter Client +# +# 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. +""" +Used for sending high level setpoints to the Crazyflie +""" +import struct + +from cflib.crtp.crtpstack import CRTPPacket +from cflib.crtp.crtpstack import CRTPPort + +__author__ = 'Bitcraze AB' +__all__ = ['HighLevelCommander'] + + +class HighLevelCommander(): + """ + Used for sending high level setpoints to the Crazyflie + """ + + COMMAND_SET_GROUP_MASK = 0 + COMMAND_STOP = 3 + COMMAND_GO_TO = 4 + COMMAND_START_TRAJECTORY = 5 + COMMAND_DEFINE_TRAJECTORY = 6 + COMMAND_TAKEOFF_2 = 7 + COMMAND_LAND_2 = 8 + + ALL_GROUPS = 0 + + TRAJECTORY_LOCATION_MEM = 1 + TRAJECTORY_TYPE_POLY4D = 0 + + def __init__(self, crazyflie=None): + """ + Initialize the object. + """ + self._cf = crazyflie + + def set_group_mask(self, group_mask=ALL_GROUPS): + """ + Set the group mask that the Crazyflie belongs to + + :param group_mask: mask for which groups this CF belongs to + """ + self._send_packet(struct.pack('<BB', + self.COMMAND_SET_GROUP_MASK, + group_mask)) + + def takeoff(self, absolute_height_m, duration_s, group_mask=ALL_GROUPS, + yaw=0.0): + """ + vertical takeoff from current x-y position to given height + + :param absolute_height_m: absolut (m) + :param duration_s: time it should take until target height is + reached (s) + :param group_mask: mask for which CFs this should apply to + :param yaw: yaw (rad). Use current yaw if set to None. + """ + target_yaw = yaw + useCurrentYaw = False + if yaw is None: + target_yaw = 0.0 + useCurrentYaw = True + + self._send_packet(struct.pack('<BBff?f', + self.COMMAND_TAKEOFF_2, + group_mask, + absolute_height_m, + target_yaw, + useCurrentYaw, + duration_s)) + + def land(self, absolute_height_m, duration_s, group_mask=ALL_GROUPS, + yaw=0.0): + """ + vertical land from current x-y position to given height + + :param absolute_height_m: absolut (m) + :param duration_s: time it should take until target height is + reached (s) + :param group_mask: mask for which CFs this should apply to + :param yaw: yaw (rad). Use current yaw if set to None. + """ + target_yaw = yaw + useCurrentYaw = False + if yaw is None: + target_yaw = 0.0 + useCurrentYaw = True + + self._send_packet(struct.pack('<BBff?f', + self.COMMAND_LAND_2, + group_mask, + absolute_height_m, + target_yaw, + useCurrentYaw, + duration_s)) + + def stop(self, group_mask=ALL_GROUPS): + """ + stops the current trajectory (turns off the motors) + + :param group_mask: mask for which CFs this should apply to + :return: + """ + self._send_packet(struct.pack('<BB', + self.COMMAND_STOP, + group_mask)) + + def go_to(self, x, y, z, yaw, duration_s, relative=False, + group_mask=ALL_GROUPS): + """ + Go to an absolute or relative position + + :param x: x (m) + :param y: y (m) + :param z: z (m) + :param yaw: yaw (radians) + :param duration_s: time it should take to reach the position (s) + :param relative: True if x, y, z is relative to the current position + :param group_mask: mask for which CFs this should apply to + """ + self._send_packet(struct.pack('<BBBfffff', + self.COMMAND_GO_TO, + group_mask, + relative, + x, y, z, + yaw, + duration_s)) + + def start_trajectory(self, trajectory_id, time_scale=1.0, relative=False, + reversed=False, group_mask=ALL_GROUPS): + """ + starts executing a specified trajectory + + :param trajectory_id: id of the trajectory (previously defined by + define_trajectory) + :param time_scale: time factor; 1.0 = original speed; + >1.0: slower; + <1.0: faster + :param relative: set to True, if trajectory should be shifted to + current setpoint + :param reversed: set to True, if trajectory should be executed in + reverse + :param group_mask: mask for which CFs this should apply to + :return: + """ + self._send_packet(struct.pack('<BBBBBf', + self.COMMAND_START_TRAJECTORY, + group_mask, + relative, + reversed, + trajectory_id, + time_scale)) + + def define_trajectory(self, trajectory_id, offset, n_pieces): + """ + Define a trajectory that has previously been uploaded to memory. + + :param trajectory_id: The id of the trajectory + :param offset: offset in uploaded memory + :param n_pieces: Nr of pieces in the trajectory + :return: + """ + self._send_packet(struct.pack('<BBBBIB', + self.COMMAND_DEFINE_TRAJECTORY, + trajectory_id, + self.TRAJECTORY_LOCATION_MEM, + self.TRAJECTORY_TYPE_POLY4D, + offset, + n_pieces)) + + def _send_packet(self, data): + pk = CRTPPacket() + pk.port = CRTPPort.SETPOINT_HL + pk.data = data + self._cf.send_packet(pk) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/localization.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/localization.py index 7b3bd053..dabd1be8 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/localization.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/localization.py @@ -7,7 +7,7 @@ # +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ # || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ # -# Copyright (C) 2017 Bitcraze AB +# Copyright (C) 2017-2020 Bitcraze AB # # Crazyflie Nano Quadcopter Client # @@ -56,9 +56,15 @@ class Localization(): GENERIC_CH = 1 # Location message types for generig channel - RANGE_STREAM_REPORT = 0x00 - RANGE_STREAM_REPORT_FP16 = 0x01 - LPS_SHORT_LPP_PACKET = 0x02 + RANGE_STREAM_REPORT = 0 + RANGE_STREAM_REPORT_FP16 = 1 + LPS_SHORT_LPP_PACKET = 2 + EMERGENCY_STOP = 3 + EMERGENCY_STOP_WATCHDOG = 4 + COMM_GNSS_NMEA = 6 + COMM_GNSS_PROPRIETARY = 7 + EXT_POSE = 8 + EXT_POSE_PACKED = 9 def __init__(self, crazyflie=None): """ @@ -110,6 +116,22 @@ class Localization(): pk.data = struct.pack('<fff', pos[0], pos[1], pos[2]) self._cf.send_packet(pk) + def send_extpose(self, pos, quat): + """ + Send the current Crazyflie pose (position [x, y, z] and + attitude quaternion [qx, qy, qz, qw]). This is going to be forwarded + to the Crazyflie's position estimator. + """ + + pk = CRTPPacket() + pk.port = CRTPPort.LOCALIZATION + pk.channel = self.GENERIC_CH + pk.data = struct.pack('<Bfffffff', + self.EXT_POSE, + pos[0], pos[1], pos[2], + quat[0], quat[1], quat[2], quat[3]) + self._cf.send_packet(pk) + def send_short_lpp_packet(self, dest_id, data): """ Send ultra-wide-band LPP packet to dest_id diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/log.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/log.py index 9cf32443..7f5e34ad 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/log.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/log.py @@ -79,8 +79,10 @@ CHAN_SETTINGS = 1 CHAN_LOGDATA = 2 # Commands used when accessing the Table of Contents -CMD_TOC_ELEMENT = 0 -CMD_TOC_INFO = 1 +CMD_TOC_ELEMENT = 0 # original version: up to 255 entries +CMD_TOC_INFO = 1 # original version: up to 255 entries +CMD_GET_ITEM_V2 = 2 # version 2: up to 16k entries +CMD_GET_INFO_V2 = 3 # version 2: up to 16k entries # Commands used when accessing the Log configurations CMD_CREATE_BLOCK = 0 @@ -89,6 +91,8 @@ CMD_DELETE_BLOCK = 2 CMD_START_LOGGING = 3 CMD_STOP_LOGGING = 4 CMD_RESET_LOGGING = 5 +CMD_CREATE_BLOCK_V2 = 6 +CMD_APPEND_BLOCK_V2 = 7 # Possible states when receiving TOC IDLE = 'IDLE' @@ -150,8 +154,11 @@ class LogConfig(object): self.added_cb = Caller() self.err_no = 0 + # These 3 variables are set by the log subsystem when the bock is added self.id = 0 self.cf = None + self.useV2 = False + self.period = int(period_in_ms / 10) self.period_in_ms = period_in_ms self._added = False @@ -214,7 +221,10 @@ class LogConfig(object): """Save the log configuration in the Crazyflie""" pk = CRTPPacket() pk.set_header(5, CHAN_SETTINGS) - pk.data = (CMD_CREATE_BLOCK, self.id) + if self.useV2: + pk.data = (CMD_CREATE_BLOCK_V2, self.id) + else: + pk.data = (CMD_CREATE_BLOCK, self.id) for var in self.variables: if (var.is_toc_variable() is False): # Memory location logger.debug('Logging to raw memory %d, 0x%04X', @@ -228,9 +238,18 @@ class LogConfig(object): self.cf.log.toc.get_element_id( var.name), var.get_storage_and_fetch_byte()) pk.data.append(var.get_storage_and_fetch_byte()) - pk.data.append(self.cf.log.toc.get_element_id(var.name)) + if self.useV2: + ident = self.cf.log.toc.get_element_id(var.name) + pk.data.append(ident & 0x0ff) + pk.data.append((ident >> 8) & 0x0ff) + else: + pk.data.append(self.cf.log.toc.get_element_id(var.name)) logger.debug('Adding log block id {}'.format(self.id)) - self.cf.send_packet(pk, expected_reply=(CMD_CREATE_BLOCK, self.id)) + if self.useV2: + self.cf.send_packet(pk, expected_reply=( + CMD_CREATE_BLOCK_V2, self.id)) + else: + self.cf.send_packet(pk, expected_reply=(CMD_CREATE_BLOCK, self.id)) def start(self): """Start the logging for this entry""" @@ -337,21 +356,21 @@ class LogTocElement: raise KeyError( 'Type [%d] not found in LogTocElement.types!' % ident) - def __init__(self, data=None): + def __init__(self, ident=0, data=None): """TocElement creator. Data is the binary payload of the element.""" + self.ident = ident + if (data): - naming = data[2:] + naming = data[1:] zt = bytearray((0, )) self.group = naming[:naming.find(zt)].decode('ISO-8859-1') self.name = naming[naming.find(zt) + 1:-1].decode('ISO-8859-1') - self.ident = data[0] - - self.ctype = LogTocElement.get_cstring_from_id(data[1]) - self.pytype = LogTocElement.get_unpack_string_from_id(data[1]) + self.ctype = LogTocElement.get_cstring_from_id(data[0]) + self.pytype = LogTocElement.get_unpack_string_from_id(data[0]) - self.access = data[1] & 0x10 + self.access = data[0] & 0x10 class Log(): @@ -386,6 +405,8 @@ class Log(): self._config_id_counter = 1 + self._useV2 = False + def add_config(self, logconf): """Add a log configuration to the logging framework. @@ -436,6 +457,7 @@ class Log(): logconf.valid = True logconf.cf = self.cf logconf.id = self._config_id_counter + logconf.useV2 = self._useV2 self._config_id_counter = (self._config_id_counter + 1) % 255 self.log_blocks.append(logconf) self.block_added_cb.call(logconf) @@ -448,6 +470,8 @@ class Log(): def refresh_toc(self, refresh_done_callback, toc_cache): """Start refreshing the table of loggale variables""" + self._useV2 = self.cf.platform.get_protocol_version() >= 4 + self._toc_cache = toc_cache self._refresh_callback = refresh_done_callback self.toc = None @@ -473,7 +497,7 @@ class Log(): id = payload[0] error_status = payload[1] block = self._find_block(id) - if (cmd == CMD_CREATE_BLOCK): + if cmd == CMD_CREATE_BLOCK or cmd == CMD_CREATE_BLOCK_V2: if (block is not None): if error_status == 0 or error_status == errno.EEXIST: if not block.added: diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/mem.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/mem.py index 071b3f0f..06e0ac55 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/mem.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/mem.py @@ -72,6 +72,10 @@ class MemoryElement(object): TYPE_1W = 1 TYPE_DRIVER_LED = 0x10 TYPE_LOCO = 0x11 + TYPE_TRAJ = 0x12 + TYPE_LOCO2 = 0x13 + TYPE_LH = 0x14 + TYPE_MEMORY_TESTER = 0x15 def __init__(self, id, type, size, mem_handler): """Initialize the element with default values""" @@ -91,10 +95,18 @@ class MemoryElement(object): return 'LED driver' if t == MemoryElement.TYPE_LOCO: return 'Loco Positioning' + if t == MemoryElement.TYPE_TRAJ: + return 'Trajectory' + if t == MemoryElement.TYPE_LOCO2: + return 'Loco Positioning 2' + if t == MemoryElement.TYPE_LH: + return 'Lighthouse positioning' + if t == MemoryElement.TYPE_MEMORY_TESTER: + return 'Memory tester' return 'Unknown' def new_data(self, mem, addr, data): - logger.info('New data, but not OW mem') + logger.debug('New data, but not OW mem') def __str__(self): """Generate debug string for memory""" @@ -139,7 +151,8 @@ class LEDDriverMemory(MemoryElement): def new_data(self, mem, addr, data): """Callback for when new memory data has been fetched""" if mem.id == self.id: - logger.info("Got new data from the LED driver, but we don't care.") + logger.debug( + "Got new data from the LED driver, but we don't care.") def write_data(self, write_finished_cb): """Write the saved LED-ring data to the Crazyflie""" @@ -166,13 +179,13 @@ class LEDDriverMemory(MemoryElement): if not self._update_finished_cb: self._update_finished_cb = update_finished_cb self.valid = False - logger.info('Updating content of memory {}'.format(self.id)) + logger.debug('Updating content of memory {}'.format(self.id)) # Start reading the header self.mem_handler.read(self, 0, 16) def write_done(self, mem, addr): if self._write_finished_cb and mem.id == self.id: - logger.info('Write to LED driver done') + logger.debug('Write to LED driver done') self._write_finished_cb(self, addr) self._write_finished_cb = None @@ -198,7 +211,7 @@ class I2CElement(MemoryElement): done = False # Check for header if data[0:4] == EEPROM_TOKEN: - logger.info('Got new data: {}'.format(data)) + logger.debug('Got new data: {}'.format(data)) [self.elements['version'], self.elements['radio_channel'], self.elements['radio_speed'], @@ -222,7 +235,7 @@ class I2CElement(MemoryElement): self.elements['radio_address'] = int( radio_address_upper) << 32 | radio_address_lower - logger.info(self.elements) + logger.debug(self.elements) data = self.datav0 + data done = True @@ -267,7 +280,7 @@ class I2CElement(MemoryElement): if not self._update_finished_cb: self._update_finished_cb = update_finished_cb self.valid = False - logger.info('Updating content of memory {}'.format(self.id)) + logger.debug('Updating content of memory {}'.format(self.id)) # Start reading the header self.mem_handler.read(self, 0, 16) @@ -366,10 +379,9 @@ class OWElement(MemoryElement): # Now generate the elements part elem = bytearray() - logger.info(list(self.elements.keys())) + logger.debug(list(self.elements.keys())) for element in reversed(list(self.elements.keys())): elem_string = self.elements[element] - # logger.info(">>>> {}".format(elem_string)) key_encoding = self._rev_element_mapping[element] elem += struct.pack('BB', key_encoding, len(elem_string)) elem += bytearray(elem_string.encode('ISO-8859-1')) @@ -399,13 +411,12 @@ class OWElement(MemoryElement): if not self._update_finished_cb: self._update_finished_cb = update_finished_cb self.valid = False - logger.info('Updating content of memory {}'.format(self.id)) + logger.debug('Updating content of memory {}'.format(self.id)) # Start reading the header self.mem_handler.read(self, 0, 11) def _parse_and_check_header(self, data): """Parse and check the CRC of the header part of the memory""" - # logger.info("Should parse header: {}".format(data)) (start, self.pins, self.vid, self.pid, crc) = struct.unpack('<BIBBB', data) test_crc = crc32(data[:-1]) & 0x0ff @@ -424,6 +435,7 @@ class OWElement(MemoryElement): class AnchorData: + """Holds data for one anchor""" def __init__(self, position=(0.0, 0.0, 0.0), is_valid=False): self.position = position @@ -490,7 +502,7 @@ class LocoMemory(MemoryElement): self.anchor_data = [] self.nr_of_anchors = 0 self.valid = False - logger.info('Updating content of memory {}'.format(self.id)) + logger.debug('Updating content of memory {}'.format(self.id)) # Start reading the header self.mem_handler.read(self, LocoMemory.MEM_LOCO_INFO, @@ -505,6 +517,388 @@ class LocoMemory(MemoryElement): self.mem_handler.read(self, addr, LocoMemory.MEM_LOCO_PAGE_LEN) +class AnchorData2: + """Holds data for one anchor""" + + def __init__(self, position=(0.0, 0.0, 0.0), is_valid=False): + self.position = position + self.is_valid = is_valid + + def set_from_mem_data(self, data): + x, y, z, self.is_valid = struct.unpack('<fff?', data) + self.position = (x, y, z) + + +class LocoMemory2(MemoryElement): + """Memory interface for accessing data from the Loco Positioning system + version 2""" + + SIZE_OF_FLOAT = 4 + + # MAX_NR_OF_ANCHORS should be set to the number of anchors + # supported by the firmware. Preferably short enough to fit into one packet + MAX_NR_OF_ANCHORS = 16 + ID_LIST_LEN = 1 + MAX_NR_OF_ANCHORS + + ADR_ID_LIST = 0x0000 + ADR_ACTIVE_ID_LIST = 0x1000 + ADR_ANCHOR_BASE = 0x2000 + + ANCHOR_PAGE_SIZE = 0x0100 + PAGE_LEN = (3 * SIZE_OF_FLOAT) + 1 + + def __init__(self, id, type, size, mem_handler): + super(LocoMemory2, self).__init__(id=id, type=type, size=size, + mem_handler=mem_handler) + self._update_ids_finished_cb = None + self._update_active_ids_finished_cb = None + self._update_data_finished_cb = None + self._currently_fetching_index = -1 + + self.anchor_ids = [] + self.active_anchor_ids = [] + self.anchor_data = {} + self.nr_of_anchors = 0 + self.ids_valid = False + self.active_ids_valid = False + self.data_valid = False + + def new_data(self, mem, addr, data): + """Callback for when new memory data has been fetched""" + if mem.id == self.id: + if addr == LocoMemory2.ADR_ID_LIST: + self._handle_id_list_data(data) + elif addr == LocoMemory2.ADR_ACTIVE_ID_LIST: + self._handle_active_id_list_data(data) + else: + id = int((addr - LocoMemory2.ADR_ANCHOR_BASE) / + LocoMemory2.ANCHOR_PAGE_SIZE) + self._handle_anchor_data(id, data) + + def update_id_list(self, update_ids_finished_cb): + """Request an update of the id list""" + if not self._update_ids_finished_cb: + self._update_ids_finished_cb = update_ids_finished_cb + self.anchor_ids = [] + self.active_anchor_ids = [] + self.anchor_data = {} + + self.nr_of_anchors = 0 + self.ids_valid = False + self.data_valid = False + + logger.debug('Updating ids of memory {}'.format(self.id)) + + # Start reading the header + self.mem_handler.read(self, LocoMemory2.ADR_ID_LIST, + LocoMemory2.ID_LIST_LEN) + + def update_active_id_list(self, update_active_ids_finished_cb): + """Request an update of the active id list""" + if not self._update_active_ids_finished_cb: + self._update_active_ids_finished_cb = update_active_ids_finished_cb + self.active_anchor_ids = [] + + self.active_ids_valid = False + + logger.debug('Updating active ids of memory {}'.format(self.id)) + + # Start reading the header + self.mem_handler.read(self, LocoMemory2.ADR_ACTIVE_ID_LIST, + LocoMemory2.ID_LIST_LEN) + + def update_data(self, update_data_finished_cb): + """Request an update of the anchor data""" + if not self._update_data_finished_cb and self.nr_of_anchors > 0: + self._update_data_finished_cb = update_data_finished_cb + self.anchor_data = {} + + self.data_valid = False + self._nr_of_anchors_to_fetch = self.nr_of_anchors + + logger.debug('Updating anchor data of memory {}'.format(self.id)) + + # Start reading the first anchor + self._currently_fetching_index = 0 + self._request_page(self.anchor_ids[self._currently_fetching_index]) + + def disconnect(self): + self._update_ids_finished_cb = None + self._update_data_finished_cb = None + + def _handle_id_list_data(self, data): + self.nr_of_anchors = data[0] + for i in range(self.nr_of_anchors): + self.anchor_ids.append(data[1 + i]) + self.ids_valid = True + + if self._update_ids_finished_cb: + self._update_ids_finished_cb(self) + self._update_ids_finished_cb = None + + def _handle_active_id_list_data(self, data): + count = data[0] + for i in range(count): + self.active_anchor_ids.append(data[1 + i]) + self.active_ids_valid = True + + if self._update_active_ids_finished_cb: + self._update_active_ids_finished_cb(self) + self._update_active_ids_finished_cb = None + + def _handle_anchor_data(self, id, data): + anchor = AnchorData2() + anchor.set_from_mem_data(data) + self.anchor_data[id] = anchor + + self._currently_fetching_index += 1 + if self._currently_fetching_index < self.nr_of_anchors: + self._request_page(self.anchor_ids[self._currently_fetching_index]) + else: + self.data_valid = True + if self._update_data_finished_cb: + self._update_data_finished_cb(self) + self._update_data_finished_cb = None + + def _request_page(self, page): + addr = LocoMemory2.ADR_ANCHOR_BASE + \ + LocoMemory2.ANCHOR_PAGE_SIZE * page + self.mem_handler.read(self, addr, LocoMemory2.PAGE_LEN) + + +class Poly4D: + class Poly: + def __init__(self, values=[0.0] * 8): + self.values = values + + def __init__(self, duration, x=None, y=None, z=None, yaw=None): + self.duration = duration + self.x = x if x else self.Poly() + self.y = y if y else self.Poly() + self.z = z if z else self.Poly() + self.yaw = yaw if yaw else self.Poly() + + +class TrajectoryMemory(MemoryElement): + """ + Memory interface for trajectories used by the high level commander + """ + + def __init__(self, id, type, size, mem_handler): + """Initialize trajectory memory""" + super(TrajectoryMemory, self).__init__(id=id, type=type, size=size, + mem_handler=mem_handler) + self._write_finished_cb = None + + # A list of Poly4D objects to write to the Crazyflie + self.poly4Ds = [] + + def write_data(self, write_finished_cb): + """Write trajectory data to the Crazyflie""" + self._write_finished_cb = write_finished_cb + data = bytearray() + + for poly4D in self.poly4Ds: + data += struct.pack('<ffffffff', *poly4D.x.values) + data += struct.pack('<ffffffff', *poly4D.y.values) + data += struct.pack('<ffffffff', *poly4D.z.values) + data += struct.pack('<ffffffff', *poly4D.yaw.values) + data += struct.pack('<f', poly4D.duration) + + self.mem_handler.write(self, 0x00, data, flush_queue=True) + + def write_done(self, mem, addr): + if self._write_finished_cb and mem.id == self.id: + logger.debug('Write trajectory data done') + self._write_finished_cb(self, addr) + self._write_finished_cb = None + + def disconnect(self): + self._write_finished_cb = None + + +class LighthouseBsGeometry: + """Container for geometry data of one Lighthouse base station""" + + SIZE_FLOAT = 4 + SIZE_VECTOR = 3 * SIZE_FLOAT + SIZE_GEOMETRY = (1 + 3) * SIZE_VECTOR + SIZE_DATA = 2 * SIZE_GEOMETRY + + def __init__(self): + self.origin = [0.0, 0.0, 0.0] + self.rotation_matrix = [ + [0.0, 0.0, 0.0], + [0.0, 0.0, 0.0], + [0.0, 0.0, 0.0], + ] + + def set_from_mem_data(self, data): + self.origin = self._read_vector( + data[0 * self.SIZE_VECTOR:1 * self.SIZE_VECTOR]) + self.rotation_matrix = [ + self._read_vector(data[1 * self.SIZE_VECTOR:2 * self.SIZE_VECTOR]), + self._read_vector(data[2 * self.SIZE_VECTOR:3 * self.SIZE_VECTOR]), + self._read_vector(data[3 * self.SIZE_VECTOR:4 * self.SIZE_VECTOR]), + ] + + def add_mem_data(self, data): + self._add_vector(data, self.origin) + self._add_vector(data, self.rotation_matrix[0]) + self._add_vector(data, self.rotation_matrix[1]) + self._add_vector(data, self.rotation_matrix[2]) + + def _add_vector(self, data, vector): + data += struct.pack('<fff', vector[0], vector[1], vector[2]) + + def _read_vector(self, data): + x, y, z = struct.unpack('<fff', data) + return [x, y, z] + + def dump(self): + print('origin:', self.origin) + print('rotation matrix: ', self.rotation_matrix) + + +class LighthouseMemory(MemoryElement): + """ + Memory interface for lighthouse configuration data + """ + + def __init__(self, id, type, size, mem_handler): + """Initialize Lighthouse memory""" + super(LighthouseMemory, self).__init__(id=id, type=type, size=size, + mem_handler=mem_handler) + + self._update_finished_cb = None + self._write_finished_cb = None + + # Geometry data for two base stations + self.geometry_data = [ + LighthouseBsGeometry(), + LighthouseBsGeometry(), + ] + + def new_data(self, mem, addr, data): + """Callback for when new memory data has been fetched""" + if mem.id == self.id: + if addr == 0: + self.geometry_data[0].set_from_mem_data( + data[0:LighthouseBsGeometry.SIZE_GEOMETRY]) + self.geometry_data[1].set_from_mem_data( + data[LighthouseBsGeometry.SIZE_GEOMETRY:]) + + if self._update_finished_cb: + self._update_finished_cb(self) + self._update_finished_cb = None + + def update(self, update_finished_cb): + """Request an update of the memory content""" + if not self._update_finished_cb: + self._update_finished_cb = update_finished_cb + logger.debug('Updating content of memory {}'.format(self.id)) + self.mem_handler.read(self, 0, LighthouseBsGeometry.SIZE_DATA) + + def write_data(self, write_finished_cb): + """Write geometry data to the Crazyflie""" + self._write_finished_cb = write_finished_cb + data = bytearray() + + for bs in self.geometry_data: + bs.add_mem_data(data) + + self.mem_handler.write(self, 0x00, data, flush_queue=True) + + def write_done(self, mem, addr): + if self._write_finished_cb and mem.id == self.id: + logger.debug('Write of geometry data done') + self._write_finished_cb(self, addr) + self._write_finished_cb = None + + def disconnect(self): + self._update_finished_cb = None + self._write_finished_cb = None + + def dump(self): + for data in self.geometry_data: + data.dump() + + +class MemoryTester(MemoryElement): + """ + Memory interface for testing the memory sub system, end to end. + + Usage + 1. To verify reading: + * Call read_data() + * Wait for the callback to be called + * Verify that readValidationSucess is True + + 2. To verify writing: + * Set the parameter 'memTst.resetW' in the CF + * call write_data() + * Wait for the callback + * Read the log var 'memTst.errCntW' from the CF and validate that it + is 0 + """ + + def __init__(self, id, type, size, mem_handler): + """Initialize Memory tester""" + super(MemoryTester, self).__init__(id=id, type=type, size=size, + mem_handler=mem_handler) + + self._update_finished_cb = None + self._write_finished_cb = None + + self.readValidationSucess = True + + def new_data(self, mem, start_address, data): + """Callback for when new memory data has been fetched""" + if mem.id == self.id: + for i in range(len(data)): + actualValue = struct.unpack('<B', data[i:i + 1])[0] + expectedValue = (start_address + i) & 0xff + + if (actualValue != expectedValue): + address = start_address + i + self.readValidationSucess = False + logger.error( + 'Error in data - expected: {}, actual: {}, address:{}', + expectedValue, actualValue, address) + + if self._update_finished_cb: + self._update_finished_cb(self) + self._update_finished_cb = None + + def read_data(self, start_address, size, update_finished_cb): + """Request an update of the memory content""" + if not self._update_finished_cb: + self._update_finished_cb = update_finished_cb + logger.debug('Reading memory {}'.format(self.id)) + self.mem_handler.read(self, start_address, size) + + def write_data(self, start_address, size, write_finished_cb): + """Write data to the Crazyflie""" + self._write_finished_cb = write_finished_cb + data = bytearray() + + for i in range(size): + value = (start_address + i) & 0xff + data += struct.pack('<B', value) + + self.mem_handler.write(self, start_address, data, flush_queue=True) + + def write_done(self, mem, addr): + if self._write_finished_cb and mem.id == self.id: + logger.debug('Write of data finished') + self._write_finished_cb(self, addr) + self._write_finished_cb = None + + def disconnect(self): + self._update_finished_cb = None + self._write_finished_cb = None + + class _ReadRequest: """ Class used to handle memory reads that will split up the read in multiple @@ -527,7 +921,7 @@ class _ReadRequest: self._request_new_chunk() def resend(self): - logger.info('Sending write again...') + logger.debug('Sending write again...') self._request_new_chunk() def _request_new_chunk(self): @@ -539,7 +933,7 @@ class _ReadRequest: if new_len > _ReadRequest.MAX_DATA_LENGTH: new_len = _ReadRequest.MAX_DATA_LENGTH - logger.info('Requesting new chunk of {}bytes at 0x{:X}'.format( + logger.debug('Requesting new chunk of {}bytes at 0x{:X}'.format( new_len, self._current_addr)) # Request the data for the next address @@ -597,7 +991,7 @@ class _WriteRequest: self._write_new_chunk() def resend(self): - logger.info('Sending write again...') + logger.debug('Sending write again...') self.cf.send_packet( self._sent_packet, expected_reply=self._sent_reply, timeout=1) @@ -610,7 +1004,7 @@ class _WriteRequest: if new_len > _WriteRequest.MAX_DATA_LENGTH: new_len = _WriteRequest.MAX_DATA_LENGTH - logger.info('Writing new chunk of {}bytes at 0x{:X}'.format( + logger.debug('Writing new chunk of {}bytes at 0x{:X}'.format( new_len, self._current_addr)) data = self._data[:new_len] @@ -641,7 +1035,7 @@ class _WriteRequest: self._write_new_chunk() return False else: - logger.info('This write request is done') + logger.debug('This write request is done') return True @@ -661,7 +1055,6 @@ class Memory(): def __init__(self, crazyflie=None): """Instantiate class and connect callbacks""" - self.mems = [] # Called when new memories have been added self.mem_added_cb = Caller() # Called when new data has been read @@ -672,18 +1065,20 @@ class Memory(): self.cf = crazyflie self.cf.add_port_callback(CRTPPort.MEM, self._new_packet_cb) self.cf.disconnected.add_callback(self._disconnected) + self._write_requests_lock = Lock() + self._clear_state() + + def _clear_state(self): + self.mems = [] self._refresh_callback = None self._fetch_id = 0 self.nbr_of_mems = 0 self._ow_mem_fetch_index = 0 self._elem_data = () self._read_requests = {} - self._read_requests_lock = Lock() self._write_requests = {} - self._write_requests_lock = Lock() self._ow_mems_left_to_update = [] - self._getting_count = False def _mem_update_done(self, mem): @@ -694,7 +1089,7 @@ class Memory(): if mem.id in self._ow_mems_left_to_update: self._ow_mems_left_to_update.remove(mem.id) - logger.info(mem) + logger.debug(mem) if len(self._ow_mems_left_to_update) == 0: if self._refresh_callback: @@ -778,7 +1173,7 @@ class Memory(): self.nbr_of_mems = 0 self._getting_count = False - logger.info('Requesting number of memories') + logger.debug('Requesting number of memories') pk = CRTPPacket() pk.set_header(CRTPPort.MEM, CHAN_INFO) pk.data = (CMD_INFO_NBR,) @@ -786,12 +1181,7 @@ class Memory(): def _disconnected(self, uri): """The link to the Crazyflie has been broken. Reset state""" - for m in self.mems: - try: - m.disconnect() - except Exception as e: - logger.info( - 'Error when resetting after disconnect: {}'.format(e)) + self._clear_state() def _new_packet_cb(self, packet): """Callback for newly arrived packets for the memory port""" @@ -809,7 +1199,7 @@ class Memory(): if self.nbr_of_mems > 0: if not self._getting_count: self._getting_count = True - logger.info('Requesting first id') + logger.debug('Requesting first id') pk = CRTPPacket() pk.set_header(CRTPPort.MEM, CHAN_INFO) pk.data = (CMD_INFO_DETAILS, 0) @@ -864,26 +1254,47 @@ class Memory(): elif mem_type == MemoryElement.TYPE_DRIVER_LED: mem = LEDDriverMemory(id=mem_id, type=mem_type, size=mem_size, mem_handler=self) - logger.info(mem) + logger.debug(mem) self.mem_read_cb.add_callback(mem.new_data) self.mem_write_cb.add_callback(mem.write_done) elif mem_type == MemoryElement.TYPE_LOCO: mem = LocoMemory(id=mem_id, type=mem_type, size=mem_size, mem_handler=self) - logger.info(mem) + logger.debug(mem) + self.mem_read_cb.add_callback(mem.new_data) + elif mem_type == MemoryElement.TYPE_TRAJ: + mem = TrajectoryMemory(id=mem_id, type=mem_type, + size=mem_size, mem_handler=self) + logger.debug(mem) + self.mem_write_cb.add_callback(mem.write_done) + elif mem_type == MemoryElement.TYPE_LOCO2: + mem = LocoMemory2(id=mem_id, type=mem_type, + size=mem_size, mem_handler=self) + logger.debug(mem) self.mem_read_cb.add_callback(mem.new_data) + elif mem_type == MemoryElement.TYPE_LH: + mem = LighthouseMemory(id=mem_id, type=mem_type, + size=mem_size, mem_handler=self) + logger.debug(mem) + self.mem_read_cb.add_callback(mem.new_data) + self.mem_write_cb.add_callback(mem.write_done) + elif mem_type == MemoryElement.TYPE_MEMORY_TESTER: + mem = MemoryTester(id=mem_id, type=mem_type, + size=mem_size, mem_handler=self) + logger.debug(mem) + self.mem_read_cb.add_callback(mem.new_data) + self.mem_write_cb.add_callback(mem.write_done) else: mem = MemoryElement(id=mem_id, type=mem_type, size=mem_size, mem_handler=self) - logger.info(mem) + logger.debug(mem) self.mems.append(mem) self.mem_added_cb.call(mem) - # logger.info(mem) self._fetch_id = mem_id + 1 if self.nbr_of_mems - 1 >= self._fetch_id: - logger.info( + logger.debug( 'Requesting information about memory {}'.format( self._fetch_id)) pk = CRTPPacket() @@ -892,7 +1303,7 @@ class Memory(): self.cf.send_packet(pk, expected_reply=( CMD_INFO_DETAILS, self._fetch_id)) else: - logger.info( + logger.debug( 'Done getting all the memories, start reading the OWs') ows = self.get_mems(MemoryElement.TYPE_1W) # If there are any OW mems start reading them, otherwise @@ -907,7 +1318,7 @@ class Memory(): if chan == CHAN_WRITE: id = cmd (addr, status) = struct.unpack('<IB', payload[0:5]) - logger.info( + logger.debug( 'WRITE: Mem={}, addr=0x{:X}, status=0x{}'.format( id, addr, status)) # Find the read request @@ -925,7 +1336,8 @@ class Memory(): if len(self._write_requests[id]) > 0: self._write_requests[id][0].start() else: - logger.info('Status {}: write resending...'.format(status)) + logger.debug( + 'Status {}: write resending...'.format(status)) wreq.resend() self._write_requests_lock.release() @@ -933,11 +1345,11 @@ class Memory(): id = cmd (addr, status) = struct.unpack('<IB', payload[0:5]) data = struct.unpack('B' * len(payload[5:]), payload[5:]) - logger.info('READ: Mem={}, addr=0x{:X}, status=0x{}, ' - 'data={}'.format(id, addr, status, data)) + logger.debug('READ: Mem={}, addr=0x{:X}, status=0x{}, ' + 'data={}'.format(id, addr, status, data)) # Find the read request if id in self._read_requests: - logger.info( + logger.debug( 'READING: We are still interested in request for ' 'mem {}'.format(id)) rreq = self._read_requests[id] @@ -946,5 +1358,5 @@ class Memory(): self._read_requests.pop(id, None) self.mem_read_cb.call(rreq.mem, rreq.addr, rreq.data) else: - logger.info('Status {}: resending...'.format(status)) + logger.debug('Status {}: resending...'.format(status)) rreq.resend() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/param.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/param.py index a04ef035..b8b42d2d 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/param.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/param.py @@ -63,13 +63,9 @@ TOC_CHANNEL = 0 READ_CHANNEL = 1 WRITE_CHANNEL = 2 -# TOC access command -TOC_RESET = 0 -TOC_GETNEXT = 1 -TOC_GETCRC32 = 2 +# One element entry in the TOC -# One element entry in the TOC class ParamTocElement: """An element in the Log TOC.""" @@ -88,10 +84,11 @@ class ParamTocElement: 0x06: ('float', '<f'), 0x07: ('double', '<d')} - def __init__(self, data=None): + def __init__(self, ident=0, data=None): """TocElement creator. Data is the binary payload of the element.""" + self.ident = ident if (data): - strs = struct.unpack('s' * len(data[2:]), data[2:]) + strs = struct.unpack('s' * len(data[1:]), data[1:]) if sys.version_info < (3,): strs = ('{}' * len(strs)).format(*strs).split('\0') else: @@ -102,12 +99,7 @@ class ParamTocElement: self.group = strs[0] self.name = strs[1] - if type(data[0]) == str: - self.ident = ord(data[0]) - else: - self.ident = data[0] - - metadata = data[1] + metadata = data[0] if type(metadata) == str: metadata = ord(metadata) @@ -133,12 +125,14 @@ class Param(): self.toc = Toc() self.cf = crazyflie + self._useV2 = False self.param_update_callbacks = {} self.group_update_callbacks = {} self.all_update_callback = Caller() self.param_updater = None - self.param_updater = _ParamUpdater(self.cf, self._param_updated) + self.param_updater = _ParamUpdater( + self.cf, self._useV2, self._param_updated) self.param_updater.start() self.cf.disconnected.add_callback(self._disconnected) @@ -169,10 +163,16 @@ class Param(): def _param_updated(self, pk): """Callback with data for an updated parameter""" - var_id = pk.data[0] + if self._useV2: + var_id = struct.unpack('<H', pk.data[:2])[0] + else: + var_id = pk.data[0] element = self.toc.get_element_by_id(var_id) if element: - s = struct.unpack(element.pytype, pk.data[1:])[0] + if self._useV2: + s = struct.unpack(element.pytype, pk.data[2:])[0] + else: + s = struct.unpack(element.pytype, pk.data[1:])[0] s = s.__str__() complete_name = '%s.%s' % (element.group, element.name) @@ -233,6 +233,7 @@ class Param(): """ Initiate a refresh of the parameter TOC. """ + self._useV2 = self.cf.platform.get_protocol_version() >= 4 toc_fetcher = TocFetcher(self.cf, ParamTocElement, CRTPPort.PARAM, self.toc, refresh_done_callback, toc_cache) @@ -271,8 +272,17 @@ class Param(): varid = element.ident pk = CRTPPacket() pk.set_header(CRTPPort.PARAM, WRITE_CHANNEL) - pk.data = struct.pack('<B', varid) - pk.data += struct.pack(element.pytype, eval(value)) + if self._useV2: + pk.data = struct.pack('<H', varid) + else: + pk.data = struct.pack('<B', varid) + + try: + value_nr = eval(value) + except TypeError: + value_nr = value + + pk.data += struct.pack(element.pytype, value_nr) self.param_updater.request_param_setvalue(pk) @@ -280,12 +290,13 @@ class _ParamUpdater(Thread): """This thread will update params through a queue to make sure that we get back values""" - def __init__(self, cf, updated_callback): + def __init__(self, cf, useV2, updated_callback): """Initialize the thread""" Thread.__init__(self) self.setDaemon(True) self.wait_lock = Lock() self.cf = cf + self._useV2 = useV2 self.updated_callback = updated_callback self.request_queue = Queue() self.cf.add_port_callback(CRTPPort.PARAM, self._new_packet_cb) @@ -300,7 +311,7 @@ class _ParamUpdater(Thread): # we didn't get back due to a disconnect for example. try: self.wait_lock.release() - except: + except Exception: pass def request_param_setvalue(self, pk): @@ -311,21 +322,30 @@ class _ParamUpdater(Thread): def _new_packet_cb(self, pk): """Callback for newly arrived packets""" if pk.channel == READ_CHANNEL or pk.channel == WRITE_CHANNEL: - var_id = pk.data[0] + if self._useV2: + var_id = struct.unpack('<H', pk.data[:2])[0] + if pk.channel == READ_CHANNEL: + pk.data = pk.data[:2] + pk.data[3:] + else: + var_id = pk.data[0] if (pk.channel != TOC_CHANNEL and self._req_param == var_id and pk is not None): self.updated_callback(pk) self._req_param = -1 try: self.wait_lock.release() - except: + except Exception: pass def request_param_update(self, var_id): """Place a param update request on the queue""" + self._useV2 = self.cf.platform.get_protocol_version() >= 4 pk = CRTPPacket() pk.set_header(CRTPPort.PARAM, READ_CHANNEL) - pk.data = struct.pack('<B', var_id) + if self._useV2: + pk.data = struct.pack('<H', var_id) + else: + pk.data = struct.pack('<B', var_id) logger.debug('Requesting request to update param [%d]', var_id) self.request_queue.put(pk) @@ -334,7 +354,13 @@ class _ParamUpdater(Thread): pk = self.request_queue.get() # Wait for request update self.wait_lock.acquire() if self.cf.link: - self._req_param = pk.data[0] - self.cf.send_packet(pk, expected_reply=(tuple(pk.data[0:2]))) + if self._useV2: + self._req_param = struct.unpack('<H', pk.data[:2])[0] + self.cf.send_packet( + pk, expected_reply=(tuple(pk.data[:2]))) + else: + self._req_param = pk.data[0] + self.cf.send_packet( + pk, expected_reply=(tuple(pk.data[:1]))) else: self.wait_lock.release() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/platformservice.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/platformservice.py index ad922db1..ff442cb3 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/platformservice.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/platformservice.py @@ -27,12 +27,26 @@ """ Used for sending control setpoints to the Crazyflie """ +import logging + from cflib.crtp.crtpstack import CRTPPacket from cflib.crtp.crtpstack import CRTPPort __author__ = 'Bitcraze AB' __all__ = ['PlatformService'] +logger = logging.getLogger(__name__) + +PLATFORM_COMMAND = 0 +VERSION_COMMAND = 1 + +PLATFORM_SET_CONT_WAVE = 0 + +VERSION_GET_PROTOCOL = 0 +VERSION_GET_FIRMWARE = 1 + +LINKSERVICE_SOURCE = 1 + class PlatformService(): """ @@ -45,12 +59,72 @@ class PlatformService(): """ self._cf = crazyflie + self._cf.add_port_callback(CRTPPort.PLATFORM, + self._platform_callback) + self._cf.add_port_callback(CRTPPort.LINKCTRL, + self._crt_service_callback) + + # Request protocol version. + # The semaphore makes sure that other module will wait for the version + # to be received before using it. + self._has_protocol_version = False + self._protocolVersion = -1 + self._callback = None + + def fetch_platform_informations(self, callback): + """ + Fetch platform info from the firmware + Should be called at the earliest in the connection sequence + """ + + self._protocolVersion = -1 + self._callback = callback + + self._request_protocol_version() + def set_continous_wave(self, enabled): """ Enable/disable the client side X-mode. When enabled this recalculates the setpoints before sending them to the Crazyflie. """ pk = CRTPPacket() - pk.set_header(CRTPPort.PLATFORM, 0) + pk.set_header(CRTPPort.PLATFORM, PLATFORM_COMMAND) pk.data = (0, enabled) self._cf.send_packet(pk) + + def get_protocol_version(self): + """ + Return version of the CRTP protocol + """ + return self._protocolVersion + + def _request_protocol_version(self): + # Sending a sink request to detect if the connected Crazyflie + # supports protocol versioning + pk = CRTPPacket() + pk.set_header(CRTPPort.LINKCTRL, LINKSERVICE_SOURCE) + pk.data = (0,) + self._cf.send_packet(pk) + + def _crt_service_callback(self, pk): + if pk.channel == LINKSERVICE_SOURCE: + # If the sink contains a magic string, get the protocol version, + # otherwise -1 + if pk.data[:18].decode('utf8') == 'Bitcraze Crazyflie': + pk = CRTPPacket() + pk.set_header(CRTPPort.PLATFORM, VERSION_COMMAND) + pk.data = (VERSION_GET_PROTOCOL, ) + self._cf.send_packet(pk) + else: + self._protocolVersion = -1 + logger.info('Procotol version: {}'.format( + self.get_protocol_version())) + self._callback() + + def _platform_callback(self, pk): + if pk.channel == VERSION_COMMAND and \ + pk.data[0] == VERSION_GET_PROTOCOL: + self._protocolVersion = pk.data[1] + logger.info('Procotol version: {}'.format( + self.get_protocol_version())) + self._callback() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/swarm.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/swarm.py index 7bd53373..55bdc325 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/swarm.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/swarm.py @@ -23,15 +23,34 @@ # MA 02110-1301, USA. from threading import Thread +from cflib.crazyflie import Crazyflie from cflib.crazyflie.syncCrazyflie import SyncCrazyflie class _Factory: + """ + Default Crazyflie factory class. + """ def construct(self, uri): return SyncCrazyflie(uri) +class CachedCfFactory: + """ + Factory class that creates Crazyflie instances with TOC caching + to reduce connection time. + """ + + def __init__(self, ro_cache=None, rw_cache=None): + self.ro_cache = ro_cache + self.rw_cache = rw_cache + + def construct(self, uri): + cf = Crazyflie(ro_cache=self.ro_cache, rw_cache=self.rw_cache) + return SyncCrazyflie(uri, cf=cf) + + class Swarm: """ Runs a swarm of Crazyflies. It implements a functional-ish style of diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncCrazyflie.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncCrazyflie.py index 12dfdcef..cfd95890 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncCrazyflie.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncCrazyflie.py @@ -50,18 +50,17 @@ class SyncCrazyflie: self._is_link_open = False self._error_message = None - self.cf.connected.add_callback(self._connected) - self.cf.connection_failed.add_callback(self._connection_failed) - self.cf.disconnected.add_callback(self._disconnected) - def open_link(self): if (self.is_link_open()): raise Exception('Link already open') + self._add_callbacks() + print('Connecting to %s' % self._link_uri) self.cf.open_link(self._link_uri) self._connect_event.wait() if not self._is_link_open: + self._remove_callbacks() raise Exception(self._error_message) def __enter__(self): @@ -70,6 +69,7 @@ class SyncCrazyflie: def close_link(self): self.cf.close_link() + self._remove_callbacks() self._is_link_open = False def __exit__(self, exc_type, exc_val, exc_tb): @@ -94,4 +94,21 @@ class SyncCrazyflie: self._connect_event.set() def _disconnected(self, link_uri): + self._remove_callbacks() self._is_link_open = False + + def _add_callbacks(self): + self.cf.connected.add_callback(self._connected) + self.cf.connection_failed.add_callback(self._connection_failed) + self.cf.disconnected.add_callback(self._disconnected) + + def _remove_callbacks(self): + def remove_callback(container, callback): + try: + container.remove_callback(callback) + except ValueError: + pass + + remove_callback(self.cf.connected, self._connected) + remove_callback(self.cf.connection_failed, self._connection_failed) + remove_callback(self.cf.disconnected, self._disconnected) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncLogger.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncLogger.py index 3bf6560d..5fc95888 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncLogger.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncLogger.py @@ -6,7 +6,7 @@ # +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ # || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ # -# Copyright (C) 2016 Bitcraze AB +# Copyright (C) 2016-2020 Bitcraze AB # # Crazyflie Nano Quadcopter Client # @@ -27,7 +27,7 @@ This class provides synchronous access to log data from the Crazyflie. It acts as an iterator and returns the next value on each iteration. -If no value is available it blocks until log data is available again. +If no value is available it blocks until log data is received again. """ import sys @@ -46,15 +46,18 @@ class SyncLogger: """ Construct an instance of a SyncLogger - Takes an Crazyflie or SyncCrazyflie instance and a log configuration + Takes an Crazyflie or SyncCrazyflie instance and one log configuration + or an array of log configurations """ if isinstance(crazyflie, SyncCrazyflie): self._cf = crazyflie.cf else: self._cf = crazyflie - self._log_config = log_config - self._cf.log.add_config(self._log_config) + if isinstance(log_config, list): + self._log_config = log_config + else: + self._log_config = [log_config] self._queue = Queue() @@ -65,21 +68,23 @@ class SyncLogger: raise Exception('Already connected') self._cf.disconnected.add_callback(self._disconnected) - self._log_config.data_received_cb.add_callback(self._log_callback) - self._log_config.start() + for config in self._log_config: + self._cf.log.add_config(config) + config.data_received_cb.add_callback(self._log_callback) + config.start() self._is_connected = True def disconnect(self): if self._is_connected: - self._log_config.stop() - self._log_config.delete() + for config in self._log_config: + config.stop() + config.delete() - self._log_config.data_received_cb.remove_callback( - self._log_callback) - self._cf.disconnected.remove_callback(self._disconnected) + config.data_received_cb.remove_callback( + self._log_callback) - self._queue.empty() + self._cf.disconnected.remove_callback(self._disconnected) self._is_connected = False @@ -89,6 +94,9 @@ class SyncLogger: def __iter__(self): return self + def next(self): + return self.__next__() + def __next__(self): if not self._is_connected: raise StopIteration @@ -96,6 +104,7 @@ class SyncLogger: data = self._queue.get() if data == self.DISCONNECT_EVENT: + self._queue.empty() raise StopIteration return data @@ -106,10 +115,11 @@ class SyncLogger: def __exit__(self, exc_type, exc_val, exc_tb): self.disconnect() + self._queue.empty() def _log_callback(self, ts, data, logblock): self._queue.put((ts, data, logblock)) def _disconnected(self, link_uri): - self._queue.put(self.DISCONNECT_EVENT) self.disconnect() + self._queue.put(self.DISCONNECT_EVENT) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/toc.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/toc.py index d722e32a..12f085ea 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/toc.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/toc.py @@ -41,8 +41,10 @@ logger = logging.getLogger(__name__) TOC_CHANNEL = 0 # Commands used when accessing the Table of Contents -CMD_TOC_ELEMENT = 0 -CMD_TOC_INFO = 1 +CMD_TOC_ELEMENT = 0 # original version: up to 255 entries +CMD_TOC_INFO = 1 # original version: up to 255 entries +CMD_TOC_ITEM_V2 = 2 # version 2: up to 16k entries +CMD_TOC_INFO_V2 = 3 # version 2: up to 16k entries # Possible states when receiving TOC IDLE = 'IDLE' @@ -121,9 +123,14 @@ class TocFetcher: self._toc_cache = toc_cache self.finished_callback = finished_callback self.element_class = element_class + self._useV2 = False def start(self): """Initiate fetching of the TOC.""" + self._useV2 = self.cf.platform.get_protocol_version() >= 4 + + logger.debug('[%d]: Using V2 protocol: %d', self.port, self._useV2) + logger.debug('[%d]: Start fetching...', self.port) # Register callback in this class for the port self.cf.add_port_callback(self.port, self._new_packet_cb) @@ -132,8 +139,12 @@ class TocFetcher: self.state = GET_TOC_INFO pk = CRTPPacket() pk.set_header(self.port, TOC_CHANNEL) - pk.data = (CMD_TOC_INFO,) - self.cf.send_packet(pk, expected_reply=(CMD_TOC_INFO,)) + if self._useV2: + pk.data = (CMD_TOC_INFO_V2,) + self.cf.send_packet(pk, expected_reply=(CMD_TOC_INFO_V2,)) + else: + pk.data = (CMD_TOC_INFO,) + self.cf.send_packet(pk, expected_reply=(CMD_TOC_INFO,)) def _toc_fetch_finished(self): """Callback for when the TOC fetching is finished""" @@ -149,7 +160,12 @@ class TocFetcher: payload = packet.data[1:] if (self.state == GET_TOC_INFO): - [self.nbr_of_items, self._crc] = struct.unpack('<BI', payload[:5]) + if self._useV2: + [self.nbr_of_items, self._crc] = struct.unpack( + '<HI', payload[:6]) + else: + [self.nbr_of_items, self._crc] = struct.unpack( + '<BI', payload[:5]) logger.debug('[%d]: Got TOC CRC, %d items and crc=0x%08X', self.port, self.nbr_of_items, self._crc) @@ -166,11 +182,18 @@ class TocFetcher: elif (self.state == GET_TOC_ELEMENT): # Always add new element, but only request new if it's not the # last one. - if self.requested_index != payload[0]: + if self._useV2: + ident = struct.unpack('<H', payload[:2])[0] + else: + ident = payload[0] + + if ident != self.requested_index: return - self.toc.add_element(self.element_class(payload)) - logger.debug('Added element [%s]', - self.element_class(payload).ident) + if self._useV2: + self.toc.add_element(self.element_class(ident, payload[2:])) + else: + self.toc.add_element(self.element_class(ident, payload[1:])) + logger.debug('Added element [%s]', ident) if (self.requested_index < (self.nbr_of_items - 1)): logger.debug('[%d]: More variables, requesting index %d', self.port, self.requested_index + 1) @@ -184,6 +207,12 @@ class TocFetcher: """Request information about a specific item in the TOC""" logger.debug('Requesting index %d on port %d', index, self.port) pk = CRTPPacket() - pk.set_header(self.port, TOC_CHANNEL) - pk.data = (CMD_TOC_ELEMENT, index) - self.cf.send_packet(pk, expected_reply=(CMD_TOC_ELEMENT, index)) + if self._useV2: + pk.set_header(self.port, TOC_CHANNEL) + pk.data = (CMD_TOC_ITEM_V2, index & 0x0ff, (index >> 8) & 0x0ff) + self.cf.send_packet(pk, expected_reply=( + CMD_TOC_ITEM_V2, index & 0x0ff, (index >> 8) & 0x0ff)) + else: + pk.set_header(self.port, TOC_CHANNEL) + pk.data = (CMD_TOC_ELEMENT, index) + self.cf.send_packet(pk, expected_reply=(CMD_TOC_ELEMENT, index)) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/__init__.py index 9f7ce32e..33758bde 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/__init__.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/__init__.py @@ -29,6 +29,7 @@ import logging from .debugdriver import DebugDriver from .exceptions import WrongUriType +from .prrtdriver import PrrtDriver from .radiodriver import RadioDriver from .serialdriver import SerialDriver from .udpdriver import UdpDriver @@ -40,7 +41,8 @@ __all__ = [] logger = logging.getLogger(__name__) -DRIVERS = [RadioDriver, SerialDriver, UdpDriver, DebugDriver, UsbDriver] +DRIVERS = [RadioDriver, SerialDriver, UdpDriver, + DebugDriver, UsbDriver, PrrtDriver] CLASSES = [] diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/crtpstack.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/crtpstack.py index dca9e67f..74c5d98d 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/crtpstack.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/crtpstack.py @@ -47,6 +47,7 @@ class CRTPPort: LOGGING = 0x05 LOCALIZATION = 0x06 COMMANDER_GENERIC = 0x07 + SETPOINT_HL = 0x08 PLATFORM = 0x0D DEBUGDRIVER = 0x0E LINKCTRL = 0x0F diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/debugdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/debugdriver.py index 86e8b3db..65abc8ce 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/debugdriver.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/debugdriver.py @@ -316,18 +316,18 @@ class DebugDriver(CRTPDriver): self._packet_handler._random_answer_delay = False self._packet_handler._random_toc_crcs = False - if (re.search('^debug://.*/1\Z', uri)): + if (re.search('^debug://.*/1$', uri)): self._packet_handler.inhibitAnswers = True - if (re.search('^debug://.*/110\Z', uri)): + if (re.search('^debug://.*/110$', uri)): self._packet_handler.bootloader = True - if (re.search('^debug://.*/2\Z', uri)): + if (re.search('^debug://.*/2$', uri)): self._packet_handler.doIncompleteLogTOC = True - if (re.search('^debug://.*/3\Z', uri)): + if (re.search('^debug://.*/3$', uri)): self._packet_handler._random_answer_delay = True - if (re.search('^debug://.*/4\Z', uri)): + if (re.search('^debug://.*/4$', uri)): self._packet_handler._random_answer_delay = True self._packet_handler._random_toc_crcs = True - if (re.search('^debug://.*/5\Z', uri)): + if (re.search('^debug://.*/5$', uri)): self._packet_handler._random_toc_crcs = True if len(self._fake_mems) == 0: @@ -359,7 +359,7 @@ class DebugDriver(CRTPDriver): FakeMemory(type=1, size=112, addr=0x1234567890ABCDEE, data=[0x00 for a in range(112)])) - if (re.search('^debug://.*/6\Z', uri)): + if (re.search('^debug://.*/6$', uri)): logger.info('------------->Erasing memories on connect') for m in self._fake_mems: m.erase() @@ -572,19 +572,19 @@ class _PacketHandlingThread(Thread): ' it 0 !', pk.port) if (pk.port == CRTPPort.LOGGING): - l = self.fakeLogToc[varIndex] + entry = self.fakeLogToc[varIndex] if (pk.port == CRTPPort.PARAM): - l = self.fakeParamToc[varIndex] + entry = self.fakeParamToc[varIndex] - vartype = l['vartype'] - if (pk.port == CRTPPort.PARAM and l['writable'] is True): + vartype = entry['vartype'] + if (pk.port == CRTPPort.PARAM and entry['writable'] is True): vartype = vartype | (0x10) - p.data = struct.pack('<BBB', cmd, l['varid'], vartype) - for ch in l['vargroup']: + p.data = struct.pack('<BBB', cmd, entry['varid'], vartype) + for ch in entry['vargroup']: p.data.append(ord(ch)) p.data.append(0) - for ch in l['varname']: + for ch in entry['varname']: p.data.append(ord(ch)) p.data.append(0) if (self.doIncompleteLogTOC is False): diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/prrtdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/prrtdriver.py new file mode 100644 index 00000000..81e4b929 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/prrtdriver.py @@ -0,0 +1,104 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- +import datetime +import logging +import re + +from .crtpstack import CRTPPacket +from .exceptions import WrongUriType +from cflib.crtp.crtpdriver import CRTPDriver + +prrt_installed = True +try: + import prrt +except ImportError: + prrt_installed = False + +__author__ = 'Bitcraze AB' +__all__ = ['PrrtDriver'] + +logger = logging.getLogger(__name__) + +MAX_PAYLOAD = 32 +DEFAULT_TARGET_DELAY = 0.05 # unit: s +PRRT_LOCAL_PORT = 5000 + + +class PrrtDriver(CRTPDriver): + + def __init__(self): + CRTPDriver.__init__(self) + self.prrt_socket = None + self.uri = '' + self.link_error_callback = None + self.packet_log = None + self.log_index = 0 + logger.info('Initialized PRRT driver.') + + def connect(self, uri, linkQualityCallback, linkErrorCallback): + # check if the URI is a PRRT URI + if not re.search('^prrt://', uri): + raise WrongUriType('Not a prrt URI') + + # Check if it is a valid PRRT URI + uri_match = re.search(r'^prrt://((?:[\d]{1,3})\.(?:[\d]{1,3})\.' + r'(?:[\d]{1,3})\.(?:[\d]{1,3})):([\d]{1,5})' + r'(?:/([\d]{1,6}))?$', uri) + if not uri_match: + raise Exception('Invalid PRRT URI') + + if not prrt_installed: + raise Exception('PRRT is missing') + + self.uri = uri + + self.link_error_callback = linkErrorCallback + + address = uri_match.group(1) + port = int(uri_match.group(2)) + target_delay_s = DEFAULT_TARGET_DELAY + if uri_match.group(3): + target_delay_s = int(uri_match.group(3)) / 1000 + + self.prrt_socket = prrt.PrrtSocket(('0.0.0.0', PRRT_LOCAL_PORT), + maximum_payload_size=MAX_PAYLOAD, + target_delay=target_delay_s) + self.prrt_socket.connect((address, port)) + + def send_packet(self, pk): + pk_bytes = bytearray([pk.get_header()]) + pk.data + self.prrt_socket.send(pk_bytes) + + def receive_packet(self, wait=0): + try: + if wait == 0: + pk_bytes, _ = self.prrt_socket.receive_asap() + elif wait < 0: + pk_bytes, _ = self.prrt_socket.receive_asap_wait() + else: + deadline = datetime.datetime.utcnow() + datetime.timedelta( + seconds=wait) + pk_bytes, _ = self.prrt_socket.receive_asap_timedwait(deadline) + except prrt.TimeoutException: + return None + + if len(pk_bytes) <= 0: + return None + + pk = CRTPPacket(pk_bytes[0], pk_bytes[1:]) + return pk + + def get_status(self): + return 'No information available' + + def get_name(self): + return 'prrt' + + def scan_interface(self, address): + default_uri = 'prrt://10.8.0.208:5000' + if prrt_installed: + return [[default_uri, ''], ] + return [] + + def close(self): + return diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/radiodriver.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/radiodriver.py index 8e6f4ebc..a0a86a8d 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/radiodriver.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/radiodriver.py @@ -39,6 +39,7 @@ import struct import sys import threading +import cflib.drivers.crazyradio as crazyradio from .crtpstack import CRTPPacket from .exceptions import WrongUriType from cflib.crtp.crtpdriver import CRTPDriver @@ -55,6 +56,9 @@ __all__ = ['RadioDriver'] logger = logging.getLogger(__name__) +_nr_of_retries = 100 +_nr_of_arc_retries = 3 + DEFAULT_ADDR_A = [0xe7, 0xe7, 0xe7, 0xe7, 0xe7] DEFAULT_ADDR = 0xE7E7E7E7E7 @@ -106,7 +110,7 @@ class _RadioManager(): if _RadioManager._radios[self._devid].usage_counter == 0: try: _RadioManager._radios[self._devid].radio.close() - except: + except Exception: pass _RadioManager._radios[self._devid] = None @@ -149,40 +153,11 @@ class RadioDriver(CRTPDriver): an error message. """ - # check if the URI is a radio URI - if not re.search('^radio://', uri): - raise WrongUriType('Not a radio URI') - - # Open the USB dongle - if not re.search('^radio://([0-9]+)((/([0-9]+))' - '((/(250K|1M|2M))?(/([A-F0-9]+))?)?)?$', uri): - raise WrongUriType('Wrong radio URI format!') - - uri_data = re.search('^radio://([0-9]+)((/([0-9]+))' - '((/(250K|1M|2M))?(/([A-F0-9]+))?)?)?$', uri) - + devid, channel, datarate, address = self.parse_uri(uri) self.uri = uri - channel = 2 - if uri_data.group(4): - channel = int(uri_data.group(4)) - - datarate = Crazyradio.DR_2MPS - if uri_data.group(7) == '250K': - datarate = Crazyradio.DR_250KPS - if uri_data.group(7) == '1M': - datarate = Crazyradio.DR_1MPS - if uri_data.group(7) == '2M': - datarate = Crazyradio.DR_2MPS - - address = DEFAULT_ADDR_A - if uri_data.group(9): - addr = str(uri_data.group(9)) - new_addr = struct.unpack('<BBBBB', binascii.unhexlify(addr)) - address = new_addr - if self._radio_manager is None: - self._radio_manager = _RadioManager(int(uri_data.group(1)), + self._radio_manager = _RadioManager(devid, channel, datarate, address) @@ -191,7 +166,7 @@ class RadioDriver(CRTPDriver): with self._radio_manager as cradio: if cradio.version >= 0.4: - cradio.set_arc(10) + cradio.set_arc(_nr_of_arc_retries) else: logger.warning('Radio version <0.4 will be obsoleted soon!') @@ -211,6 +186,50 @@ class RadioDriver(CRTPDriver): self.link_error_callback = link_error_callback + @staticmethod + def parse_uri(uri): + # check if the URI is a radio URI + if not re.search('^radio://', uri): + raise WrongUriType('Not a radio URI') + + # Open the USB dongle + if not re.search('^radio://([0-9a-fA-F]+)((/([0-9]+))' + '((/(250K|1M|2M))?(/([A-F0-9]+))?)?)?$', uri): + raise WrongUriType('Wrong radio URI format!') + + uri_data = re.search('^radio://([0-9a-fA-F]+)((/([0-9]+))' + '((/(250K|1M|2M))?(/([A-F0-9]+))?)?)?$', uri) + + if len(uri_data.group(1)) < 10 and uri_data.group(1).isdigit(): + devid = int(uri_data.group(1)) + else: + try: + devid = crazyradio.get_serials().index( + uri_data.group(1).upper()) + except ValueError: + raise Exception('Cannot find radio with serial {}'.format( + uri_data.group(1))) + + channel = 2 + if uri_data.group(4): + channel = int(uri_data.group(4)) + + datarate = Crazyradio.DR_2MPS + if uri_data.group(7) == '250K': + datarate = Crazyradio.DR_250KPS + if uri_data.group(7) == '1M': + datarate = Crazyradio.DR_1MPS + if uri_data.group(7) == '2M': + datarate = Crazyradio.DR_2MPS + + address = DEFAULT_ADDR_A + if uri_data.group(9): + addr = str(uri_data.group(9)) + new_addr = struct.unpack('<BBBBB', binascii.unhexlify(addr)) + address = new_addr + + return devid, channel, datarate, address + def receive_packet(self, time=0): """ Receive a packet though the link. This call is blocking but will @@ -389,8 +408,6 @@ class _RadioDriverThread(threading.Thread): Radio link receiver thread used to read data from the Crazyradio USB driver. """ - TRIES_BEFORE_DISCON = 10 - def __init__(self, radio_manager, inQueue, outQueue, link_quality_callback, link_error_callback, link): """ Create the object """ @@ -401,7 +418,7 @@ class _RadioDriverThread(threading.Thread): self._sp = False self._link_error_callback = link_error_callback self._link_quality_callback = link_quality_callback - self._retry_before_disconnect = _RadioDriverThread.TRIES_BEFORE_DISCON + self._retry_before_disconnect = _nr_of_retries self._retries = collections.deque() self._retry_sum = 0 @@ -497,8 +514,7 @@ class _RadioDriverThread(threading.Thread): self._link_error_callback is not None): self._link_error_callback('Too many packets lost') continue - self._retry_before_disconnect = \ - _RadioDriverThread.TRIES_BEFORE_DISCON + self._retry_before_disconnect = _nr_of_retries data = ackStatus.data @@ -536,3 +552,13 @@ class _RadioDriverThread(threading.Thread): dataOut.append(ord(X)) else: dataOut.append(0xFF) + + +def set_retries_before_disconnect(nr_of_retries): + global _nr_of_retries + _nr_of_retries = nr_of_retries + + +def set_retries(nr_of_arc_retries): + global _nr_of_arc_retries + _nr_of_arc_retries = nr_of_arc_retries diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/serialdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/serialdriver.py index 34c54036..2d7f36fc 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/serialdriver.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/serialdriver.py @@ -28,19 +28,58 @@ An early serial link driver. This could still be used (after some fixing) to run high-speed CRTP with the Crazyflie. The UART can be run at 2Mbit. """ +import logging import re +import sys +import threading -from .crtpdriver import CRTPDriver +from .crtpstack import CRTPPacket from .exceptions import WrongUriType +from cflib.crtp.crtpdriver import CRTPDriver + +if sys.version_info < (3,): + import Queue as queue +else: + import queue + +found_serial = True +try: + import serial + import serial.tools.list_ports as list_ports +except ImportError: + found_serial = False __author__ = 'Bitcraze AB' __all__ = ['SerialDriver'] +logger = logging.getLogger(__name__) + +MTU = 32 +START_BYTE1 = 0xbc +START_BYTE2 = 0xcf +SYSLINK_RADIO_RAW = 0x00 + + +def compute_cksum(list): + cksum0, cksum1 = 0, 0 + for i in range(len(list)): + cksum0 = (cksum0 + list[i]) & 0xff + cksum1 = (cksum1 + cksum0) & 0xff + return bytearray([cksum0, cksum1]) + class SerialDriver(CRTPDriver): def __init__(self): - None + CRTPDriver.__init__(self) + self.ser = None + self.uri = '' + self.link_error_callback = None + self.in_queue = None + self.out_queue = None + self._receive_thread = None + self._send_thread = None + logger.info('Initialized serial driver.') def connect(self, uri, linkQualityCallback, linkErrorCallback): # check if the URI is a serial URI @@ -48,12 +87,195 @@ class SerialDriver(CRTPDriver): raise WrongUriType('Not a serial URI') # Check if it is a valid serial URI - uriRe = re.search('^serial://([a-z A-Z 0-9]+)/?([0-9]+)?$', uri) - if not uriRe: + uri_data = re.search('^serial://([a-zA-Z0-9]+)$', uri) + if not uri_data: raise Exception('Invalid serial URI') + devices = [x.device for x in list_ports.comports() + if x.name == uri_data.group(1)] + if not len(devices) == 1: + raise Exception('Could not identify device') + device = devices[0] + + if not found_serial: + raise Exception('PySerial package is missing') + + self.uri = uri + + self.link_error_callback = linkErrorCallback + + # Prepare the inter-thread communication queue + self.in_queue = queue.Queue() + self.out_queue = queue.Queue(1) + + self.ser = serial.Serial(device, 512000, timeout=1) + + # Launch the comm thread + self._receive_thread = _SerialReceiveThread( + self.ser, self.in_queue, linkQualityCallback, linkErrorCallback) + self._receive_thread.start() + self._send_thread = _SerialSendThread( + self.ser, self.out_queue, linkQualityCallback, linkErrorCallback) + self._send_thread.start() + + def send_packet(self, pk): + try: + self.out_queue.put(pk, True, 2) + except queue.Full: + if self.link_error_callback: + self.link_error_callback( + 'RadioDriver: Could not send packet to copter') + + def receive_packet(self, wait=0): + try: + if wait == 0: + pk = self.in_queue.get(False) + elif wait < 0: + pk = self.in_queue.get(True) + else: + pk = self.in_queue.get(True, wait) + except queue.Empty: + return None + return pk + + def get_status(self): + return 'No information available' + def get_name(self): return 'serial' def scan_interface(self, address): - return [] + if found_serial: + devices_names = [x.name for x in list_ports.comports()] + return [('serial://' + x, '') for x in devices_names] + else: + return [] + + def close(self): + self._receive_thread.stop() + self._send_thread.stop() + try: + self._receive_thread.join() + self._send_thread.join() + except Exception: + pass + self.ser.close() + + +class _SerialReceiveThread(threading.Thread): + + def __init__(self, ser, inQueue, link_quality_callback, + link_error_callback): + """ Create the object """ + threading.Thread.__init__(self) + self.ser = ser + self.in_queue = inQueue + self._stop = False + self.link_error_callback = link_error_callback + + def stop(self): + """ Stop the thread """ + self._stop = True + + def run(self): + """ Run the receiver thread """ + READ_END = bytes([START_BYTE1, START_BYTE2]) + received = bytearray(MTU + 4) + received_header = memoryview(received)[0:2] + while not self._stop: + try: + r = self.ser.read_until(READ_END)[-2:] + if len(r) != 2: + continue + + if r[0] != START_BYTE1 or r[1] != START_BYTE2: + continue + + r = self.ser.readinto(received_header) + if r != 2: + continue + + if not (0 < received_header[1] <= MTU): + continue + + expected = received_header[1] + 2 + + received_data_chk = memoryview(received)[2:2+expected] + r = self.ser.readinto(received_data_chk) + if r != expected: + continue + + # NOTE: end is (expected - 2) as the lenght of the data +2 for + # the header bytes + cksum = compute_cksum(memoryview(received)[:expected]) + if cksum[0] != received_data_chk[-2] or \ + cksum[1] != received_data_chk[-1]: + continue + + pk = CRTPPacket(received[2], received[3:expected]) + self.in_queue.put(pk) + + except Exception as e: + import traceback + if self.link_error_callback: + self.link_error_callback( + 'Error communicating with the Crazyflie!\n' + 'Exception:%s\n\n%s' % (e, traceback.format_exc())) + + +class _SerialSendThread(threading.Thread): + + def __init__(self, ser, outQueue, link_quality_callback, + link_error_callback): + """ Create the object """ + threading.Thread.__init__(self) + self.ser = ser + self.out_queue = outQueue + self._stop = False + self.link_error_callback = link_error_callback + + def stop(self): + """ Stop the thread """ + self._stop = True + + def run(self): + """ Run the sender thread """ + out_data = bytearray(MTU + 6) + out_data[0:3] = bytearray( + [START_BYTE1, START_BYTE2, SYSLINK_RADIO_RAW]) + + empty_packet = CRTPPacket(header=0xFF) + empty_packet_data_length = 0 + empty_packet_data = bytearray(7) + empty_packet_data[0:5] = bytearray( + [START_BYTE1, START_BYTE2, SYSLINK_RADIO_RAW, 0x01, + empty_packet.header]) + empty_packet_data[5:7] = compute_cksum(empty_packet_data[2:5]) + + while not self._stop: + try: + pk = self.out_queue.get(True, timeout=0.0003) + data = pk.data + len_data = len(data) + end_of_payload = 5 + len_data + + out_data[3] = len_data + 1 + out_data[4] = pk.header + out_data[5:end_of_payload] = data + out_data[end_of_payload:end_of_payload + + 2] = compute_cksum(out_data[2:end_of_payload]) + + written = self.ser.write(out_data[0:end_of_payload + 2]) + + except queue.Empty: + pk = empty_packet + len_data = empty_packet_data_length + written = self.ser.write(empty_packet_data) + + if written != len_data + 7: + if self.link_error_callback: + self.link_error_callback( + 'SerialDriver: Could only send {:d}B bytes of {:d}B ' + 'packet to Crazyflie'.format( + written, len_data + 7) + ) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/cfusb.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/cfusb.py index 28715eaf..3fd6c72c 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/cfusb.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/cfusb.py @@ -50,7 +50,7 @@ try: pyusb_backend = libusb0.get_backend() pyusb1 = True -except: +except Exception: pyusb1 = False @@ -65,7 +65,8 @@ def _find_devices(): if pyusb1: for d in usb.core.find(idVendor=USB_VID, idProduct=USB_PID, find_all=1, backend=pyusb_backend): - ret.append(d) + if d.manufacturer == 'Bitcraze AB': + ret.append(d) else: busses = usb.busses() for bus in busses: @@ -120,10 +121,9 @@ class CfUsb: if (pyusb1 is False): if self.handle: self.handle.releaseInterface() - self.handle.reset() else: if self.dev: - self.dev.reset() + usb.util.dispose_resources(self.dev) self.handle = None self.dev = None @@ -167,7 +167,7 @@ class CfUsb: pass else: raise IOError('Crazyflie disconnected') - except AttributeError as e: + except AttributeError: # pyusb < 1.0 doesn't implement getting the underlying error # number and it seems as if it's not possible to detect # if the cable is disconnected. So this detection is not diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/crazyradio.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/crazyradio.py index 0fd9e531..9622f497 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/crazyradio.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/crazyradio.py @@ -63,11 +63,11 @@ try: pyusb_backend = libusb0.get_backend() pyusb1 = True -except: +except Exception: pyusb1 = False -def _find_devices(): +def _find_devices(serial=None): """ Returns a list of CrazyRadio devices currently connected to the computer """ @@ -76,6 +76,8 @@ def _find_devices(): if pyusb1: for d in usb.core.find(idVendor=0x1915, idProduct=0x7777, find_all=1, backend=pyusb_backend): + if serial is not None and serial == d.serial_number: + return d ret.append(d) else: busses = usb.busses() @@ -83,11 +85,17 @@ def _find_devices(): for device in bus.devices: if device.idVendor == CRADIO_VID: if device.idProduct == CRADIO_PID: + if serial == device.serial_number: + return device ret += [device, ] return ret +def get_serials(): + return tuple(map(lambda d: d.serial_number, _find_devices())) + + class _radio_ack: ack = False powerDet = False @@ -107,7 +115,7 @@ class Crazyradio: P_M6DBM = 2 P_0DBM = 3 - def __init__(self, device=None, devid=0): + def __init__(self, device=None, devid=0, serial=None): """ Create object and scan for USB dongle if no device is supplied """ self.current_channel = None @@ -116,9 +124,15 @@ class Crazyradio: if device is None: try: - device = _find_devices()[devid] + if serial is None: + device = _find_devices()[devid] + else: + device = _find_devices(serial) except Exception: - raise Exception('Cannot find a Crazyradio Dongle') + if serial is None: + raise Exception('Cannot find a Crazyradio Dongle') + else: + raise Exception('Cannot find Crazyradio {}'.format(serial)) self.dev = device @@ -155,10 +169,9 @@ class Crazyradio: if (pyusb1 is False): if self.handle: self.handle.releaseInterface() - self.handle.reset() else: if self.dev: - self.dev.reset() + usb.util.dispose_resources(self.dev) self.handle = None self.dev = None diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/utils/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/positioning/__init__.py similarity index 86% rename from dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/utils/__init__.py rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/positioning/__init__.py index fd35e362..d776760f 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/utils/__init__.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/positioning/__init__.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python # -*- coding: utf-8 -*- # # || ____ _ __ @@ -7,9 +6,7 @@ # +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ # || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ # -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client +# Copyright (C) 2017 Bitcraze AB # # This program is free software; you can redistribute it and/or # modify it under the terms of the GNU General Public License @@ -24,6 +21,3 @@ # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. -""" -Various utilities that is needed by the cflib. -""" diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/positioning/motion_commander.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/positioning/motion_commander.py new file mode 100644 index 00000000..f075bcc8 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/positioning/motion_commander.py @@ -0,0 +1,484 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2017 Bitcraze AB +# +# 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. +""" +The MotionCommander is used to make it easy to write scripts that moves the +Crazyflie around. Some sort of positioning support is required, for instance +the Flow deck. + +The motion commander uses velocity setpoints and does not have a notion of +absolute position, the error in position will accumulate over time. + +The API contains a set of primitives that are easy to understand and use, such +as "go forward" or "turn around". + +There are two flavors of primitives, one that is blocking and returns when +a motion is completed, while the other starts a motion and returns immediately. +In the second variation the user has to stop or change the motion when +appropriate by issuing new commands. + +The MotionCommander can be used as context manager using the with keyword. In +this mode of operation takeoff and landing is executed when the context is +created/closed. +""" +import math +import sys +import time +from threading import Thread + +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie + +if sys.version_info < (3,): + from Queue import Queue, Empty +else: + from queue import Queue, Empty + + +class MotionCommander: + """The motion commander""" + VELOCITY = 0.2 + RATE = 360.0 / 5 + + def __init__(self, crazyflie, default_height=0.3): + """ + Construct an instance of a MotionCommander + + :param crazyflie: a Crazyflie or SyncCrazyflie instance + :param default_height: the default height to fly at + """ + if isinstance(crazyflie, SyncCrazyflie): + self._cf = crazyflie.cf + else: + self._cf = crazyflie + + self.default_height = default_height + + self._is_flying = False + self._thread = None + + # Distance based primitives + + def take_off(self, height=None, velocity=VELOCITY): + """ + Takes off, that is starts the motors, goes straigt up and hovers. + Do not call this function if you use the with keyword. Take off is + done automatically when the context is created. + + :param height: the height (meters) to hover at. None uses the default + height set when constructed. + :param velocity: the velocity (meters/second) when taking off + :return: + """ + if self._is_flying: + raise Exception('Already flying') + + if not self._cf.is_connected(): + raise Exception('Crazyflie is not connected') + + self._is_flying = True + self._reset_position_estimator() + + self._thread = _SetPointThread(self._cf) + self._thread.start() + + if height is None: + height = self.default_height + + self.up(height, velocity) + + def land(self, velocity=VELOCITY): + """ + Go straight down and turn off the motors. + + Do not call this function if you use the with keyword. Landing is + done automatically when the context goes out of scope. + + :param velocity: The velocity (meters/second) when going down + :return: + """ + if self._is_flying: + self.down(self._thread.get_height(), velocity) + + self._thread.stop() + self._thread = None + + self._cf.commander.send_stop_setpoint() + self._is_flying = False + + def __enter__(self): + self.take_off() + return self + + def __exit__(self, exc_type, exc_val, exc_tb): + self.land() + + def left(self, distance_m, velocity=VELOCITY): + """ + Go left + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(0.0, distance_m, 0.0, velocity) + + def right(self, distance_m, velocity=VELOCITY): + """ + Go right + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(0.0, -distance_m, 0.0, velocity) + + def forward(self, distance_m, velocity=VELOCITY): + """ + Go forward + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(distance_m, 0.0, 0.0, velocity) + + def back(self, distance_m, velocity=VELOCITY): + """ + Go backwards + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(-distance_m, 0.0, 0.0, velocity) + + def up(self, distance_m, velocity=VELOCITY): + """ + Go up + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(0.0, 0.0, distance_m, velocity) + + def down(self, distance_m, velocity=VELOCITY): + """ + Go down + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(0.0, 0.0, -distance_m, velocity) + + def turn_left(self, angle_degrees, rate=RATE): + """ + Turn to the left, staying on the spot + + :param angle_degrees: How far to turn (degrees) + :param rate: The trurning speed (degrees/second) + :return: + """ + flight_time = angle_degrees / rate + + self.start_turn_left(rate) + time.sleep(flight_time) + self.stop() + + def turn_right(self, angle_degrees, rate=RATE): + """ + Turn to the right, staying on the spot + + :param angle_degrees: How far to turn (degrees) + :param rate: The trurning speed (degrees/second) + :return: + """ + flight_time = angle_degrees / rate + + self.start_turn_right(rate) + time.sleep(flight_time) + self.stop() + + def circle_left(self, radius_m, velocity=VELOCITY, angle_degrees=360.0): + """ + Go in circle, counter clock wise + + :param radius_m: The radius of the circle (meters) + :param velocity: The velocity along the circle (meters/second) + :param angle_degrees: How far to go in the circle (degrees) + :return: + """ + distance = 2 * radius_m * math.pi * angle_degrees / 360.0 + flight_time = distance / velocity + + self.start_circle_left(radius_m, velocity) + time.sleep(flight_time) + self.stop() + + def circle_right(self, radius_m, velocity=VELOCITY, angle_degrees=360.0): + """ + Go in circle, clock wise + + :param radius_m: The radius of the circle (meters) + :param velocity: The velocity along the circle (meters/second) + :param angle_degrees: How far to go in the circle (degrees) + :return: + """ + distance = 2 * radius_m * math.pi * angle_degrees / 360.0 + flight_time = distance / velocity + + self.start_circle_right(radius_m, velocity) + time.sleep(flight_time) + self.stop() + + def move_distance(self, distance_x_m, distance_y_m, distance_z_m, + velocity=VELOCITY): + """ + Move in a straight line. + positive X is forward + positive Y is left + positive Z is up + + :param distance_x_m: The distance to travel along the X-axis (meters) + :param distance_y_m: The distance to travel along the Y-axis (meters) + :param distance_z_m: The distance to travel along the Z-axis (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + distance = math.sqrt(distance_x_m * distance_x_m + + distance_y_m * distance_y_m + + distance_z_m * distance_z_m) + flight_time = distance / velocity + + velocity_x = velocity * distance_x_m / distance + velocity_y = velocity * distance_y_m / distance + velocity_z = velocity * distance_z_m / distance + + self.start_linear_motion(velocity_x, velocity_y, velocity_z) + time.sleep(flight_time) + self.stop() + + # Velocity based primitives + + def start_left(self, velocity=VELOCITY): + """ + Start moving left. This function returns immediately. + + :param velocity: The velocity of the motion (meters/second) + :return: + """ + self.start_linear_motion(0.0, velocity, 0.0) + + def start_right(self, velocity=VELOCITY): + """ + Start moving right. This function returns immediately. + + :param velocity: The velocity of the motion (meters/second) + :return: + """ + self.start_linear_motion(0.0, -velocity, 0.0) + + def start_forward(self, velocity=VELOCITY): + """ + Start moving forward. This function returns immediately. + + :param velocity: The velocity of the motion (meters/second) + :return: + """ + self.start_linear_motion(velocity, 0.0, 0.0) + + def start_back(self, velocity=VELOCITY): + """ + Start moving backwards. This function returns immediately. + + :param velocity: The velocity of the motion (meters/second) + :return: + """ + self.start_linear_motion(-velocity, 0.0, 0.0) + + def start_up(self, velocity=VELOCITY): + """ + Start moving up. This function returns immediately. + + :param velocity: The velocity of the motion (meters/second) + :return: + """ + self.start_linear_motion(0.0, 0.0, velocity) + + def start_down(self, velocity=VELOCITY): + """ + Start moving down. This function returns immediately. + + :param velocity: The velocity of the motion (meters/second) + :return: + """ + self.start_linear_motion(0.0, 0.0, -velocity) + + def stop(self): + """ + Stop any motion and hover. + + :return: + """ + self._set_vel_setpoint(0.0, 0.0, 0.0, 0.0) + + def start_turn_left(self, rate=RATE): + """ + Start turning left. This function returns immediately. + + :param rate: The angular rate (degrees/second) + :return: + """ + self._set_vel_setpoint(0.0, 0.0, 0.0, -rate) + + def start_turn_right(self, rate=RATE): + """ + Start turning right. This function returns immediately. + + :param rate: The angular rate (degrees/second) + :return: + """ + self._set_vel_setpoint(0.0, 0.0, 0.0, rate) + + def start_circle_left(self, radius_m, velocity=VELOCITY): + """ + Start a circular motion to the left. This function returns immediately. + + :param radius_m: The radius of the circle (meters) + :param velocity: The velocity of the motion (meters/second) + :return: + """ + circumference = 2 * radius_m * math.pi + rate = 360.0 * velocity / circumference + + self._set_vel_setpoint(velocity, 0.0, 0.0, -rate) + + def start_circle_right(self, radius_m, velocity=VELOCITY): + """ + Start a circular motion to the right. This function returns immediately + + :param radius_m: The radius of the circle (meters) + :param velocity: The velocity of the motion (meters/second) + :return: + """ + circumference = 2 * radius_m * math.pi + rate = 360.0 * velocity / circumference + + self._set_vel_setpoint(velocity, 0.0, 0.0, rate) + + def start_linear_motion(self, velocity_x_m, velocity_y_m, velocity_z_m): + """ + Start a linear motion. This function returns immediately. + + positive X is forward + positive Y is left + positive Z is up + + :param velocity_x_m: The velocity along the X-axis (meters/second) + :param velocity_y_m: The velocity along the Y-axis (meters/second) + :param velocity_z_m: The velocity along the Z-axis (meters/second) + :return: + """ + self._set_vel_setpoint( + velocity_x_m, velocity_y_m, velocity_z_m, 0.0) + + def _set_vel_setpoint(self, velocity_x, velocity_y, velocity_z, rate_yaw): + if not self._is_flying: + raise Exception('Can not move on the ground. Take off first!') + self._thread.set_vel_setpoint( + velocity_x, velocity_y, velocity_z, rate_yaw) + + def _reset_position_estimator(self): + self._cf.param.set_value('kalman.resetEstimation', '1') + time.sleep(0.1) + self._cf.param.set_value('kalman.resetEstimation', '0') + time.sleep(2) + + +class _SetPointThread(Thread): + TERMINATE_EVENT = 'terminate' + UPDATE_PERIOD = 0.2 + ABS_Z_INDEX = 3 + + def __init__(self, cf, update_period=UPDATE_PERIOD): + Thread.__init__(self) + self.update_period = update_period + + self._queue = Queue() + self._cf = cf + + self._hover_setpoint = [0.0, 0.0, 0.0, 0.0] + + self._z_base = 0.0 + self._z_velocity = 0.0 + self._z_base_time = 0.0 + + def stop(self): + """ + Stop the thread and wait for it to terminate + + :return: + """ + self._queue.put(self.TERMINATE_EVENT) + self.join() + + def set_vel_setpoint(self, velocity_x, velocity_y, velocity_z, rate_yaw): + """Set the velocity setpoint to use for the future motion""" + self._queue.put((velocity_x, velocity_y, velocity_z, rate_yaw)) + + def get_height(self): + """ + Get the current height of the Crazyflie. + + :return: The height (meters) + """ + return self._hover_setpoint[self.ABS_Z_INDEX] + + def run(self): + while True: + try: + event = self._queue.get(block=True, timeout=self.update_period) + if event == self.TERMINATE_EVENT: + return + + self._new_setpoint(*event) + except Empty: + pass + + self._update_z_in_setpoint() + self._cf.commander.send_hover_setpoint(*self._hover_setpoint) + + def _new_setpoint(self, velocity_x, velocity_y, velocity_z, rate_yaw): + self._z_base = self._current_z() + self._z_velocity = velocity_z + self._z_base_time = time.time() + + self._hover_setpoint = [velocity_x, velocity_y, rate_yaw, self._z_base] + + def _update_z_in_setpoint(self): + self._hover_setpoint[self.ABS_Z_INDEX] = self._current_z() + + def _current_z(self): + now = time.time() + return self._z_base + self._z_velocity * (now - self._z_base_time) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/positioning/position_hl_commander.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/positioning/position_hl_commander.py new file mode 100644 index 00000000..5d8c58fb --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/positioning/position_hl_commander.py @@ -0,0 +1,298 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2018 Bitcraze AB +# +# 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. +""" +The PositionHlCommander is used to make it easy to write scripts that moves the +Crazyflie around. Some sort of positioning support is required, for +instance the Loco Positioning System. The implementation uses the High Level +Commander and position setpoints. + +The API contains a set of primitives that are easy to understand and use, such +as "go forward" or "turn around". + +The PositionHlCommander can be used as context manager using the with keyword. +In this mode of operation takeoff and landing is executed when the context is +created/closed. +""" +import math +import time + +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie + + +class PositionHlCommander: + """The position High Level Commander""" + + CONTROLLER_PID = 1 + CONTROLLER_MELLINGER = 2 + + DEFAULT = None + + def __init__(self, crazyflie, + x=0.0, y=0.0, z=0.0, + default_velocity=0.5, + default_height=0.5, + controller=CONTROLLER_PID): + """ + Construct an instance of a PositionHlCommander + + :param crazyflie: a Crazyflie or SyncCrazyflie instance + :param x: Initial position, x + :param y: Initial position, y + :param z: Initial position, z + :param default_velocity: the default velocity to use + :param default_height: the default height to fly at + :param controller: Which underlying controller to use + """ + if isinstance(crazyflie, SyncCrazyflie): + self._cf = crazyflie.cf + else: + self._cf = crazyflie + + self._default_velocity = default_velocity + self._default_height = default_height + self._controller = controller + + self._x = x + self._y = y + self._z = z + + self._is_flying = False + + def take_off(self, height=DEFAULT, velocity=DEFAULT): + """ + Takes off, that is starts the motors, goes straight up and hovers. + Do not call this function if you use the with keyword. Take off is + done automatically when the context is created. + + :param height: the height (meters) to hover at. None uses the default + height set when constructed. + :param velocity: the velocity (meters/second) when taking off + :return: + """ + if self._is_flying: + raise Exception('Already flying') + + if not self._cf.is_connected(): + raise Exception('Crazyflie is not connected') + + self._is_flying = True + self._reset_position_estimator() + self._activate_controller() + self._activate_high_level_commander() + self._hl_commander = self._cf.high_level_commander + + height = self._height(height) + + duration_s = height / self._velocity(velocity) + self._hl_commander.takeoff(height, duration_s) + time.sleep(duration_s) + self._z = height + + def land(self, velocity=DEFAULT): + """ + Go straight down and turn off the motors. + + Do not call this function if you use the with keyword. Landing is + done automatically when the context goes out of scope. + + :param velocity: The velocity (meters/second) when going down + :return: + """ + if self._is_flying: + duration_s = self._z / self._velocity(velocity) + self._hl_commander.land(0, duration_s) + time.sleep(duration_s) + self._z = 0.0 + + self._hl_commander.stop() + self._is_flying = False + + def __enter__(self): + self.take_off() + return self + + def __exit__(self, exc_type, exc_val, exc_tb): + self.land() + + def left(self, distance_m, velocity=DEFAULT): + """ + Go left + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(0.0, distance_m, 0.0, velocity) + + def right(self, distance_m, velocity=DEFAULT): + """ + Go right + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(0.0, -distance_m, 0.0, velocity) + + def forward(self, distance_m, velocity=DEFAULT): + """ + Go forward + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(distance_m, 0.0, 0.0, velocity) + + def back(self, distance_m, velocity=DEFAULT): + """ + Go backwards + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(-distance_m, 0.0, 0.0, velocity) + + def up(self, distance_m, velocity=DEFAULT): + """ + Go up + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(0.0, 0.0, distance_m, velocity) + + def down(self, distance_m, velocity=DEFAULT): + """ + Go down + + :param distance_m: the distance to travel (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + self.move_distance(0.0, 0.0, -distance_m, velocity) + + def move_distance(self, distance_x_m, distance_y_m, distance_z_m, + velocity=DEFAULT): + """ + Move in a straight line. + positive X is forward + positive Y is left + positive Z is up + + :param distance_x_m: The distance to travel along the X-axis (meters) + :param distance_y_m: The distance to travel along the Y-axis (meters) + :param distance_z_m: The distance to travel along the Z-axis (meters) + :param velocity: the velocity of the motion (meters/second) + :return: + """ + + x = self._x + distance_x_m + y = self._y + distance_y_m + z = self._z + distance_z_m + + self.go_to(x, y, z, velocity) + + def go_to(self, x, y, z=DEFAULT, velocity=DEFAULT): + """ + Go to a position + + :param x: X coordinate + :param y: Y coordinate + :param z: Z coordinate + :param velocity: the velocity (meters/second) + :return: + """ + + z = self._height(z) + + dx = x - self._x + dy = y - self._y + dz = z - self._z + distance = math.sqrt(dx * dx + dy * dy + dz * dz) + + if distance > 0.0: + duration_s = distance / self._velocity(velocity) + self._hl_commander.go_to(x, y, z, 0, duration_s) + time.sleep(duration_s) + + self._x = x + self._y = y + self._z = z + + def set_default_velocity(self, velocity): + """ + Set the default velocity to use in commands when no velocity is defined + :param velocity: The default velocity (meters/s) + :return: + """ + self._default_velocity = velocity + + def set_default_height(self, height): + """ + Set the default height to use in commands when no height is defined + + :param height: The default height (meters) + :return: + """ + self._default_height = height + + def set_controller(self, controller): + self._controller = controller + + def get_position(self): + """ + Get the current position + :return: (x, y, z) + """ + return self._x, self._y, self._z + + def _reset_position_estimator(self): + self._cf.param.set_value('kalman.initialX', '{:.2f}'.format(self._x)) + self._cf.param.set_value('kalman.initialY', '{:.2f}'.format(self._y)) + self._cf.param.set_value('kalman.initialZ', '{:.2f}'.format(self._z)) + + self._cf.param.set_value('kalman.resetEstimation', '1') + time.sleep(0.1) + self._cf.param.set_value('kalman.resetEstimation', '0') + time.sleep(2) + + def _activate_high_level_commander(self): + self._cf.param.set_value('commander.enHighLevel', '1') + + def _activate_controller(self): + value = str(self._controller) + self._cf.param.set_value('stabilizer.controller', value) + + def _velocity(self, velocity): + if velocity is self.DEFAULT: + return self._default_velocity + return velocity + + def _height(self, height): + if height is self.DEFAULT: + return self._default_height + return height diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/callbacks.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/callbacks.py index 3102bc63..1bfc52ef 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/callbacks.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/callbacks.py @@ -50,5 +50,6 @@ class Caller(): def call(self, *args): """ Call the callbacks registered with the arguments args """ - for cb in self.callbacks: + copy_of_callbacks = list(self.callbacks) + for cb in copy_of_callbacks: cb(*args) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/multiranger.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/multiranger.py new file mode 100644 index 00000000..84d25456 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/multiranger.py @@ -0,0 +1,115 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2018 Bitcraze AB +# +# 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. +from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie + + +class Multiranger: + FRONT = 'range.front' + BACK = 'range.back' + LEFT = 'range.left' + RIGHT = 'range.right' + UP = 'range.up' + DOWN = 'range.zrange' + + def __init__(self, crazyflie, rate_ms=100, zranger=False): + if isinstance(crazyflie, SyncCrazyflie): + self._cf = crazyflie.cf + else: + self._cf = crazyflie + self._log_config = self._create_log_config(rate_ms) + + self._up_distance = None + self._front_distance = None + self._back_distance = None + self._left_distance = None + self._right_distance = None + self._down_distance = None + + def _create_log_config(self, rate_ms): + log_config = LogConfig('multiranger', rate_ms) + log_config.add_variable(self.FRONT) + log_config.add_variable(self.BACK) + log_config.add_variable(self.LEFT) + log_config.add_variable(self.RIGHT) + log_config.add_variable(self.UP) + log_config.add_variable(self.DOWN) + + log_config.data_received_cb.add_callback(self._data_received) + + return log_config + + def start(self): + self._cf.log.add_config(self._log_config) + self._log_config.start() + + def _convert_log_to_distance(self, data): + if data >= 8000: + return None + else: + return data / 1000.0 + + def _data_received(self, timestamp, data, logconf): + self._up_distance = self._convert_log_to_distance(data[self.UP]) + self._front_distance = self._convert_log_to_distance(data[self.FRONT]) + self._back_distance = self._convert_log_to_distance(data[self.BACK]) + self._left_distance = self._convert_log_to_distance(data[self.LEFT]) + self._right_distance = self._convert_log_to_distance(data[self.RIGHT]) + if self.DOWN in data: + self._down_distance = self._convert_log_to_distance(data[self.DOWN] + ) + + def stop(self): + self._log_config.delete() + + @property + def up(self): + return self._up_distance + + @property + def left(self): + return self._left_distance + + @property + def right(self): + return self._right_distance + + @property + def front(self): + return self._front_distance + + @property + def back(self): + return self._back_distance + + @property + def down(self): + return self._down_distance + + def __enter__(self): + self.start() + return self + + def __exit__(self, exc_type, exc_val, exc_tb): + self.stop() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/dist/cflib-0.1.3-py3.5.egg b/dfall_ws/src/dfall_pkg/crazyradio/dist/cflib-0.1.3-py3.5.egg deleted file mode 100644 index 46769634708d7f600c6989168c364e8f92277b8d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 194915 zcmbrm18`+qv^5;tPCB-2JL%ZAZQC8&wr$()*zP19+xT)H?tS+@*8iWXb<U|%d#*jJ z&KhHmxz?OpP7)Xd1poj50wBsnO7iOq0MH+AUoV8O;biRSM5n83Ze#AGt4nL=4h$go zx9e|w@u@9<0RXC@006N6{d#97b1O%>KTLHE^{uQ7^bIW?zig+JHErkVQG8}<*ynJ~ z)YEkkkPP++s#Hpu+kX}dCd3A0WHv5kwywyC&H8YU$Sk`Q^kPW$E70<$TxMQ2WMK=O zx<ezS-56YBNhCDss7JUS;P~UPvDM-*z_!oNbH-@eU@v#Gs^_hSX3R!k!iBQAJFmey zbw7aHHB97pc&}Ny2F{#o!h5yrMo-$Wb8IrXBzUSs9J8x|u|%{pIrxNcqIR(7vh{?l zs#)Fux0R#lQo}NXNgq2VkUzi@oY`(LS1|S=4p+ur<r$e1s)C`yjH;z_QffHBQjwsC z|KhJn69l1Qa-2fR<|mO9R|AAntd82dox`^St`uKaQ1{DJA+4yaqE-N6lLVoRw~S58 z=){@Xp+PH6^^0(zbptZx?h`DKHdWfhx<^t>Ri!mF^Gvnz@XI6CGijxk0pNH>t&}%U z7n&io8n>eNj)lUST$x5i&<(d#=s<-qaVhK5f8dIzxa!}f{S^*D0~trI<4B+vEoU() zv8xFI6%tc$y!lKWVCMyiH!wzwEtW!tVwD`<**c6Benh3f3z}b~rcY_HN!ZDk1+yhD zv4WQsl`ko&#~wahGEV_BLx#{V!X73XxT?<XAF+C{=jDL~Aoa8P7xP<Ne=MRJ?e`%R z*nL58){l5JWkpNEU=mFt8k+zw=_m$H(~1*+XfmTZJ8TNKl0C>P7$|eER+Y?$@Hjr& zGU@HAa`*y5NH4e5B61ZiNF*N%@@)DLZlbrmScT`=lr_251Zt4uyY@|)ir4)4dwo_| z;FyD?aT_5U7>j-Pw0I6;Cy+w{bL!_HNCwlfq!8&dKbTVP8A*_N52h&cHv0&ql~q4; ztL_JGPf^85{(`hBEG!YxrS+JYEE}pp$ZMu6FizL^_Qv6MnSwT<#v+4`i9H&iWd=z_ zsmo;!LgnuCc%u!bRa)Ot6uA$ynLdzpb4Na|1*}DXuWwS?TXjt6o-aj4`2yp3dhhfa zb=1NlY>}`t*Ja`#Gw}yS^j;)(>i`r5SLW#NviY8$!m(TX525{9)xJdo1*#9V7S3H{ zn^;*R6#Co0TUY34&SON<=6f_hziBt;z5qgTc+3#KdZwtValclPzHU6;TvY5-dQxs! zKd|Ag?6b}C#IC(YY-Ewc4c4rGP$b{Zv2F5nUH%=Te_;9FF^%?jjQ%&s1~-+GTwn#l z(fC4k3M2pk^FOWZ+zs^&&5U(*|A}%#J9j5DTN@fCmM_2?HYsb$A`77KdYYT3&?rG+ zux#NH+eBIug9Kq13Woj!HwfTe8H`+?2GDG#xe&?Qh5d}A`^fda?j!pMkj-XVKey4R z2^!Rqku`PgzV+UooK~+?iVS4y;r(C+@DVyJ+J8j#d3T1v=7VYlm||D$Q_igrR0RFS zvg~(yg+mVI7Y$Z|#q6A3XNWotVYRN1zgK+T-fw9dQTja&8HT;341qg;Pm4MrRT@P0 z3bFy9liX3N*e}IM2Sf+VW)vH|#6N?P4zLCwCyrx_9=em#5%>vq$B}U)!*bM-m(jrI zG8nHhiGa^|)INcI3+OkHf-!(UPzk<c68WXtNwb)%rUvu8Xm0W*uim-O3N$xRC^H|- zEXXGM#RdFTvEA8>2bGi7mYMws{7LmZbWAobkFIeA6>MG0GDNI65e)Wn3WcQH`^&Dq z(v`^7?iIn$Ig+3CjHSguCpR~#Ff?&>VDYZtd<s%x!HS@XyRoA62YBA(&5C}CT8DX~ zOceFUsN#v{j=X!QN%Kl2)alLMx^8_-DYGs-`Q{Wlh`xm{?1>PE(F^Ej>t*7HPcVI; zzQTzS4nj+f;f!kIp_%kFx-aWtb2YmmriC_c^C(hKs8CEOq@~TIv!?Iao{<8zy}!f3 z?CFMZ$>)NTD%$Ab9KB^5&tiFR3S-?Au-6G1x2wt=vxSF4w{8~S)FpzQh1l%iwBvYz zCm)0>?e_yXW*nx{g6wfj8zY2LIFRuWj<U?BJ@VH-(~&yTd0cOod4~5iiBuQTNwwX* zekWtfOtBg6BQeR@-tc|OV<v82Mt}=^^550NODRcmcsT}mYbEmVIpaH~4lCYHxy9Fn zI(R`LZPZeE_<!0s<>#^}Ti1G&F|^S?vo0EB+(lcVT2caIa8V{gN@87t3CfdP=<yC% z2_N$<WDQ(VD7q5VTsUarps5hdqnH=T#21rGQm&kJiIf+QTgVGkZ#?HiWAK`WZ%t68 z+k{z9L`p>7pH=I@z#}i6-_90o7)4@9c@0q^KTro#g5C^el-M!ZtBoi9VoFrdG5YPj zC(@EuUX~HUL9-oFmX_XWgPO0f;s~@xI~Dv;ecE_ZuedDsLvrI@lGt>9n6~u2Ku5^~ zk;>iuTgcRgQpK9?UkLvLtBySf4VGUR4fz_h|2<a!MEl=SioE~p*Z4yx-WUK#3}!3< z5ds&0Jp**CxV|35lF^;!m>dX_C_+zUf&`PJ!d-#_V}#_L1LLg(l@k^9<ldCjo#Oob zy`;j|uac6Cj^X$F`%Jftl6(92P?WazD+h-qiHC)2{*mNh>R|stJpAD{rESZ*@t3=P zUxWPL-PYCpi(LMHIqdYmJN#d}%8VXZ3HTpe{X-WK1;1KAf3YD47ytm#zq{(_Y-eZd z;6$hI=x$>u^lwV%k56NVFZPR4TDMteNAO-&#m1*opxmxMHi+wmuSaYFtC!h<4hH~j zY!qI#GMmHy-Fjm3>HQ<|8;QBAJkXrDqseq8W;mzNQD>lFil8;Ey`AzA{AJj5KGW0v zUC>d|d_I>teD`V4eRZG5fe6wOq{s7V@LS??Ay3|?GxM-whKQ@}`{LG>>LpjejO|1m z*Ci<Z3U_Dcwa4&m;AQUbe0kBGBW^ACP+*=S*r~B~X1=A@wa}?00$j4zV|bqt@z(xY zTkO@+Fm;>Yp{?U6eXdzUWA-15NnDHrHFBrGP{n#~6qQT{-gemi{$=$gQDiGWcPiFi z;mQxdY$kSFSJjUxJH1k?uKcNNQU^EnX+-?L$=eyX$$m*2uJhy+wPgasJr-&iEc&0q zlbN$8P+AB!SEEryu3By(ifPEEP}T@cM@ip~yJjTCZD7Z=GS=SRAFUHef}lDzyGlZu z2gPY{gA>&pv8ij|81GR~B4y`)jjS&st)AiL)IW1)&|KD#uUNC>y~VL98MLGXq?XYP zBvyQHH+{PG;QbJ%ST*xt(%yOnBc1<s=26#s;1Uhvy6VM&Q)5%laiMbCu|DLCu4YF^ zHF?!T78yS3l3uLlFcQ?Ljpr+yVevhky3RNzleJ}MFD{6IQ}p!(olVA~36e*_j%$c2 z6iT84MU3cJ)Ba_I=KlA2b#ZEWe#YLrUw*1bEb~)vf!khcX!sMEf@Ok1VO7BueLc*v zE)3ZF^iInM{*XnSGZ9t|E1b-kn-XSML4OF-r)Dpt2ACL%NU+foVM7z;u+%sU6>jIR zL&oqo4k~w%5?S)y8}4Q;6^ihCyJA#tU6Pba+y_PahPnav@7H!PF}|M(TB6&Z%)Diq zATlr%&nyV+qj+bQql$=oQ<k}9f^xUBP(^eu4ZDYhw;O>*(;2ns@#z<aVm22c{!H6- z;MtyO-<Oeg_6mR9Uu430_!#wrKA;;-S$&`SZ0HX2rM($`7lFR7cbd2o(q7xFPRhL8 zcZnaH8OD|J`ruaLOF$2l%J&8Qi>>~dV_^IfOMgQC@43bwbU~g^6>Ik;WQIWi0J#3M z-CwlvU*YlZl;^B4Wi!u@kbSR<wCo>Bs3f2a2?-f#<^Z6KPoT5_EGW1uM|)83(5bmU zXy3mkpHZ4Qp7ywt^w95*T+<tt=8S}dwRd*rw*2~jHkoBIkJtTveH{#bg}mg$8f}O@ zqzD7_3B%~8lcX8TfT2Fy;Max73IW~?G(@G<@OyoJ_FaU2GuHfafQ*C)v1Y(i^2rs0 z7>Ef-l$$%^$`pVCNM$s-&q=^-aL$o`fqy|dIsz7<d#o$mRqV2x*2LWl$yl8){0Fn- zqB2aFfvbRQL-2kOF?YY+*bb7Pp+Opmu64prg&|S~NOnl&H_o*P*ix6^$^0}I!X%Wn zZ`t$M?Q0Z9F2z-?HKAg0s>%abIEgXym-`>gQ^F;5bNN=L=Dc0(oo+sZG1<;W@lF!z ziCG4mX_3mSVbz-EvL@}*?&&2YN8m=eGRbNK+_&#E7wZ!<hRrHESeL)wv|)-U7_e~Y zTY*?>>4BJ%tEwL)8c8Q+Rh%r>jtb1kIW_}apf?J#UP4s&8=<(I3RTLPzZZJ&2PGqN z_q0f#>~$n5SmrGxo?JT@>0+ST=A|%tYPVVJh0QY5FTz5xeUD<oC~-H#oHCofJL(C~ zFp3dt+c}cg;3f8$Iqn|vV(saXejN@=0&c$8sdb<)#m=<|Dfd@`m&$?FLgsmDX7<NX zotH_ACf;%;{Z)8EIr4-*+>?S^Uk;Ta6M0D{e1XA1!^*d^MqH6kNZ_J|8%2DiX2pvY zVJ_<4`+Q`csLVx)e}xvjxp@Dg`84+SQ7;c{IRkyx%Tl41wti3`pM*b^P_FRco9py$ zT=Z*kYfiRT;{oq40Q|9#+Z9SNtiKj;=+~hCpBD0;VEFs${l5ilssBCxMMy$J-9$*- z{nv32h5}3-{2y`9WB}t81{45b4ITi1_}^VObkO&3H?cA|{?}~aU!vi^|MV3In^ZMz z*I7|~9&6b7aj9#<y(m;*#@==??9p?-Gp!3CHiC*tCQ2)z@x)8)5%BpO$<-5cO*>ck zsUbaQ4P0`eD{%M?=)w^w#Yr8B#jZYGv0<5GGsF2+zj~6>g`j`zWsz><w4ZA8E)UC_ zxmSW(H+ut8ojEjk9&cp9>~`1p>$cD9-UItKu`yj)yK-QgShM}UnCv=>j2A2MM>(K$ zFkyd=YU4Y!^ON<tD8`r?f?u?#`sJnH_pLd1`L~ZBvboUICn7yN1^rWVG&03bKnc{x zq#H_k5-L^*d+HiCi?%p0Rn=iS9Uz_|4G0G6x@PqdL!~kpfviA;I9A0k>IR@f&}>ob zqOm@tdE^>%YDpp|8+0JMxFSH*j+7X5)hqcz!CMg826aNACt{&EEP+F8)e?aQ1jNau zX#-(wQc!RV3a7~`rQZw?VYgT|L99=3JU4RGicfa}=2xvGhgfoSdm7@du#hcD=C!)s zB#c05oITJ@f&$QYp-8sI@x4;~Cc>E{ylwpSUK|-8*UuJEff1HZj2JQC=<}zBAnU>X z>h?qqst#@aqhfyb%(CZLWeGoS=dZ8enK3gny*V><68wIy-t9Rt`u{v)fZ1`N&(4Oe z;e{Qxb7$#(<K}<`APq2U!{Ei$5B<5SppQbN-zFu+|70muE@1H;1los)zAZ17O+3=D zp=yavN-KY^Z9a5|GJFKzP(0~=S4FZCwF0*|ak8TF#V$F-AHK&0acCY763oW{F@{%^ zQS`GwnBsgOj1g^@)(F^7re^&d+hyCeomWd5OaOSGq7k%#HDiQ2X$i{kTb+tzZb`2Z zRXS9wddY4q*;wQczT@a7c{NyE85Re4g64T@h>2lJm~ol)2&l{s?Tqi<wKgg05{hcn zw&N^NxER_f7%0Y*Mp#r&IGvBYowhhEW@Pr=$&_z(3_M4UnA!XMLd2pA{25muuRo(i zQ|%0!%VZEQlS1xT4@7t7rmcx%vujnUW<rT+A%2R~2o#gt<(0V;FUogpn)@C%dLB&; zvr<N;?a$Ygx|xvl`;6r^E#pHdr-#RCwCDy+cw&7AjI5*5(ewW{p!4|pv(>l|<}_9K ztc<j#F`p{){&C`}MNex+`ty`DdRr6FM(LI#X%G!G@SBV;m+{u{=(fRXxq@h$QESwQ z;C^54hG=%>^@4F|Qdu20Z1C#TZ@}iGtf|@@OCcph)B^eoUcLE3#$#4ZXC+&{@@1<< zZ}>>W_M2&;jO!q@TxYqZX(_s#-;1VN0Ij!<d1t@3A#S1gK8CH>=#5#o5&Q^AlttWR zDaz|IPAbK*(<JvJaZqcTB<X8*!^!5gu=G<~p@X>q@W{F`5nU^!t=Y&dDEQ5!#eUF- z%!u3`CAlvK$|iN_B5kNXaS60|csKsCv_+%*g+k1}IT+q8KG^K7gHEmhB7ACj<Y}yZ zQK}gcM_A*2!Y-5+LRQh1{Mt#)7S87UY^KhL%9L%^S8(rJ?tc{SOf?Gs)IsN;9$Kfl zO|`$~At2KX8WP61mp1H){D`Ebxx2cM=&ZShB8Zu_xZu+&#u(mzff+v_iY@u82uGWy z|9C!u0IR3W;cA^NZ+X<4>UZc^>Y_)6)K$m1@AOWEYsSm-`(&HMZ=<JA*p6RwABp@N z!S0NuI^<d^8|uvmzqP2ZL43TUwI92V7fRk?DK35wzx3UvhK%fAm47^;{}l-SP(l&t ze%N|n8HEof006=Nz@}2Rrl$XrQw*tDe^DvI$AzvvKd-O`>X7+QeX~RO=r||bIpzi& z6ah`MMyXXnV|k)7V%(d3SFx@a>AH+YWTbV%%jn0AZ!z3{1-j9_=n3@M-GNHrVm&{_ zPjj6C?znjcpWU8z$b9AxDu`}7#}A|JQLH8!c2_igdMBP4o5jrdGVgcl_WEUCia$?) zKX_?Pb|y|7*w1h>zTcjwr6kG6o6#c#z=#xM%J^JQ_Lv?6_;RGBdNBiUBaaD&%%_1> zm=2sijMdnoS?JdLayZR6V0meR$dB%Z4*`8htPY}w9U^(KW1L1>FhipfD@c)K0Dr&` zALR<?UZx$C)FMzkQG<<<<;^i-m!u1o`VS=-5`6E)-bAK0qmCjY*P3D9A#?;Kq^G;A zvDx8?X){99D%mH$+hx3SuVk-d(#ir`jFi>uq{l`t9H3tYqy>R8;Y7KnxI#E0*|0CW z!qG_x@=DVx1{Mq$Vm7A*ye7<wI-$ikXg6?XE2!a@!H<mENE1hxg&`pve5DW9n<P-? z7AN{4jL+b867%uo#uRX|NaJ+^2ew)9^PB?dG_6<NXM{<9ms?;$7C`?y+9_zc3=(f9 zyoWEo<YT4pD&8iNU&P1pi5GiNL=5n8zq2d-$)gQz2XJdQrj{>ub_alvj0NU5n-+Qy zax2=|aO7%r42qOv+n;4n$`PdWhOXFIr?*#dsD`OlV+LX)B81skk>XnF*C_n}26;HG zDFnmeXs5I!591YZcZS=}JLixJbx)c>A$S&rVwmXqem8W41ckt+g670*q^CfQx;dGR zF)~|?ve>PdE}LlSs^YK~dEq(c*cMYsHlPZV{yuG#(q`kv7KpDrXd;G(z6G|CQJEDT zyo=++PpLA7%XG+8rsPc4L`mPm%mv&jiaTcSgt3D($)g-9uwYID*PrF?8v8k@#ZIux zis`Q%pUMYQ*8#gCz+7&bZ~EC0uDH}}vE2-NEagd<>JR%rRcd|o=4U_sfN5|kbciT7 z_HBx7n%+Vwl;<6T235vHY<Y^=t1XRW*iVM<r41->LEBjGW-Cs?v(<|gtMtl(UbE(G z9z?;=Ed%KGQeTx&INJ!QJDQ}T;5G>Hl(z}fGPl%Cw(%F)`f9b^(5PLA3L?seI|*la zd^>SM`@<K@RyWEk&a4t`R3FGj+>~g#!by`zXS(Fvtr+`$UAx-+RF=ij8|FJkkrcKL zed{bP&=jvdEz~Y*UC7|s-`i^wO??+Wl282R?R6nf((oX_HdGx%Pcc>ap)0qDW7W74 zZiy<?4dV`q=^UO7Y3J&N)oTMqr*GITV-NmYiQBA^u^?MCT_0;KQ8TSH3XTFg`NuaH z(HE@^W8Sj4N0E(sR^@~qqQqNYgrG$i{JpxSrUfOEmFA4XL`O?mijOjb+D0WqO4DoF zcq7+!AF)BN6zgSVL1NhF*-@@t#AUA|E5@&&DsqeB;+-w>B&1-)zO*YhSr@191I~!g zyzB<l8BeVAPCwXO2-xs>e_Ez)7D4ujo<linCfFfoT{lZ%eunHmWm&g}6{=qQtYPY* zUUv7YGnLP5W}R*xst9{Ui?11Vz*O{cZK2uh190&sK)+;Bjg~1a8!gGs>JWiXq|GRA zZ+st~mkqoWed>axYYH>J_^r3nCJVh{8O=t+VlgMEN=Hu8jqhiM=lLnP9my4Wa0w;% zz61J)R8nz)QnoU)KiTyh1yw1PH@8LgWAKMU(~~<s6bK7F3J!BM#qANbi6ZaOwX4-( zvD4-9@|qKm|4s_99jv2yiAF_zc3VZ13y)%p0-Y%hZfRW#TKofMyA*x0*_y=zMHR8v z_MAp7TcS#laXPB%{`a-?&Ksq6Ss5FiUK$*qa~7~Wdq8HqRopX6(;TvC9+u&p*geJS zFk(xVn{|>ovh7Znnl)*P`aC4~x}=kgS<BMljE6&#Z`6iigE!OPhMP)D=XAS{m*y8R ztWWw}%|q&Gsgrhh6>;G2<8UL$ws@djd8rTX^&OdN(`}+ewPE4YX`sd(t0Lv68Z7zW z3f$m=LXjwhcT!J#intQ@8UY=fb0-!md#b;GyY;K4zT}vFr&EtW5*jSNcFxP$9>C%k z?KC(JptPj?o=7;4xv64G4T*IRE&`m5xspHcvfXVp%e_f@xh8v_G4%P5M18sw1wZ>s z?0bJ@>3<&X{Zs6_>N{9}iTrc5zlr>M<n<ML;@d#OL2Ex&Sg$XU4>%(JCGttXME*X_ z`z2Rlbu`ZM_hn}c%HCwRr>ue7ENEvAze8DR2&2)VGYlkT7T>1$HGy-0Gkah7A%Ux2 zU+(oWbZOU4@gq2SDA*Y0o!Ck|e#S1PbKK|)8E`vYi`^ccb=_z19=t=QtKD4(a?&3* zb6H{ExMMXUq63X%>&1Bn#^49vLk9qLp3Bmt(&O<)e@R@gZuqg8@gJ4GLuWc5lfRG! zewc@+O}2#;#WRVZ`=!Jgz%)iql9jJORvG~TqUNfNHp#z{GQhL~QuYg#Rr-U1@oK26 z6ABjhPGVvdqhT2xfYH$vU&TWfo57@vNlya1O#zcKH=LlTwg~c=5^Pjv4$r>OPkZ_0 z2@fpTQONk&XR6vwBn~q;RR&w7O%}r|_=`o|Yx!$wbb+;Z1f-@bG&N;;e`f@t&D?C$ zBFy8^5Dw3A!ybSQ6mB37^R@))ySnhYIXQO%dXJ!TTgHoeK~Jba2FYj}RCk$BQ1q&c z<j@e+2#0DAT&@acGcD+&Qu>{f-NT!sr4BT3J2tfH1~bq?bUa|}%gli%rTZvm$AP2W zjg!*^Fg)4*%izf^h(OQ~I!qoWEsuMNCZeam(87rZPG80rlax*G4GpJYMRZ~@J1n9o zl_MI0w!jUD8;BqZJ_lt)gTaBRNTqAC9R7&V?D@*^o4k@&B*T?qpj#uu0pc3oumUBX zOc5)DE5Ru+w)5I~fk}tw!h=5NMT-T7P8rN`(li}%UzGmZf<;_BG(>*tcB9pM%~g04 zGiQSz3|DiYm>m@&%#FN%4U{E|Q51Ab{SBd(Fp>{&&8bj}y;eilsT7^j6+_Ea$h6xP z7$^&xr3&CLo0jGR%O?C{jR6pXY0Db9+I+x8YE1`DPFo@Pld!#W58B^G@iGLzP2z33 z4uuJX7$>DtvQ6w0SL=V^G$WMC?{<A#LG>D?<N9U%=%G!O?;mFo9G*NtkK-P-#wlUg zaW|*rHe|qSG~QKSB>KCeNX9C{V5KRKP%m9CEsmez?D>iy0+_mjD?txOMHpF?^jB*Q zi()atPC8_>0K5TdXZbf;v37ZY)y;TNm)BB$ny_I``IE_<cYo0?t)Ur})$zz-hQ8^i zRK@|G@7%#F1NbeK{tG%R;NKe0AN;po)i<G53b*=cb#s&EU_DpL9O5ErA!9+I!v<jx zI~?8M%Q#^%2{fg&TgTmymP>`@s~H;3X!UF~eKS9{oR$L``nIfXlANM4fw$BzdV#08 zRHz_CTOrpWjJS*R;KT#eG;CNW+$_Cm7n=rAVAtBJjRbFF5z$1{?A7u?lP-~yYv>rz zTS^vJl3g5BTpH(ZPs;dHWPB!UJVnW|VY!5WC}296j08Zl>OheXe`iEgM7%#-I6tNw zU%GAveT1o5JctG8?=ufK8w(h4`5VRfsTnm4f+_p94d)AkJkX|XUp!LOI#|z?`zByD zgxu=w>^DM(nqI$x?5Q{2Qov-B61aX_(#_C}@CM-sdA!HBU_)H1)_v6!$U<3Ig*++F zy#PCQ#8lLR;90HPZLXnOnYOVi2|vFW-eX!+l<cD`Sf;9WSsH0(CNjhu2Vm<Cx?p!Q zm33Oq>)`O{N>5f=oqmOrPO5psGb@|Ie={rft;ky%-}zjVk#(PIoM=B<5i74q-M+4T zE<oyOM$!(-QI0mZ$yQ2;DLW&d98r3xkdY>OC=hN*K5p^g(u{adk)(bFQ+`f$)FMql zplu~EI(;NkePT_`kp%U6pA{t$cv;$AUpE(-+ElGbTaZM%TjK3~#y<|YKMB-tfTPR& zNLJo1c*CMu6=0~sSc(=mzTm<oSVAM1Jr&5>p+ZCtT2OQymvtl`qI~}L_q5|H)A;j1 z80$Z$9e?gR{pT%Mep8ru^sj`41P%az`@gdMYZLZg%0K?T74-LAtSVJW+jUWdEs`>D zlJWRo+*x3Da?DjPu}EyN0r?PE?BC^c(Pr62kaW<P+Z4zZ6Fan6ns*-da6K$8-ho9v zk?45t5_@J9O<hDJ>VL8SSUa?P==<fh&CTAeRH6LP{r)PVL3V)0_-NR7&!RP!gAepn zKukC|<t(99?i45thM7Ld0y$LooiG9hdXVP0P9&cYGdWaqZXYOY+{g@hnKTiZu{1VU z@Bso5*;y-0Seel&^b`S$t-efy^<G+z)L+_%gq(vU5Y++ZvbsQ;tLo$%bJu$Q@3p`K z`iGWI^0oUno=!)=`G@2y(jQ&q2lS=qJIQTf`CE^}K|*%7&CBrb=W#tpGfaj?li2<M zAnD-C{K$T=^suD>SO6R+Xo7Iz5_I?&{C*yYhyYFt`t=e(V!!=rL<3NZ2Eh22<T$Sy zB?5})^l!0xyJD+p`Q65mf6tetxzY7D1s8wFBrf+Fh=wY;NCaXdhcl7Jp&hq!(nC^F z!$m|4AjKIAm;49>>KD$6<qftT?wxi~39Xb#xtpxZgRzUP&Qi(aDubqj5Yu(xY~ggZ zb!Kf*q*^`lv3Tkz`xWLhS6+0e7L*UN1nnfDapP$P0f!h$-SjSx?WlW$uboxCOK!qL z7pXT6*-yNU4|Cs&qTe$kViEJ;KABIyg^Y1rmKI6kwjtrR@EQ>sLH~FexM`08nx)My z+N^*2w9^pi>AJefg|l_(N^G}z&2+dJOL9AHc8OOU95jLVz$XgNoFr>i@cs135~WP2 z1|wmj1bang=D<cc*W_^c6~FN2fPsWhvFMuwxCH?wKi~|8#7`T4_td&r&vG-ijszgP zc6-fjR?T9AUY0kV_B|3v^m?xN7$0m;`3ij6o%p1uu5}5Uc9NNtS|=_=R#a6DEkROS zO45MZ<^6z>_^5rqh-3Q5R~Rq!;jlY{9I{6Q84*;hADqR~)|_pw=@G76Rs@Gpk(Ka} zX(8JHM2bT%y`#lanLvlkRE_KPgIEFld_}0zgNh7?WyqwIau^{}5tI@#0Xp(7hYa@! zy0#Q{EROZ|V3l5;HoUy`>1m%oWL7sO#Gt?dMibz<x7d`X)#sH*HwTo9&>2_|?;6|^ z)ar#FD21^Rp!@~Nq)~~Cr8X-N=x205$}0!f=)l}@YhsVwf}(<<F*y~Kv9?@{ruRx$ zvY1^(g}VEKF~Xt<WRc(*p|vT?$q^O`ua5y3HEgbcb1n@Xn#(DXMPNm6f&&d$3UoLK zn(&NY7uCyxDY8_WRGq9e#u3faD$x1c6|>QtrD);5YonS}GVKOK%BtC{vDW(tC_fPn z-F2FzJ0-FH4gu8RredGraUozopX|`3hL<rX+^@;-$fV;19`EtJ@lr44Oiv^`soHCQ zaiEF%$rT|mBFY1%WKYNL6>$w?O+zVTp%N&An}a@a>2h`x<lP#HEF#HDZ%<!)V^6TI z%bhk=^lbG|Am8uYG}0<bXE~i3ljC`Xvw-kGnMl_F;dv%v*WtpN;tcBHawf^#Q)$j< zNs8dS50h^)^OhrWN*W#`*Ew_?g$zdjJeL4duE{+ICxte?bl3(VgHzl2_;f)`Y%b-A zcvq6N*etljkK(vdbk=qQWYfS!#YE$Ic-%HVH%b|yDMZFZ2e(2+mv|KKWEjGrryn!b zg!+VoL4wr5`~C|^*Dy_ui7clls)A{HY>e^nwBInl`>H+Da$9K3yDNIzzw_i2hM%`M zSilwps^nm*zIR-*a?hA2uto^1pvu^ca4EUg-Z6P&?L3tvROAMDEJSDHNa%_7Gg%e# z6iS<~LnYf&uH{#u@vwpID5fM8j7OIqcHRYjh_P->=!Ds>GRkG18{QB&xdwUdHd0RR zlM|vMoRnU*0eNZjBts_Zh`m(_q$(<{SQRis==U%cV2!~6Vw#wJIYKm5V?{2^%gdM` zE6<Y8b-AC%OWwJ9Em>^g<x$QxIjPokPSNcI9i@+v#uy~lz8+5b-*k`2XpvAQ?QIV< z%86*p%x2Ck_q8-cFIu?CO@1+@icjd8M_<+)Iq^%eMS=zE7RW3|hCKh{sN@itg#Q;f z06@oA;nJT~NPndu|FKx$Ujxp+q$7V1G{4klY}ZFovv=Xc;!9V;kh#V$oz|V2)YmON z6E4t1fA()uqnUv)U*v1%f%e&n>Tn|cf+?$}86<nm_WTS40$tPbILqVz49W-i3OS9R zg0kM1QR4FTC{z(ZJPV9?xIYGVJ1<|iCW%x}?@uCTKAt1yPb1$WP(P^IeIUf%#OQ%O zI8GUtroE@vGQ9$wVV9WH*Nw1eq?el1W=yOz?8jF0!@{sU`%*0wT{D~~DvxTL2izJn zS(NLGWkK)g8n)>h;~NGjxdQ7f&lGp*<@2CXT}*15CycVfC_VM*?>$dE!m=1rflXhf zA1x#E77xn0K9g!Zb`~CG^Yvt(2NGo15_L1|a5Si7-vjC0*5GwOzE(Q*OOKyFxl^Sz zu+R^Fg5&1kJi*xheh57s>r{8vXP2~Jx52e~=>R}4sH9q?CkI0NB&5lsH4K1yTBLZK zTKWdTUJ%!m$jhTYrYoc><9Y@Mok_6{2BO$fTfcu8liD!YXLw;8!0FkuRlP|KL+;Kt zgHdh}c1XLB?G(g5hu-nPyh5g`@@F?^R`$V3IdLbDpb18GPsJl?vmjzQS-A{z=ui?F zy-F7(C3E@2-YtHg|6Vnd<J~Ocl5r*z-Vi#ErEn$es%Y%iE(oQ-giG8Tk2+y<<SIoY zu-?Px!wb=2aN7p4Z&dJ2G;sfZKL*z`hHoPg96SRus2$UYdA<zY@c5e;SsBj6!EFJl zs9Juit-~?~?XN4V*?VjxM<)d0m|kK`T!3Lr(-Lk=hTjYL+XgkgyW|Qo5LYVmGE>!& z<h2VI0;P53dAhgzYUKwBDZoAJ%!?#eRDe)+>6|xD;$UGYD9x-BE4#FyNnXFnbTEd( z@IV<KyhytEzvI2w9$qI^Uy<-yMeld)Os~d$lA{9)M^m_T@*;r@dW$POUDsfprGNni z;A4~miF=*B-r&BvhX|@K+J7v5#6@!J!O7v5t3o8x$91t+9iY#%z(%7#ZC0b`;F+9y zqmt^H@TcWwE(kK0Aht6_BVR1W<g?q`QSeR!)}I_|^Ln|W@i*9HiYH6RV<JD9*&!hf zol?DU_k^0g-L0ZylA`J7SMN7!<6JTEMUvoOkJ;nL#Mk1naDZ~-{9=_(zB+N$>+a2C z$DC5K+)`vtBx{I!xEYOVZ<_qkp%~Y*sE2G(W@1LnDLV~Smd{iOsNjFUhk6dVVhAIX zhQldhCkj-M0Z+vQs$%?ug{Jnsu2;(${^yuTQ7n;jAR`T2@SRZ!Fh$XYfn#)sMJ#2Y z4PUZwTYFeWph{YM@Zkf@lPhFhG+sQrSnoX%Pmox_P$3~7(oyXzq@Xehp$#CSDs1d- z0tI9D?rcLsD~n`d;k=-zBIiC7FYp!8oUmU_44~^Ud9$S<0JOXGPPywWb<oMiLebA5 zbc~1sP%GN>&X=WChx>?$_E8tkm42OdLk^$MH;+fXX^$Udzr3#3F$IhpArO0^TUaz+ zO9<NI1cddpL+9V^yZ6$MLEp*aM#7eFi9Y!sj1ocG1}nknfR&tiz1XR?k2Z65jZvNN zm}M^&bw=%?f4_lY_Vt8y0i>!n(%z(8qO*Z<O^h~TO{4(3c|lmt5)1#HGZVThKwd-9 zyDp6CJ%P#B<5hxpMvR4rE+Y&CEQSi+!s`t^(eq;%d9UlHJY+mM{fS}}5tR_AiiHER zl`|6v9?vzZ1aACml&!86gpYYdc_@#ky~y4|h81(xNSd|J!85(8DOZeNM@}24|4=+I zkQqX|Fmjs4%V&3EnBzbsaubVFz|<0la6{0R>(OOYl1k4|Hb`Ku(u_093$$A1Bx@=1 zGT$A&NM}xAq+W_gxL?W*A>EppYu<_VaE@L$QkBI$WJ23#NNe|sNp;E?u49u6TJD)o zq08}rirTT5r3SGc3SuhBJ;7jn*gb(=HwXE78ig?;^2V3U9_h$n??bP;b@A0~>8I5s zzP&ZvTTd7N+9MsY9jmr4&0Lb4F~EwO`V?#NG^LzrPJs*)J>gKMRlUQ>4JlX2bl=Mb zw(}yzNx9;Jau236i}WTB^R|a4(md1!lTtE`;IBY7<GEI?SKv82Z6;{j0;bk?y}E-; zMZhJ-@|X`zC9=k|u5R_xO)?DX?%hshnJE&|n&tI-?x&T@(MpN6u?EY-B|iHZt%Z*e zeC>4NejQ$20BTl^ine&pZ1iWI-|ps%w;tXM$N85YxZM}0RP%8<q75O3aOtmR-BE{J zX1KZT@UY$c6*SE2X1v0;W=MY6puwxrfrAjW6OvC%8}XXKx<k&JSUAhaYDHTOd?EU@ zQr<AYMLQ*=8j}Km$McW1-lLf4;FR4A-_lUx#^rqZ4XD@QIEuD1UA6rfBl`z$Kl~rR zG4EYj>=yhKT_T`|+M8K!du)6HrNASlG1JxIG7O>JxyJ>T?y#%hZqz74#T&zKiY?A- zdo;pn6eVP75ZUWT>H=bM&MXy(Eu{Y3Tj*tc)3D!juThy-iMhVG%zK7_^(m9<xOEfp z`-~PctO5#WDFdxLdDcI0mloPZWt=Knh?L!1zyy#e-G6Axorle_J=h*+J*LUgky~q- z(Wdg@CV^3STviw&f1^LSV*y|-GJ6PuePd4GOy%|DMY$-lnnp3U*d;a{O5*I`RQK_l zFz`weKE<j<!;<tGQe*w*t5MeW#`jl-`$vUE{5PvXdk6r49`vu0z5ipL`frD9f7cF4 zYLd3tBZ$@RX9*n#HzZ+^#ykdM>Rg04YKRAe#pejo1jK|0^P=$r0eyBRt+*BsaoIX) zMh6GE_^O+ZQxt#>Q}9<TeE7Zi{6GhVJ-LeI<*qsttG^@`?j9`LJG#qX$~~$Z*QZ9{ zKW{6xZ2{ll9X_SJc>Bp-(9v)|mhnMq=i0%Nhn;Z*abCdGz|0m{@tN~<0W0#?NQ0D* zmwU_0T!Pn~Yfs9xgKGibN!6qms|8v?-qF-(7ORC;LOvMPCUTzv$f$Ojb{YJhzS(XE z)dIgO*QyA7bBeESDm+!Rh3rIoLoB^xVORfQ>b3+Mzgye!79h-XY;pZE@^iI!)3yI< z)E;lXhOV}wjxO`IVW0l0PXEnnrGWQs6%Q^N*rE~schg28sq;=GZjY`qRTsV8H;?<c zdFTx>p~t$65e?be4>mON0>P!Z-?5=|xVU{HdWe$c86bpvqW4gMAsF&qP&$EyC7dp# z0YtN*sV$SvnSKB+ty>_rsGTg;`v=ZftgTx>w#c1SS|jK+0j^P}6Fb)aEmO`~2bw!w z!_LC*oNhIaIOv^#Thi4v{;trS>slj2JyCu=h;*h;UKe6>i=-H{ba{=k>~Db3V=kmD zZeVMQ0Gi<DdN{Q{`GMA?$dqG2l<>+4kWEH{JZZC|RkHvckPhaI>i69H;hTh4@EtD# zR-#1P=glI>F+|69_ES8~ucf^5B`Oopgs$uuPt|uk0=US_1Nt$hgJ4U-!7nPMGsY3} zLO3&V(KKGm@Yzq<=eS{5Q%w1F!bA*2eB2*Yq0(obZLZ94g0_zkuJK&@^cXo?Jl=NO z-M+TVm-j9tgsrEfOC!=;64#rUSwl&qDY}stNTm}nx9QFKWHZmA@|axQZMjH1@?$u1 zy}P~&kVN65Sr~Q(HvlIBhA}*67T}xZYN~D&Zi7&<eH__rfP~#A!f|wk=kbAV4|Y2* z532re3YGO0p|Jg4Of=QA783l=MMUQ?b9Ht`^w=u`M*BCNi9D<KJe;j#R!gkYkHtaW zLqkxtW{}h^hkb(QAhA%ugw^r_g!v|gM1?EqG#6R@ke+?HVn=(+P-L(60+X+|gPC38 zl-b$KFPn_lYJyf?RoAJ2vP}UOQ&J19!5KxgNNh=SeCUQf6%CX2i}t@(AWMvW17mpH z6PN?Yk_{Ke>+VG6J{36)lHfO4RU&U)Cxm;9q5?FggfDbw5;PSRkXwk0V;UV5h!A3h zXknJawCZ;uJ0R9-*C+KCCy$AB6vVx6GzY=T2Ju2!r-<;Pzg-YZiCBF%ux^IjoNCPJ zHsb0RyZH^DLk>LZ@*W^;ODQzBHVj*pm({~JpNXbcyJ7l(27uo61B1j;HNnNexG7U; zQ=)4;^1yCT233`Z@2<#~gOS6-WEmq`bUuLH>EdN@ZcWq_mlm2jWlvC`D0|0&F$y}w z@s6QPaYt6aZzbj<WY;&s$Ks>}PLn6x+5?UmF65w?vU~Bksl>x1U@9=BX+VFwhoT?_ zwpvcjWA%^{${t0ba&EI=#YvdXz|*@A^rz4=f;P}C4dqsGw1*6VM?M1UbStR{zxa^z zI_^`+T=S516PP3aCLc~2hDU+0;yPv{HXGssu~P_$rev8&je%8%H6g5%X}QVEyTjb; zZqdV7`zXe2rb+L3qqPp104eV~GFc?j3l-|qwAR*m<*_SA!9ps4WZUOWFqF-jxZaZh zCJZI?{LZsRco5bb==jI&jE_1NaN<S|hrofD{eFVtGTu*n6Su=a?4i=zRfkkiL@tb6 zj6_-po!N(k`;SCuaMJeUl7_O=q$L{Dx)$_0q$+;(;Y9UGfSsw%wd2TVW+tA)+sww& z_gha#CqBnGho35R2tS1Zv?1w_&TOxnS9KohFdilzKbWkG92+@&YtF8qs}$^Z7hLdw zbn&z6LB?(39<y!H9ng~U;<jZXRflf+#gk_g!m9)5Z`V%4G$TBNh6l5jCGl5j%m~R) ziaHkP!Vq7ldw)NB`{IAbQ!aHD+n)Y%Ki!)^1(2{++fGxsUe>sv1er8_Y1~Ef1Rumk ze#jQmZ(-CeV8iA>8SD`7MY+lIy1a}ftrFL|oOD{mtU)I<qg;&1b+er;oa<#}$D5Cz z2%q+s&jA@@rYbNCXam)KE)N^0+2m0Ht4(LWB6d-~CvQVa{>`hbLOi5qPhSy6YwqG< zFB$cWhgnc#Mq?<=^{E$fgRWVVxzdwyqGRDsyG$m3PMESyroQ$gb)4JCd8b=q<8sC% zz|(6Xn~r3YgZ*Ys{)Zv&Co#UX;yGKIGQR(13gl-v6&il&!E;`(T|8g2(f4GTZB36g zB?)C|opRKtK5m3<qPE}7PC7?#=F|ZZkn-vMn${B8)}}kFx*YySQ2LB%8I>Ue2F&na z97(3a2=B-aV<+iL3=;{9A}LgC`P<Y%xg*b%`(`M1iA`nH`96I&<xq>Q0q&iSONypX zmp|so*-Y}OxAFq4RK487>MpdSM;rBjnhDC>MKO;FQCVszpDN9I;dL>d+&-`$+t|IF z-FdG^XRyXcv%!^Z)myidmLu9H1+5kDu~6D5T$7?6JnU&xk~bj3m*&zD2i#~2EKu;~ z22`8w5mE9M8}vY^hNr3Z2gK)w1_(&nHfg}VS?*mbSc2w&@kx7`6%O4pn8bqG|J;m> zI;IXk-50=z{B~M=5F@w$(~SHe+VMJqnrcPE9<j0@3x)NA*|bXb{$lo#Eg$Iv!c;p4 zH~I$8Cher^yq-hCfAV9gIGsLO0OQ=K#qOTrDvXY>s9`_P*g@Q^zJ~1P{A#3!bG5%a z5c7Ht#%TZLRieeSa5$8@qo}Dddh6#LUnKmg$H>z^bWH6aADiu$ehL2?jQ_Ka`E%F) z?*iukRx3LBzt@T;L?BgA&O0zF{&x)?U)7=z|EL!A>3mTt`0ASAf(8Ki_LuukcK_Bk z=HO)K==9Yc`gMLhrTkZAQ};^68z&3~)<K}vV3j}h^;-ZTKVWpR44QoUf;eT^kGCfr zl2wh&BJp)l3_!`f>x(u|+?!*j<BtVUeWbFM%e*V|$7Mb9tfp!F$PqDiIMKlDJGh9; z_FrzQRrh01S*)l0IXpPMC#{rch+y#hkld{DcQBV%mbh19pS3_avh#6i_Y*@mQ{!V{ zEcnUTK!M>R%9u1hCck2meE4<cK@~NrZjci$t2Rt<*An0&i_nulgArm*jnmH+Nf4{s zSg$<$ko6s6&`6CIx^Fa$=LBq~mTqunO)U`n(iXNIBaUj>Kq0F83<$GY92DI^e*2#m z+FAju{G2X))uVC}+~F0<CFTMrr6I$sUcLfk(Wutbu}Va-BLTJeL6E8Vpyz~1TDzKp zI4?I)Ukz9s;@6fUngcAM(PH;w=_j@*V4jSkp{O2pV;g*uCVuz9a-PFuZmX@J=jU`c zL7LwJiH(T^VIm@-d}oS8A6TAUDjFpe!U0T<Nkt6XDeB;I%N2zV_1@{?IS0q<<SgZu zJ}8MR2SpCR&w8y_o+MlZpAIc4UIlUPZ0#wP7XMzS=JswaT78cOKa9g`1D1@+nmy3T z<%s90n|kotK{=JO-3cfm2|X?$O48#trE2syTXRL6q++DeC!D!Ms6<yKj1u07$C?dx z<Gbbq@#(1WBYef#VKF;fk}Oo)Y+G{(TNjpqG_)=VAIy04WnC1=p1T8C48=604<$@P zB8+cGV_k{VU>K1h0|Ks3w|W?T9+;0B#5Hxh7!sF1pH--uOuz#)^yZP5j(!ce({}Tp zbE;P!I;InGv;^%<zYjDLMm_*mqMIOJ)ZTV4LRF>fLBYLq+HxsTsKdL;r9ObDS_qL# zAxOic)4R1_gzH&3G;zUNh>!I98|I0MW(^AuH>r#k8kYX191QwC#dxq_SMod~-UzN6 zJ6?k6sdPzThSFC%tquz6GeUvhoh#jACfFi<oKU;M(I}12dq6IDi?IJg{-zN`=SAn^ z`|Nq3q0*5@8lU|`^K3x-V}@GFH|%lo`5H>ZH$sfgCXBKt0fuoVzmtyp(tTZ`F?>$9 zo+iq`yB>DJ5wx-c_a(wJUZE)<fgc<#8@@s_3nONCUPXvbPrkOq>DPidNZ?Tc7)6x* zW-k*|K!X$Io!10UKbM|#G)5{*TI@mH1jc(#;=On-P2c(tSvPc?3Qk|_Fnab_Dm$aQ zUfKRivHsb`f%-RW|H(xE`TX$5TYam=*TunKgXSMbe;pnEIl=!IDvON&U;ES&A|#;x zo0@kia<Em<|G;8@B$L*?`)#pbEY|eZ3Cr}~I{mNh?te1c-(62imi}se#~8sQGhZrN z<<#qx#D_~b_O}5aj7W9MK(M2L81~1ltzTImuWw|J#xUcGq8m^h4+bvr0SyB2IqP&P zpwV1Zlf^l@{``!<>p(v|?958x+u}0=cngY)DX1Pfk+`S`DWmg;$h9<pCIsq0bE3hY zNrRpAxAmg|e=-}$gVhGlaa%8kWl%2>VYEG;dO2MdXdN(S=ZsU9Dn#19)ecZBojh@8 zi5p*6Mn-Ye+rpw(9idDGR9UWrwn9rSF<e{)I6Q5Ivw~acj9&CBo@<PqQq@>;Clrde zBxuWKS#ZQ`JoN^E!iU5Th^9$=Y&LcViMCnYe5Mc0hfRtMd1p=rLN;=VmoQ%Y?$-E> z6IAiyv$-zriKw}y*CpIspp$vAxz^$OW2>!evZXn>2&o<$ienaWh&+zc(({U>f<&wP z+XlaK^b&_;H!be{?2?cKnTwA(Sw(J<uaa)OA&-(R?PdM!DxknHcrvc(KsQt<Zs8PX z7C}3f!NV?1<2eLMyt{=;`xNl7$f32eJ&`yP?LmXAIYN__{6L)zg2X*j#cdZLJc(&~ zxVed)9|LU*@ON-;0&@f=EE{lpZ2L7y@|XeM{m6$suVj)tm1WE0%*{saoBLe`(h@1P zIY-goJS?X>eo8QpBTS9VLLGXg4AG2lfhsHm+o(djhD<-EI)5)VVk=RnuXM>7l&jI; zG!&nS#|`V_i@{dq`p6<Xe4jpka1z}|&Ps)$LZ3Dt4Q(JvJM<l!JXReo7_+lc$-b#W zwyKKWb#x`n`Q0|0vX$U~EKgs$Yq&?)`+lSL&hfdFlPcm$uFM=OGKHWqc(^AoRlGqu z@6KID8QJ7p9^kWe$S@=*`-G3+?<FsP8)jSD#i{=*%PIPrS+n4qx=a+xLgoHK<@78Y zf95=*M%e;WH)f%HT}_?~O4(w_JG=ZTfNQ-o%F)ToEHkcjp?$sA{$`J2RFDBMxI->m zex`7rUs6-jr^_9_XJbWiM`n29`j}RMnOlLH!D6^##1tn`t%eJzM9Be18%l}hha63L z@%cLR!A7G(W_HE=O+9CkeeDFr6t{%yD|Hn81H};0*ao7TODNMy=ExxutJ_IL#flb} zMadoURj`&=+h~7_*NE-Y;r?&WDh(Cc{cPd3%^^Fc6YIuncH0!w_U9NmF-1#%PV#d| zMdN#AqW4|Y(HWm@joMG3zo_gFfb-ittRa2@`>Uq~;14Pj5fh{NE+Z;S=U{B_Z0=y} zNbBV0L{&;nBU9hNvcNRUB+j@8^be9KB}#AoV-BRR@kf*WpL00b+UZ&uyBJ&jF^Qzi z#F*6HI0ZSFJW1IQiPk?RNdQ}B{303vz_0PgWPeWLVQxp`sBdDt|Ige0M+=<)Xklb* zXKZ6+Y-8xIYh`Zp_56*myZ<NaNG^P8>#v)MeHHor@eGhZ@24oMtRN(!_=k~m!cUt( zdKi)IM>=c1{Iz29dCsaeCaB@rQi5ru`6Qor{8^x~SHXDCv%xlYz&3kJ@`@4!(`xU4 zxnr*c<28%v`i%PFat(9Mxx>?U=lh4}ddd6uizCn1PTkuyMWtLJ&D>yCrZwC^l>O_L zpSU8!2aJJa%*Y!D!dBv_$CnXV13u$br>x23F#ChO6_V>yax2aT{LWQpfx`ITMstI% zCZhv{Vf-0i^3@WO+)2h*mg3J6RT=5SC2yShedq9(Fg_B|9fd6QJ+*nDo^s3Mt@Q)I z8OhnHS&hirx5wT~u3j3s4M6-+v5~uaJIe-PxPjZZE@A;{prj2Xj?z^`g{29W7lXJL ze>fvlyOGGbm<McRpjBk34XlZ4!g?$#l3q%MsWQ_R%6cZka44X`p;Q>bbcTipywM{q z&^2fRhtXT-iwP(aMInAyl(LXgfBPI2+{bp`B~{HepeYb~XXm=uT1w-_W^edspBNZH zRD<N#-y`_d^!T^sASd~+3p7c7!e*Zyrt_4_Z3Fj=c`DoKgos~(_!LXL!?W0U7*UTW zIbYkYr&}Vuc+_4tzc+0c<~agH6NTCbne1C<h&zWWD(9TuLzneJk-g^hMDQByG=VHu zHpZtkrT_vN2M9dPdYoESU;&{)3Md>Q!|&C~1_zAvIS@9>%2cVswC8+uckyeAJlv4C z+K>?@sM!|10QBZ5eE)e&`B<U#Q$^^g4d1e4*3v4L1I6s_@|Jx;8Vby2c^Sm5a_Re< z5`}N+Tfi;fbEF4`VBc_RSqLO#6duW6doMB`7Yrp_Y$-go=ES{2qdR+L<U&9+24u;1 z7%uOiJer-(dd{+U2}I$Dnnpg$J^mkG?--ujw=EAQJGO1x$&PK?wr$(CZQI(h?H${; zJHLCn?>*=KyZgiYtoQ4B)~qpR)vQr75XIf#A|E$nD+9_y>rbp=NG4VN3Op0JqN^gJ z!-z%nMi0?~ayJ)=r0Pb7;K)hVBaYRat02!pyppdDy{hYXxNaHT|5Sv3HaC@IJYwTN zNL2mNkpBUOm7SxNxdEM(t(~pDjiH(CKl9zy%9^ozKVxmjs@PLp)J}q+Wfdw?&jfO- z!UllBc_?Qp<>J_OtgG?XCZvV0x7;m){ToF*i-_W0w7I>GOe?dW<xt^b7~62WMU7Xs zBJ&+K+JWk_vU0WPXgs&pNqC(u-cB7@Ndl!ft~;bYJ@_>rS?fp-xFUvb7F{>yTSqHg zJJ*?wpgp}@utT@e%70z0Sm}yD=Z5tN?c~`^%06({b*(M|dbz+9#kFq?<&zRF;V}R1 z!$Ny}>go?V5sncB>m67X04d6e)u$eSzod&x@P|unBZ=GQBa?}NgNZAaG#Pa!mi%Fc z&)EVu2Z%{~sbX$Gk}U`J&dV$3qJ&T1^wP1~VLDVwz*Z^Mo<>Y-3~~^T=ImRDmcucF z?40+If(dmV0xbFEA8rz`{mZy4)lRgypBoxlz*#Ez)IV;P^e=rXKIHxie+S8d5NplX z`W!2N$)C0%?yz4#9QcGGZZmh-F32(wCZ!up@Mh54CUdEWqyc*M!M6P9ppj;tk;8BJ za+23&fd(UlreRU~;{DFyi!l8w;%r|5w0&m3bA>gL{y3r1ke;(hr4j(wLH3*d-kJ=A zSIM+%){^z|V_|8sg592>Hv)G-P8&+H=yy28dZ$5ECTQjg25K)<+X!mlBo?uYin!xN zrA70yH5A$>jconHxFg_cM~Cqgfm$nRv5{HfLBAh<-ACu$MED^Z6RvC7BpO9A0q>gu zMZk>?Q9QR%LJe>N^Y*FJ`t4YI-DiUHQe9bDnL=ZhfK*IhA)p}Ku9Ct}$W|K8K5K`V z)z8l27!R%nF%*SJhXC&80I#6VSCt-zSw|xiZquv*>q)E9uinf#kdi+6YJnoUzC=8H zH(9Xe0GONit%W2bGGQEa$3H>2!4s2G?>>{-hnEQ7+>JJVO8pTb%~J2Dk~$B44LY12 zv)@wSe&mmF#yD_Qagt_ylG_^!!a$>w2~%Hv1{1c)n}(T)wz6K1A^D4QY~EX20Ld{L ztU@UR_j7^?8mSlXa}j%XRz+z<IQcAsquxDA{j5*@UIyNBTsjt&_?5rel3U?DtMY8; zBQ<`d6x#m89(lnr)spaeankef<O=vGgVa#Lyeoyd`j(Q_6oy#3er&OFf4XYJoMpsx zI%kRz%n>We7WBhUoa_B-?Y%N3HTBMi$hRvA4wD@glRw$gVEdr<bN5+3#Tc(EQsqha zu?`FlHwl-^MdMm&ZAN%+KdzWThg@OAU4F2J=Q6S*<DOF*Nvs1&pqG~SD_QI5dc8{Y z+Rg<?(f<R^>Ko)gv5$->2SfdX{U09iU)}uw#{PeklK)6{V57TJNujg$5U=~MWQPr* z8xUc?Uz9ZRzY)Tb$tlYtyu3n_Gz=HC^&rF;j~(2OCTG#mKUoAS7ztuk&7^odY-zTF zT>(3Da&J9Jnogv3&%Ib2&Xtd`5>W(sF$}Uk90^YEJDN<TdS=kvcueQkeJ&k+cGq80 z!E|+TMURXwvaT}Qrl2Z?omf^OJ199!4n8v4$n5R&bos#+G&}duDlD4Wa-ctk;2Xyt zaE|(mGCp_0j<hGQh%J;fa9F7Lc^#+NEs`_IN?utsmhg=cGfWG9YhYsz5J0C*4ohhI zB?QfAT3Q+nvrL8$*l91zwXb`1ZSE7LYBm0{cO(~zXclX)YL_;3>R?$W%h{dnh$=p; zyJXiZ2T#MuKVWIY?;R#uVYy^z1pj2<HUTK!Wim{+EE_+93Ac$1NO!b&xn9bRoWw60 z;4Y7V<Uk-yej$$d1r}3s<gN&e8W3=6-2Cp;x=qm0J(6nH7;fYGyn<{c6Vde%?<!YN z1<60Elwva9B(zEB)w4#;BQL?MTdmsZsrkpDxwCuCroL+(UjW<MrE<sz#~S{c^>*`# z6u4z$-U0KgwSN?%N~y?T7zRlg=kJTBg@yED1T@*xXn8vYTC7mi981OD@3l68vBJvu zfEh|1!GpMQV7K`Ilc6$RO^byYZJ4?QbMzet33(|VWa5uyIWB!_VVRc+0SX+w8VkW) znFjE*$&!UJvo{Y$n7VC|d{%VmvV3NUThw5-RiF6-k=qJeUF-D}b&+z)36Y2-(t=98 zYK366rGCVMZ-m&fha%>&L-oM~gwl$+WI}OI=QkwqYNG_4%X)^7RKBogMkA^a;N}D) z6XCfpToOW|0=g5C7WQZn(U4F6(2i7|)yjUmSwc<?b#6g}CHCm1xW&VHbMw<G<*M0x zxDB_Is!x_FcSFp}BeZet;sm4!Q_BXs<oRJhg!RnpsH0?Eck`Iu8SGC241o@0#(Wv> z7oaJ|{F>qYF*lA*Z0K$s&hdIF!q(dbuhsQ|jLf1l%lmTIFXpUn*c;L=FRUHym#=|1 z`m)q5+5f@TKRa!Kk-FcuKiI<g@eou0Phb6a8`r<}*#G3v)`~N+>q5vmx3$DJEz0>c z!GbJku&BnW_)2{i!K=X_)yN5ENb*am@%!mU*&I3aObA$&+%(_N-wAZsY?r~jen|Jj z^{g~(>Bq;fw_DFW&r^wkfj5ssxwSej2yalA+%*{6>G_0)=mPci=nP<o=tJnAgIa@J z51hX|_w!c$o5c@O2kbnODH4vt6@>1Z4<gVs5WI)PDI)?(Igmi+0>T222*xDDWIzc~ zjHs1BBh~BiONBj1iXd$PC+RmskC<mchwXsv0P=tU4AJZcaT#9>wx@vs;$Qt(uJBEG zIG3*pO}@C#pW&fk-aM7r;0@)Edxl6qXowScil=ov(6@ntfDE_v9zY2!AToqx(u0hi zv1^gitHdZ19XMy0e57QqdBW0YU@-m+MkPk?MG;338<8@#?9js`0p|S1mDenOJ+njK ztylq#$QoDV%9Y&qdj%ScasRv@vPwL>FdJqphP$s?)$;ZEe1v-2t0d}C!#=c3Hf=1_ zsuDJc<kqsSq%BsDH<#cI9=B@OdELb!2%YjcyDIaO;ujpE;|sR#AF<UwXCJ<=I>ww4 z#mpxOu`vUqnL@p1o#5%Xom&TB)ABGoEi~4nfZ<bJWwt>CIozfJL()Mn808Sxb(Hp* zctG*GOj;PVP+feFE-N)3ju~6D%VZ!tN-@qJ1zDN(f5WfGoVHk+W-4b+w`Q^3zl>Sx z6z@-yZ-0~R09DSe9(tMHJ#IM#5igQzu?DDQgJ71NNt@?o&zw0PC{qNHn2@fZf&-76 zEjruP<0@HD-FM``m8LC0E6i6GI6NY(#?4$GDPv4$o?5ZgxJPv+eyBccj#AnL)eWwt z>Z-O=cc*3;<V&<%2qy9#VzGYm0gZ;MMizkXHI;dt%Q1L*ZmGC+8K^jtG<50s6HSZl zv`;uY>ltBZDU9D{JTTAA&dKD==i&|*MY7K?IehrKX2#sCB-U1P*TWER3Y7|{SKEph zH6d#4?J5kKFcUPp4Itnbaigfkvq4p*gC|0;kwK_#FHsq%fMk~#xLx|NBAu{8)d1(8 zi;l!wAwPE-*6&Hr@wxlK__bs6G!i+HtDB>fGl84s4t;dm380zOvSSK>KzY6o00tZ7 zGuvysLfCpHH!fs>A2j9v9jW9jYjLpcGp~fb)ALUEpTK>>C)vyYp(0v8RD|;X9k~D9 zApaA##tAbP8}#tQ-Tt$Lqb$b+WLPaOtkNy!W|D%Z`uY$d5A!-fR%4w8#?f<l4eP9D zg%1cBl5pOUIUJ0%6xDn{ObI>LtO+u*GOIR^`wP$e)bHt^EGEp`a}QAglMOS-rfb^v z#65F}UK^BZE3SG@Kz{@4>=bM9t%SwQA0!0$%<8WTm#V=bubfx=F*SoQyJ0b_Td+v2 zI)#rVhZ79wnt};B0K0!(h{=B1<2UQ5)r+^V9DGCaU((A>Arm(@D4`Bx^MT#5kOKPq zJ<E8pJBi5B@9|>CRc!j_`Q+JaB&hSDX4Um5!ZuybJ`!F^vsqRlkbbc<Gr;4s|Bdg6 zB;a6qBRqul5T>MlOgaE{(nluz3+FipC!*ch637}G<<1|B2xi<q=aQPsPQaq0x^!=0 z@8hmgcY1XqMc9s!*mW6EuH%97LjRaTcN9lAevjtZMoyRN=%%jIO)0kDlE%%ot7S0p zx-y9~XBfMyx+G+6v?O*ZC=Ou%ZROj1FcB$X{W}?ht6OrYy`=J}3mX<rR`;2_P~P_b z!Ezq$4d#D7^gqm}IJqwh>L*}_`G@)Z!#NFqay<<GJpnXY>F1z^4f<yUy-$(>e+`lI zlzwM+3&t+c1ZuWfTZbN5J6_SM9pOyOpPFnUpZ5!QTzsRda{%HdlKhU~HEwatR$hJ8 ztj3A>F+)YOm7aqwe|jC3gjD(MHcBGZ*~e7eE&xeqX2wa4iMs3daKII(cT3q6p=i-! zS_64125rj4C3%g>*;nh~w7sQ2v-e|>?v3hi?(B2!CO=o?NB;Np#}OF?(Hk~fAY~*a zBeqZOtLf1rxbG#T30ZZ*b>`A?#Yk|WNw09}rcQ0(if4x$ZT+6D`0bDkLZ@{KmH3JP z)|*BIGXoVF%_G5L&3p#65<itCZnYYs4-*v$3aKNO{vo@yw0QWek#Pm2=~9<dLK0E_ z!l)XkT7k$~igB?F;1z1Zj*)uY*vHYrV-k-zP4(z$OV%-EK2@@qw%Bj9o9TW70>up5 z?jb)z^lO7Wf51As@e{`c$m5jddDPVf3ZjdR3;J~<YL?*rQ5pi>lV<p<6o*}lg`1VN z74edyrV;Hl6hsXG1PU9aoCPff_0g)yb!b52x8GS_J?S#!Jw1iCw`Rz?vRBjjQ7Xgb zS`&~GG^%<$Bt^!-E}B8p;JUP;pELB~bRnt(V>o2==rT2QBZin8QRF4-Zp;`@rK-1K zHl>B@nYYGb%qiF@$2Z#;CD3}3K&XnRLF18ekJoaGzw!?$Xa+S3+QOAAfl2A@D=)vP zwQL>=XAs6&B9Dt0=ZBlk4N*LX(pN}~?>j22G0%vt7D92Gf_%pLKUVqi(1DTxedDkU z*PZks!JK8)r53p_A3L(Q-fe277woY?qeY0){-|!g=qee+a`37;QeC9%trM)!AKoA~ zYNcq9n8kW?FuuS=H6!Mfb)&En8u&m0U1#TKyCr}efp!H>`~oVnkIiRMP4IQ|ARm+N z`<|S(tOIbYk2m}61y%lv8CAhp4-<xzrquYb9IA%Ee^KpCH9^QvMKsb-<~8rcys`3| z$=&8RwP+}HFelUt>6@UrQChf=4_9P?2UwkyIbZ#Ltp1;FGU0}@Ec;l7lGt%s$ZhmA z#Nxy*sdIUQ?_@^V1zfL@%yo1PNV5W3VKM|aB&0Ue8BJV;p*74;>LYgYW#WJpWRDcM zsP6zn+8#E8>$}iDVYnz$oz>pm;C`D0e6{wGjrjiKTvAn<!4g!glGS^WrE8EDWxS`s zsGXTO<od!-m1*sP!peoo!I&%`A6;h7ipkGk(zkNX3?spsTauW7-D<XWyjKj@op6_b z2fVNIod*RBno`2=y*-3f4)?_~qg~gV2$e$=v>@m&7$5mbBv5zcj}|#UXAN}Xo&bT> zN!3S5G8k;9LRk5aor%g=HTcm(s`?5EsghH2?|lDFy!@wfjA|bO+5hbA7=G;f|HOLz zt8)A+3;5q-fd8w2{A5_v=-Ny24B8m4$;j)O{fj;^l08BN=+Q7saI9&W&*M{gV*X@U z6djPeXj%ai$3Nd~IJ$Caf6dcHUzKV-$zSQKu0<#GkvwcY;48AHp2NxgEqJa>1Wqlo zKYzv0Q4xsTdT<_Z<?h{D?%)y6Ul;F~m6bswj@G?=f)4BzHFUG-KDq3<GS|H^{VwyT zJKhz`dgz|_Me=1!<PgdYoXDFlFcBH23-?8|1#5z`OcT){<5lUDxPKfLFx?0~@3UJi zT;W8w&oqC66X3FdK2<^qAeu~5x@k9ZFL6O-i4rHbwr<|A1LCY+&an1x2^Ik^g!I(I zw9Qi>F_H=x&cdp6*U$jA@gM7|Z30?Vh>aK@lSoHu+r*cPs|Hkl85miE<S7uE0_I98 z-@(|pg)Zhlo+j@=%78hFQ`s`yW244|rI!buq*lEHjZ4%Sz-`WF(&7vvl?ucNn4i^O zW?12SP0&s~QNd5M)-J>|-6l;3O2u_8bV-^Gfu|S(Li?o<G_NNgG0Pvvz$KHKd!;HF zW-5DwK689)_39)z?364X=~<Qk;v$+n<3B$y^*5r7GiclPcwhDaF}B2Y;V@BBk5PNt z1`R50V}>9k)U78gM%DEe8&~B%^nJ)0xQ<VBV&&!-B_!ZaOGHIlp|Mul=o+uQB8)r| zyVWXgc{|1(H-aIvedn3)ZyECTC-ww;%^|EE5HVvxHZvL5p^9tGvyJtd5c*_w<o<U8 zb%s}Ixm~oB3kbu0sQz5=VkdASW9szxgdu>y^If}HtR5_AK{c8^^0u}%@L{R2B;#$q zVqble=<`KMs`YSqt|ckeEfO(A6@^k}>1SKJM~j%6ED3PB@BMN9!k#xwV1Cjx2018> zO*sEdgMa|F-}bwHO7~R+h9BU?HM5o-dPU=#0Pft@+z?>#hWx!?wC&OfG5qq(v!XBc zA|~D|vHDr(bN%c>)?x)8&B4a*IoQs)96{9Ffw`;~V*A4h{(}ROun1foowC{9W54ba zt{g>@q@4PLZ1_qA@s*ww6|`9mkw~F?AV0aE!!BLO9Rp5UFw8b8xW7yhsn!;1@5r0} zz6CS~zq(Hqa15Jkm0AaM>w8#FdkUO20@QYFM1lQsPtklk#cbs~+!1*Y9pb2#OK~~7 z>FfQ^2G3nyrRVgsi}U|!@;~m_|A6U#Z{hyYIP`7*(!+mF*ScBuCb7Vqv6y4#{s<ci zqUzw4ag@fS_F>I>MC<;>dn4Cbb;9Sr%~K3UT(5JkH`&|0_ESaPu?W0r;Z{|Dt2Q`> zZ>{4ZCPTJ=`puhkKTprM6USneBKbt8flf7X96Q(Iu0+p}QFW-=qxpQi^LfQs_RFAq zVaeKA6q>nIdj5sb{m8}b>f(u+tk>l{XQ^SWt%|8%-a%%j%$OW~MO=~9+UK*?5p-<% zy+>xDYhFJ^Q$wn~0Ua`cE8U6?m1*{rO@yB7-&ENkU^khr^rF<jEblqNLTZ%M!Y|xT zziQdMWCi9i#e7Up*(h4_3Z6_EPY*Grs9%MeIqv`tMXIQ4E?QTJYn<Ge%t+#p={QTk z36#8)`Th#|tmQBTNj)x2fXEdQBsrkXR=AKocfd7NQbANg8+ynNCWV5)M3sc?4|QjW z-S)d_B-)S-&++IXkGUqzIo&c&r{9@k6B4A++U)!KOf#M$sLI{3nT(&EAz`qP9MXzS zVxY0%1{=ixmMaoBM+G6^6?5iC`n)&eCZyLkzPkgmEgQ6vO_t?vU`}i)Si~6^>9o7! zBj|H`VvAgs`H?=Su2UqXas`0Zfc2R(t8fG1BbD3SG`1f7NnFjBSUy~X;}L#}FN&f~ zI=R&L?#iN)U^xnfgUin1Mo=UW$?!?!y6S&vAlB9Kf2>hN;W3IDaAP!Pwd>DjQaWy0 zDsfF1Pd(jOiIEd^p(sD*5p&o|2#LPT^OK(FRfZ9}Xw?CrZGLPSwr-s09%?j!KF51| z1^4OZ`4WP@(DL9^ZS1Ynd=5D+s?_;#h6_O-|JG0b(F(#-;@E0`7AokE4);$=-oN*g ze-{k?r?>nk@o-N3uZ+hLQ=E}kl}N~L{2~+-F%f1!KpHTmIn?I81R#`(uppHd*US$4 zEGO%QWy(^A17WvfEw&rftTcPAkt73i(MHbm^z9FBolB>T!e?Gy?pnZ)fO*BfM^x1Z z<Y-{@JY#x2d>Hfs!#_P$vqxBQ-HdvEnn<u07H?JU=fM8wZbUrxvPo#7T;WLvKBN1F zL$1w<I@lmRd;ZrJqPolr%Q1MKZdET&(~||Q$xq{K!z|Odm>?M7@F4ug*kXa?K#BN9 zEccc8G;z(7qNT76@vkg#(!kc{A!GB>Jvc{MA5!K+-Pk+=bO$wi8Ze*a!*K^P<c(|{ zxD#t?)2)(TILv~6k^u1(E_zs}kS$eNYQ~$#$#1_iSt2Cb7>H1?KLM-_0=8>62H}im zlGR$VUi2M$e7-yct-3DCck7Px-E8Q>Kk?5{C^{A*)wRKS9}Ed_ks{(DQfa3SFLXw@ z3X9D9tP9(X2EBjLH-LL9fqjzmvg;#v8~l+w1L{n$xrJ+|+;D71vJVYCtD3EufcwPX z*(Ii3+-FP&?Fr=&((YMlg^?aIO<~HeklRZUu`zM8A?@2xIxV{tqo_gRB~W7;=pC6) z?rOb@UVra|y0N9YpJ^QC4LR>voQlthYP4-m3j(Q8*&jno-aqs3@7U4K(53M6D2}bq z0NQR-m{cIqeSer1WIld&yl~A;-K_*n1)cL9Dd)8A*Wc<REp1|rlT`FP8W~YvoEtEz z68IpPE38plPS#G3w4Fb#=1xy~9ujyrPHDMQA)jwOXZFfxQW2QU5QrjUgc!Ajvd>`S z$1R5-Aj^UOTQCX3NW+-jD~amd$m<k6{(G(|-MDGWrP=z)T5+3zmimzR_Eu;nkqDC1 z^n2`gWpBEpHFsXppdJRQrP9~`TKpaFA9IyIi+<?mNB94;`2V|N|L5BOe_VfSqy2ww z(f}dof7JuQqd5YGBZG#J<ByHPSB)td|3OJnOG?+(sFKr2NKaHxNdNhl5U*Acr(PA8 znvs!^Q4psDfh?{p_Rpd9{Qlj7QP&VIUT#7zHePQ+ei(!qe%gz1f>K6$VnJ?Fg1S~g zYGS&oM!u%LKB}!rL2gD)4cu}yTtlH6FAonBT_Z7%PHo;DYN)i0kA%5QMK<-QJAUi` zKF_{9Ei%yg0lo82ccS?3_x^Xd|9`x(x00;oIz6&$=Ric>N;aOq0Ce?cOik2$a&iMd z9M*aVPK&~1BQY6a1TrzZ`E&GBvd3Efwm~WPSY_fYqd$u1>*w4%w=i8x>(A8&&(8zZ z)SWXb!=T)@r?*k0@y5JnTcfo1(p|nO#uw*m{p|y}t<froJmgo@UN-V}oKW-rD$Rnf zP^P)Gd5;Qwb$>3M{$dU>h^dv)htQ{7@M1a!`%zIF!<=S__a%5H!Lr5UvT;DP0M5*z z8;f-6nKJeOU;=7s;%$#zLNJ8jqAFPC$<jsR8=VrTTHvz(0utE2V6K1fo`;=A#7Y7q z;C8Jj!PMM#?{B3;v*(RpP^-QqtYKZ2X2533voC;FUd2x>9WieI5HW~mBu0srg>s=F z5j)tQjzUf_`Kyd>m^Tiyh?un7fg+?x3RvI^Mk+=3Mb}zaM=va(p!<O<nn3{i5~pME zR6K9%sDx=Ljey1X#MYnWko$s!F><u8;c;za$FX23E!iSjn+zkQX)$Z4?K{cFe-_Y5 zPn9H}k0>)$d_RyyQ@r&DlJc*zH!%Xbx3W}?sS|ewdqCe#w{>~fAw#paXRXVJvunhD z4>7_1I6ed3Ff6p^RORRSX7RvMpL0*juhwBP+<A6wsLJ~^^iHuB!B7Ep_~oduHoQX9 zO+-A!7=?kp303#W;PETrGKnqZdST^BYc?@t4)=GGJ}`Ew2tvX=U168FEbmFys~pwj zx~>WzW1GYpf96k$GZl0BWr0^Y__pq~PIqr59GnyfW=h3nW94EOrJ;)_n{y)z;mX5P z`7W8g&Aa~<+ZTn9w^;=P0ATWC$^FOH`mfGpU~B7SWvg#w>_BJuujkJp@ur5S<GKj! zw{Gq)Q&~|ZLB#^ZV+WZ<jP+>E8IqbA71F6TTwGzA;%bV7kx*;xg=?Qbw0NDw#uL^Y z-JH{EDQ!^Hejq-7cwD|2Cl`#^_IKlgTj6UPjgg;R^smpkZwlDq(7@tMzqY767S@MQ zJ$QUW&g^gcWItr1XPyS{rCMNaX`rD^0R%;T|4^I|ubHB6;^7P&XF&3v@_sJi-OT8( z{o-W_9ax!`V~+Tad6{#Q#14in@?R8?2#Mxp-<v`B1n5mqkiJ!+^u-=J528!KKpz1@ zkG1lI<INdBnCTk)WDOiBEFk*Qcn37KI|@PgAaXs{K{loKH}t|VX;^U@Qw&Qqi*KX) zQ|r@@UKF3Z*$&|eb50I614E$im}3Hwdx!y)<Bv5RDlY)7!Y2Bav30nMoo*@#$~H<F zJc`EK!}$)dT^~nc191FGy@T7ej|-(JazGm+L$^SZIbcOYE+ZB)Appu29#@}vOYQ{| zW$5{<m0J9kH7Z<?L8@;dh#YWWO6(3;PWOV9&wd5IO<mf;*;1E^9Sj$;XM$WLIAs(; zxoe*vfC<!n{DX@=9K<Cgwshgz_k})qpi%bb_GWMI#_H{q#YIGQSjA<6n5rjY?#_{~ z8Ig5znViGk?fYr(#gmwwi^JQM<5LJSD@$f(OGl@F3=Yi>{5TYCVPPNc8kTP7V_@hN zF4dOCPg2AH0?Vd_{$<n(B_HLO+R;5uWAPhF#v-Bs#8IuI6`E|t@B<aZkzsG|F$D=t zXjkAQEZdT*2lPr1-I#QP1lyY=@~@)A!DCg19i~SL#QX0jhk;B07~gb#-vj%8?*m^% zA$fy-`6QE7?X(McJ?56nxtvcgqs*J#yV<kLi;D+~QrQjmSUpr>b@=v!G$Tk}y9E*f z$QLg4c=7~DGExafK4=HU*!w$IcpB8z_K$XlM&nnUP2%T<JJn&;D%GzWyO;Ds67`My zL^BZ7vAAl(6oEOzGg7D&?hTG&)dtBaIj^Gh^Ub8}Sh|wq<CjjOXEWW8`E&M|%tBkz zFjJ%xs?oX95`6gU+P9H;htG4JSSkPCSxLX^<py2%vUl0?I}Ku(P98mQ|FQ-LT;++L zggkLqkP*zd{h7NrXB?%gcr7r8|2&=)jXEHh!5$G)-^ujDwKp{2dW+wmA~lsCJxLWz zq0)su&>QkA6{A`8oU=#{-9U-~Rp0=|V3tgX$I5eE)>b>6s@fAK8u(>M)D)NDlUIsl zc)OWBgA{^|07LKM6@d0J)sWCUUhX1PsoI@IOF?hTP!?8uZp@D98%-EYF_MEAB%w-D zB<!oaSk;r5PE9ZmJc{Wdm}8g0X0^Os2ob5C{wEwuPwo7&zEe+Te2#&Xem>Kr{km~5 zAJ@E7S!k_9MBj66)#iRLYi5jOCM49mJDddKjS3YQ#|WHT{Xp1X@d)H6{mfxrZiE6G zTr<+P`f0vcDD_S>P@1$q5&8X4wcGe`m|@Cm1)J@ProWaGD$R)Mc<=-&i31&0R1mmv z_r-e~_%PdzscgR=svs#mZ}u~rkk+`_u%gG`PODv1y2w46<dqVrIPD%MO1{)({irUu zlfp01#Qvn3NtWIKQJ8%(pBO2HsH^E@pbQIfmwG(1lLSr<4;6Ej*$+a7G8spYe6cPR z8tex2BEBZ`;3qSuBkyK%pvuN7Bbr}!L5fvee?%h1HjhOsg-nU0Shet6XTSO;WW4DY zK^C<|#xn4!I&3bLiU{f$<|Ypu6GG{`vZT~<?XE6^Rul(OE(uZ>1)>xJoCe%vH|<&{ zX46{fQ%q8@BeWWWgjZpjP?+2^)p%G#W%WanqdB@7Iy_1MZv;L_Q17VOP-=#FFf`$W zhPxPb^jBsfQB<tJOXXbOiwECgrZai2za92w%JxnjkT)vcQYphBWNSCXYDVo~v>w!2 zw&D>Kvbz&+;}js*xtzSBgV)X7+u4rZOpi*{>&=7h@h`ZJzAzrq!amTp)f4!KxP)K4 zOodgYb|u$9TEys?q-tkAi=nmp+d;J`nlPZGt8`d`-~eJk!v=;%(X8U?A~%T?cp}Xy zurOV?Uk*3>wcb#DNaw<Vi|EXQbb9(32hIt4X+E3;!s3%yvjem{K#8R>I7#TVWxnb` zE6f@oh@EP!Om_z9z6&HO1ZqLVY--s0JIDvZ#R0uR$Pze?1ja*SMhEYU>P~%!Aj_K2 zsl1MZd<a1elu-4wQ-2Rr6sirm2kVr`RYEq6XJ}~y;z(#^(_4wlzmkcf(T}Eo#{8%m zH|e_-owkCXY2oUp9bO}v(yI+CptQBdX~vslRjY|A?j)-K_k&a%)hp-|Gp5sIC#vE~ zxZ(ZF(Q?;!Tgn#5l#6Y;Il158Zy)xw(H!<0Os)DIe<83x%7)lfOU1)W%e*4XSq;W% zy*K}<UC%`+ka&dMT(2^LaJ2Q1W-aTcU0C)G*7Q0ZRA=e^v}US<!W$EnSJ5a~>eozp z<fWG+G>mkc-uJ@@))q=$Hcx*N(=NewPP?;D{O$RBLvX;Wv+|F*Ndyg(zg9ySt8t5h zNh`ZmBV|&s8Ezp$np#HLqbtZg$s3m(p#{C})3+jk50F?Qc#mgb<mWw{-5U+R=O5IX zR?vFmd}|;->uBWp1^5Yp`bzZV`tBqzwo7e@F;i%343m=8@WN{H;4j!A$yLgNsp?<( zK&)`w^<aZcP%#c;h?4Ihq(ru3X1zkj@g_~js#c(sm2PcOW)Gd@?SQQLo7C-aBI3l+ zN}zKQfSoglXh8#^QB#V-Hyj&dVlhtNm^->@N=V(zyS1cUjJvjKaQf~hhK1a?A7kjN z)Ljf7C^%m;bF*cs^pyB#Al{KA+zs=^OGe?D%6+_T{mRjNb0yYb*0(OZnlkV7)I~5w z@G-Jh1pT*T=+GEe)=ot?H0o#pz1EE>DqeQ(dadrQm8&D})(#nWuLf<p{+7s%a^<<^ zkGg-Td@Qd>d5qtM^7&=3Jb1Gd2W19L9KT{Fm23$ShR3c>sAJNgBzU8tnGkeJi_^^; zO2CI)>=occCXwDNjB#oSr>(RDV*E6)^Y)tPN=TazP9^;|;Cav_sYfpnEW)Coyo79q zJovFS2~f+zgDX5kH+bv^K$vDJp0OAdrn6IwI~B|#^R_<EU5-uYCI+G`;NjE%((Wpg zv2Z7&uT)=7Os6fi(Bq*>IK?BHH!KRah@NO9+GzMks3-4>4e-cinVAXFPY6!&;aqj= zw`d@&Sx0Rf05=m_J}btMD2?ILj>eStQ_A9lC)Te}BtUpQl^2W}x|5=hXa9;QJj0Gz znGinPcSN16yk9hXVj9j?v7|6pg4Tjv9?#KbJ6tcUad@jI?$uZSGMiW72Ec$)v`Gx) ze1;)QRDo`CvcwlUn(yNae4d+oelfealqdQ#ZWv8Up$z!cM%pajbn9Hn;VuB6j5OzB zh^?DL?J~3o<fKxcui9-MQM$}<0~0l(8M)|er)W1`GmE(Cl_St(uXkt$Rr+Wl*)Uv> zCeO1Sqri(u)Q`4~U@>AW)Y^-q?VR+qWcFc**OMSqmLoGOm_IsJY*guO*Zp}ghLE!h z|6^_F(k8Y|YX}dchg_akDp4*Q_iuA%_x|?Uh;MJ6l*b+{kEuZ@8@r0PS}|(Jcx)X} z-6r$8{iL~Z{vh`Hv=yASN8(r2sKV81-3<O?#KNbF8CjSuKaw$dND<ijjEm&z8TIAK znui==t_X~gG*YK<>0@|>Mb@n9!POK~d|DnLgqq>hARopaloCPGH^b6*W)a0VQ_Jb` zo220eZ@Pxxp((OSLIApBDVd;c{%%agB8jWy*G9b9l9Q@pT;|~r$X~`=EYUGM;O>ob zK53$Q8ksJ9$aU7=68+j?NEb8?{yXZ;VL*&iMY<*Mb22fcNx|<K1t&gqm}itZvuO%i zoJt9;)4)Svhl6sdR9jp>cN_66Oaq+q$EHZ9q3T)zR9C08SX1%XOkGyLbyjuS2N&{U ze>QP_3&ko!zkt_`v4C|ng<bU*hA#+J2na|Gnin69po#rr`YYuCr3D|qP`|H+4TJP@ zFXe2JVc9ffmCevm*Q#O*R0a~1f-lZk+~YQS2rhOalO9ZugU%u<l<W;vIa9M>Zv7sa zGld3x@)~`7WuVc*=}G1t%!>^NinZ`sNOqm<<6A}6OTpES+7SdENR$@y3}&sOiR-C~ zY31pgXN_hb%4b~?ROafwV9x%S6aLoY$tlzJ*hq<>+pTneLz|VC7)E0W-I4U$HEs1K z|6Vg9$bigq46&q!7778FD+ZQQR|PS#4fZdjf%!L~wlX}?u}~BE)OzbXoAyejjpN>U zo0ysdmINs^2W&pBifYN<SMr+Dd34T_3)h(K&i65gU%UHfR9a#PdSP_v^R70G+kFm0 zWo&8iIhJdkIIWq6EtrqMYbdSYqR&o+dZL~3atI&wXqFXh?n^iu>zie-2CYhe>#IQS zsW#JF#H2DetOt0m1=Zgqw{R?myhcz{UGN-cY#OfFTFerYk-k1UnxQMM@WKbcJ7M?P ziS`T{dwSgGHvryMoD^lxBMcI*Rzjgz2<?SF_i}s4o9Eef(&u<jSiK@o;D@1I&Ot?d zowi3h0^lZ}#Hqf{Kf(S}CkOnD5=j41A<}<l7yohA{~sjpAHL`0Zuc`CVCSB#;%mFd z2LH*MYf!U9SqBq0Tj^w>d<u}P-K0H!YxrDoPGO1&RwZq9z}B?k()%8rEhmt-vY<{# zz_ib5d$cAa<7;7DZZ(BrE8i2cBtiqyDwBWP1LzNqp{pfOQZP*S*C4w<H1^ok4TA@^ zYfqbV2Gb<#um@EmU+4aO_U;+%WvI*RFH@WBCN9^t$*%JDqphoduZAWZm(oK1nk`0Y z`}<M8!BSWWs5ZZj@HBKbT+iz(DeO&d;sEk;*GrC?HL)f&%A$v}S!d45p9yxSbV%aY zOo38O;JpRX2#jEY-CsTvV(4MX1&AJI2b8fHwCa#l6sQTre!fKF6h(vzu|o4yt6|W; z`uXSMiX|G{OUUU#f<kEsSoi`kg|VzB+`@J&!~qkDDZ)m%ywIn2fPQ?#=pt)eCV(3a zes@V{r@)Pth8;x&ldL8px{hhc*m-pDY2>6YC~_e_5SEmRULh?a<nzdBu;36Z1<Z~R zYIMU(@mHV*1ulx2BbD1I7{B>`5%5W)TtU2Srgw=u6{@na2%81@-8?aHM#*rb=cp zwtiTy+XjZrbuB%5Dx=3~#*rMgy8f}?p9bPxi@-&e{^LyhYa*FbC$QGQ({9>4-ZWTS zQlyjZ=zO5UX*Z6ODH~2h^r_*(&M|2uJpmS)g@F}LXoLWgU!CX*!fIK+oj<rEG6<X5 zf=JXAky-Psq6fjR+Ln%ZA<>|E=vfSIY9dwt5bg-D-;iU}ppd|lEG@WJaM17YFZe^j z6@q`G8t#)p?jsb=5Ds3C2#A4o5GteFXe<NTt>+y7?s8ml)cbwPT%DMRR7n*S0WvoN znuAGg5;3>v#NX()hUi{*_)aVsO?-83StrRkx?IEd`-#^I=8Z&`wFT%YX%s|xVJf1e zQ}kVSq9Guyh$5+<j;6cM(|ZOl`ntsRD>bwJny}>kphHwk=jskp)$^DUcBVP%ctuJ7 zI3S4dc~(szA^`#qt+f`7UU%`vmV2fK%%XtC&Rg4Lr3w+r#8;_MN3Nw%pd(2XPF$Ik zeYG~1m!<Y}`I51{a6{s-H#vXP$<<BsIm&l`FMj=dnK|W+f3e1?62L8TF><FEBtB58 zBzI<Aq`_w!J!Jn&nAYa|2nGh~GpTPQmA=(nrZ`GE@xm=oAvvq{vXub3dmmm)1a0g4 z+?rUpfhIID=nAcnCPS3}&g?0WG4|I1@-{HNunLqt6`_s>-Gg_oeTi3Z$~>EcUogqn z-$f$=%JF`0BHTa;V8W-?>#}*uRgid)N5v3P7>{S|d+G=~wDYisSuBF3LrWQCe#(8W z2aw9i+2%`cPTW4=DZxJTb_b<uaxY)a3nH_DwZ|vmK{OL$+TC}!vUb^RI^S=3-yIjE z*sY+lzd3Bi$}UtrC+3@LF0DRsWwjGvieDsMP`8%WMU_k0)H$6c-iPp5y$gE2t1mu% zD(U1nL0r2yixoI7lm_fzV7s^Wd4-Bg$90TGZ{?lxi(V`kuzbre{iOG7zTu)$q(_cn zB;d2mLC-JPv!TQM8g9Bjxkxt~Pcx5aEq^i}|JPVUGi|+p*N<?e&HArE@BgEw{kORK zGmwpC`4i82*Xc7<B*Iq_Z$2jM-|z2X7gfeWYwzI0oazYkk8Wj6uFy(+Ngnh4K6P<d zPn?=?afAy@E#KMLc%QRI(EWUYFFDwkBnn2|5xm5qJt%Jr_td)$#+!3%<^!ybdGReo z)Xklhe}1k?PKQSKF=(6NRZmxoW^n}|ns3|b&1QFw*7nNLd_e`x+sol!yF~d>Wcyah zvy%%p1pTqK0UNpr#7@zx{aVN%fldN9=)Wf*AClPHc{h`6=jRF(Op2#GnLAk7ymK!M z`6P}98(KKW<MRPf>vjfp4HdYr%8vh~0Y>m6TM09K(A=B&bV;Q9Az?=;fH=4BKvW5F zp=}}F{DzO>M+7^~CR>$M8^L(d0S@@NTN09IN&%D$gf0VTFaVxfUbHV`xWO!BbO8it z!zi5(dlauXOS_Mb+Mpk5*ZVh2JDhFXOhM3`1DtDVpHZI)z4inOQo$}^DIh5W;gbTc zD4oB37Mk6JP(bf)9R0!i0UH=RR9$xxIhx-Gp%&hlw%|$elETQO_s{{f8}Tje9tvX< zU)1Ox4xC^b<0vAk(XO8yKD`%P_s8Sr5(##$cM#mj@$rahDxNMOeFo!ngJy}`?I9!y zFOZR>n|z1JJjB5I$}w5*Uc$a=sjUnhFCtLl!bIZ=8XCR3E9}V4*UQJ<!@=3qEqhll zhwt~*UNewgUl=vTfDMG8-)IVhg#EBWY-qUP4W4{CL;~ux-tH!&Qq9Z@4dPM$NcA!& zC2dq;`vHPK6-5s)E+29!P#Y4qHA(b3W$|IM3YZ<{>okB5HbD}aH>CUx8bv=*3<Mnf zH*u69gP*E>0%05S8pEF(J7&zQSReElP&;S)i-(@~tIn-THkpCd!a9HXz)-G3>Uafw zN{LjtKV`9MMK_`WfMmUJ`>)t5sJw~J3L7O}V-fFkUMM$lj~@PEsXJ2k3r^kr(Rc0z zd#uK0+W4tCX^jsFArA1lCn8W&fHI3SI<aE?yY~E<f#+MJ4C~H6v`wpZ`@Fp-HNPDK zTHdg(Nl$N134Q$5vNG=Hicjg<m3u)t@jOhfGkHFNH6_7z^c8D@1aOj%C=m2zw?V~~ zW+YTlpd0zf++kDu!8b_Lm}g{vVpLuo+QzW=d0@Ud|Et`h95HcsGgcIEs*9-PHgMj_ zISV3DYmqC-u)}WFOo$NlIoY`iAP29Hsrg^cG3FW#XAk3j6CmxAG#Q+`j~~o}7&Y-l z<h$VI{epjn6hg?O{LK_FGY`4N2jm~3QL-N?aNFC{M(A$^oT}eG#xt2%cgw~YpwAV5 z?m$YjgCI1Y0VSUkUMWgy$g-Mwt&Ex(4Vi|GseVI7`UL}>*r1Qm;fwihe}Y<{jxQ0% z?Uq`6pH_5Th+mrXE$&_%g;_=clVE6JQIJAk!z)~6q=@;zn2r_B>{n1Qkn%uviM2w` zT3sv9$!7>>@MC@{fY{5U=>S=n=frMJyJB5ofncOr20)JCaCX?z)^D*yC_OUH>TBov zvpP=+MiTcro{quVzTP7<r$}whxLQjX#yD>AJC^uFPm-M@<tslJNs9UKKt38aS{`h{ z)p|zCuJdl(#~Ua9j~E*VC<glm^RoFuf2*Sl&#S$X=wRTl6?sX%Bk2#2d){`TgvjRP z$kF1kOGrAwtMk>kWY82~OBS?G2{L6S_>QL?L24fNfV*0!KKS!&Bgm5mJU8aZYs5Nn z6R<Fb{0|(#9TM|wUWpJHM8=i|QJ9ZWj(KA}&q$e@+V3eN;}lgKL!u3r@+zv1Q(%@- zO~iW6x~NBmKKAsejpyTQ+U@q<ZXVZAHE_)CbBH#P&lch*dJetA5CV17urw4?dnmI* z^LlmhWZ-5jkWdtm%uD_{Ut?-{4W~ww<zTDK(Ddd`#58WJ>T&-739hY8yw6X63B@{& zfRtn-s*3K_i}XWu_eCr1I%Xt!eI{jeB1<WfOLqW8UM-#lCpqdZ!axi2U|o7RMFIML zE^H7lTGsLvwPSGq;;t$HK2mpeJq7!us<as(jzIE7kMaT$%#>=-#Pi+bv4av|Wlc1Y zpn!5^?00$#$%<iWMgp`|rHW{XPriAMWjjl)i2<R+OTfG&uISfqbSU(XWVR7ITME5% za$OdH$k9LB55c`<(<8d59eO>{#xjX2%Ao{ZB6EUFriIE(2=4l{OwG4#c@l|<8LIvH zM3C8VkUt+;e9S;cJaW3-;;Rg!#R-oX%i+`sd+Pr4eLmgID8Z%Fk}}DzmWv@y9sK-@ z5<?AkzU5)wAkjr(^s*eGH++3?3Awl!$cTiuft}0#Ub8b!mgx7DzZ1SgYBAa^KsMrq zI<~q{4ROviX;J`wJQ)PR47i#(w<WQ7y-nn<q+b!r;74FBDT{>0j<4L~7fBqfp(Y47 zERK3L52}Gu)cW$$q0u+lL>(p?Qkh_Z^aXFi?=WO6e{IdX<qmU8SWEHw@QF$xDSdIQ zR!;Z{jUqoPw0))V3i~l1#@T1{LP3;*sEhstiZ$r<`D6oC{6m`yN6H(3R4`-WaOn29 zBC6*W&dSx_XweR#v`VGx&6U4RGviL(R!wuO6<(+`drJhNABQ;{v-(sV;5Z}mO~?-N zpW%u%lUtS#)w(Z5y1;C^7j@;(;Juio&+f@_*G=lUXOlFO{n^@8wyia(<qf0~z^BTH z(HSd70^dVr<am(+goDFpcb~uXbraPQPRv(YR->?VDw*vBxpt+G32FY8J@f%B$wHNB zgSkSNxc&5aN|sHhqCe50%`|;mRZu`Mj2K&H`j-1O8NSF8y`=t|Wo|+#7MmB;jx_m* zAdhR&PDup|8AO@|0_K`@^lOVPm|UB+)ktfp$zuqyhDsv@Cg%5POy@OLMYT2)$|!Y? zgx0FdQ>*V*(1kK@w{rgWfLyzDFEq=zKS^k0D9gJU4n_#j^q~^+>YYiCoNW%N_v(tc z?gpE*uM}_#?29$y#FA1l;z}Wz)qUq!>;|PsE-$*KlN4HKM;>hp<E8G?GCB(=cy~8? zacxANaM{8`A|nftJa+{qQ1vxE8)nr$-Eo78A|fQN)idg{#?A_7YL?`2qw)Ei#?+@^ z&BZ{cE|1Y~8ui<hMHL;r@-nAnGsI8}9dHPSjN`~w7;X86<~C?!EZ$p9`b`40T8`Ez zh0)`PONvy~BhJ{?bc#up-H$jK$5J4r;$un?<_YsbigX9K6a*0j?Ao$Oy6WC${Zt<l z0MaOOI4T^zilZE7Ki3V_o3rJaL8xnbF2Htb$E}cfJIGsxQr6=sCwQ7w$Pd`e9+ntv zRjreqKYj~3XWqriYb#p`ZA=9WrWtcK=?u&-Do6?%H+H$PEnCT<Tn@x6pAvP14dZ&Z zUxs|?XMS$VYisp<?#e~>Q7T#=)O%JEPANZajzW5X+5h;-#?2cJlfrMoOZSsd<Gf?a z=QQK%7dthDkE*%)ivg{BnpP{`i+IVY|2!!0``$TYmK|3&te^BPQDo~7h7gHI<;!>c z=xvQ2Ph{vUn&p6-9+2pHu_H;|mveR}(7W$ht7q<Jc(6t;Nn9!wH1tb&ycRT;ju^99 z)~U-W-rsh1-?O2S9}vy^Y{mpOa#GSXpDy3A<1q#UUm^=yWNKPdd(_TGNQ-=bgRFuN z!pMTy@?@)OZjr>V@cL{<f@$ZcvL!c(W)&j{l~2LXqxp>$85>w&@i1li)AF-dCR!wF zZ<tm={(3mJF!u9!ZF@IZrc0k2HLlSUH)}=<TJYyw#+>9s){##iL5Zp4%#0_>d_l%t zj40mM7E)~JqdQr99o?Q>p0@>$Ac58%ilgk;e69*;bQkZ99^17%W@U6xP>v6CmN)RI z-C+MMXk;<I9ss8aZJPsygRc4h1=uMq(LVN_7M7xY-3LsBdGGZoRf7Gj=su3`r+OC+ zJ6idz5#L`90I$Pr`Xnd6Qq-O}Y~uPZo%Ni#2t_RITW3w1ieY#)lVNM)Q<PeLGNJ65 z#!V_J3+D$)90CY$8T6ik<-*&scKUjiTiSP#vgyR%I%tErX`s-;1;@h!nVb%@Qu)xv zEtf2QZlT<TTpE;*7?jiRA_Hr}@U<4?k8!syG@ycAml0nBxa6SJF{^Go*`;|<Yx8#N zfYQ)pmjQgzT#FAiP(mm^z#9uCIJ-S(vCxsYMbe%f@#)9Kqfza2S*6j@QjuCyTA?OU zpgHA~u1rI+pzwT;G32Hc*lun$>lKMkvwavZ#O*W9$>K435{8OJTV3SiukVd##fXva zj2jt|#vEyEI+1{UskDupO3AF367O+8PpHF?uXE6Jxb8n=`gw_}w$794_!zQ_YHr1V z-q8^qQqyJe#{D-Mr}Vx!UV+xO`!T66J8z``1aw`kC*lpQX_$tJ6If5HIbVvZrYo;( z$(E6l1uu=K`sLFx|F}0pUTUI;UtkShzeOmOCf?XHcpky#LPM_Jl?Kj!*eb(V><o@0 zU~)lGwUo(g;m_Sk-rWK8!wDbZ{$Poj0Y>2Hw7$W;_*Ld3|9Htj)Rx!UDx|xW&U(Hx zBPJ}Xi!|npvypA}>$JrCRJ*R422T<Ik08&9F?;@Bjn{7=@7>C?ZhVdmgps_jMhV|+ z8BHG02{@6I8c@w^dk17^J2M~ArtJ$g=2={g>KrSO`F~I9`Nv4d!bm|?{G(*K{N&fL z{J$w#|8B4OA64r=9Yx;C>k1np@HpBko~*$1zYqOTN-qRz#`_ca5Gj)#Qi7DmZ~y9t z?_WepR8BDFCI2o|$1-vw<c*gdr8^~obKgU|i!1VM`kUG3myx3~Gnu|%sxh%-ae5Hi z>+@MCHM(uIC+dF;!8J!k4@+QOhiEQ27$05;FG`{v++=*$oj5Ri4SZQF^%pXTS*kCN zP=GS%jtxYx0=%#2mpR7Ji+wpl$OaruD5$pgpK@7tXQEB0^yyeF?^yNQ^kc<Vm52$L zaclI>H`eH)sC%6b>H__^BsiL7=ht2J?Px?AoYfUvQ@kk2L4NSP5kZPD9Jyaw07n+! zh%q2$bi39%LOXQ1!jOVDQUOCXcCS>sQ-SrxyD=}iA*OJypNNy}1X*#0;aQ`^8WSOm zuxmhrbC@B>2!BQ7X#5r#7frl;2Lrd70_48U_1Iljk7*ZH&YPu)YGRODEHcHvj(3Q` zw}C?_`A8i--<|J=`tApgk0!2RC#Tl<xXZ6DZKHuglE`bdpUCu4(!OSFO!>S`3-@Qk zR=hBwWq8>?4MsLztp+Y#SglrD8s{*U=ZyOg)gm>%smt$XgNi4^n8<HA=H&$f4p`Ka zkBF5cR7oY&Gsk;!rp}-<X#_1W8`#JPiebW&=W3&%r^T2t(_31VM@WqP@paNR*u6KI zBgFfdfhvzPOcWTWbWWhX9;ixQ*Z<rtuvYn<qc+kcN(|D-T;@!~3WRR<zicpvAix7Y z>_>%06z$e_$#v<}$!-y;v9fkW3hG-BCI~ji3_>+nV}OK!^}NAN^|Dqx+(Oq{*(;=! zE8t0wGmZ&&J)f#1K&7>6o4Oz9AZU`bFYo?9ifeVdCNP7UmiEv}IzsNMX|dB#KaV_! z-bPmI{4e=^_f9sny9XrjwbAH;qS4M8V?kS>2o8{`>s%E$3JK-12dcxGp}sA6F$1V} z{2e0CZMOI<QoD57FBkA9z>MJXZUDM8Pcs!;1(<^MzE8+>i-X|)B$ERvrt@nH(#yHB zEGc^HxdV-mVL8hduKLliMZ9<=2zM5c=994I*?1<=F>DscAlkV(ct8$!C*Vs-jC}|O z$Z)CbC$HRKt|mb|+n$r-p`In@sjy)ig;QuQILu!ng!tR71%<nLz^*a&3}(j{Uw$0n zXKEXa2SU+W+lJ4zr@!o4&H38Rc?N){p>R-2efHa%0-C8EiP;W>C)(Ia0urDgFajL$ z23X?d^o|QcbtTe?5@$li|1ZAYfkzZ*&9*Juwr$(CZM$lhZQHiJ%eHOXwvD?_I`4IN za&!O0O6FYO93wEvSamJCF0;<#pu&W6Qi;6b;m9tt3#7Rttwdlx(+2h>PF<;-3%1K% z-OsC__D^olwvUTp^1+|i1S(yH<|=;YC#P@FH?9UQ9CnaqWlGv&6%hu7NOr=HCWn#z zBplBU1N~M#?WI<(9_pS2JkxG=G$)shAWc@O{1ycb*qvvZTs^7+8^suK3uhMmf_^rL zzn_F^VurUbVO<feqbz=cBj_UaEEMx$2Gk2kYpRqztW;?dwpi`!UM~<a4vWJ=@BG8h zipi+$N>*4{c2~i!AE0$$b4!M%Fj_tE)A|#1#p&MLm6H2aPlNZ*Rx89Tnn@?g!^6Xy zzrg?9;Q!~{yJ)O!!}zyh%O(9UZrA^%?fP%#*#CF3^}k=eVJ&GJoN<quo7{7cq`@!= z#RaLuZI>?NT1nok6gBGGpv2>pX6Z>Rt_QdVOO`UPF+4c)P*z?f&IE+M4PFpQe}XYm z!FXeT0LDN7z{G4v2=6;e0Xs_&hQOl%5C}&JI<LA%KR=h}r}!l@Xb_0@>c5pWH8mfX zpFirB6-tyhJD=;~*HuDajS}A)Pp@>}u)nEL^5JADp?5O#tRjnZF3K#jx~(FM3(wIO zX3o6SnVPz-qRiwxSgDBHU2D|gW`Y<N=Iy#D(?rdd)wCU?_3CKT4OXXZx`@+I&5wng z#9e`Fr6p5PyC^x8cc(*6Rx?qz?xH-OBKh8O&^mo-*v|`ZTK6r^qhZ%}d#lBlpx+y6 zz4)%5HK&tWo$`LVZf(d<E!NipH@prdy;?khG;FajRF`5Ve>xmD;VaaXnx_W?_>0Z% zUk0ba;kQ=k_@|tz=m#Avc_Fl)6nkHGJd->B_AE<Hauywb#i_gnno=882<4Lfjv{>y znN*k&;%?v-OASmpZI9Slo|Y?{OS+rZoQ9|)?!c@<^DI~2RURM%C%&8nv(tBh+AUB= z4R8+<PY!4!?J%vLKQ|6&?{i6hXWz{@`K0Ri5_F{nyCtluq3)3GFTYXpek9)MoqTk0 z`Kz16ws82m_z*oQVmJrg#fRYEyfq(rvuR}{d&_)u!eV}x8ldo@4j>*>R5H{l7%~<Z zolA+SH*^>Y$Ce*C%i{rwmJsAtdPE*nc&Z=;>`7_*H32ykF$Lv{bu;{=d36&UHMf3v zc@^o+IS%IURy9LN4Q{L$+G2Dtfs_vTT7~O-Aq8{0*J?!hbqM}xZNcSv@v3@a!|IPG zKk2yiSSZ637v8OEzm5+Ux8+|_E;G-}_iRpgwp)<N{pGNDPhYhSA#UB|Ehc>q1&k@y z4AKky+|b)4zPof|zmY;Pu(7S~c6)-Z^iebY+0xPO>~cMxIBu@O_hn-~7woi~0D?^x zMKEWZFhEXVP5h@Ff5K_*C}*&5^)bhY{x0ugwQBV_&o{?NNsn+S8Y4OqOSXj-3qVKp zq5NF1oTn<f5O^8%t=e_L`*f6Oh<lKmvwqE4QBx_*1a`<zfX-+bq-Z^b10!j*=y$;H z6kOfD_^?9xTbmofB;321N(x9d%*+~<6!9Z6<`mx_^H*{1d8MVx0HbE%M+{t_zwJKs zafE&4>-xGGt>4|+))B?}??1CfSd)O3Is(@WtN#a)K`u4MleJ@opX@es%}A!PYVR78 zktfDI{vz-sk+ZABjkH6FarkMVszs4qY!z#!#hJW8v*2lPOrpVkzTFsV_C|X#N8AA^ z72gnedU8{-gD8EtzO)*%=*n&>(GjY%MplBSuUYsU5-zm0r&%OhN-BrDb}**>4X3il zD#}6@46#x!Y2^*n6VfsF)Jp91qNdR=^#P)%Q`dBb2b0hbSf+};WxSm25;OLp5Rh`{ z6XGGW{N|{GXhtdw_&iO)P=Gs*JQBWXGGq`he?y0FttMv6R<1C>y>`Lvc%v52b95pO z^dd>TrpT<ZV>H^Esgmmq2s%7rr3c@HN0H6i$Z9lcqs0uihq1Sw^n3EFmKlu`_Srns zuW=A6$#^QsZ}zY>(iuiQE}@eJ&#~C%5O5eP9%M%msQHlXO1jh#xR<*c-VdI<X`>CT z;4}j{mxo$88a^X-sl4RIQ^pZBi^>nITms&$S-bB6w7jOvZocX*`x(c13_sIY+tB0b z^OwybL+>aaWJZlV?a$gn<J9SGYj|zzUvwKzn(#UbF47+Z%$GY$u`e{>)M|?9dm8G2 z$g`=w)KU|cDuy&)BsEcUIp-5YM{X8*wC-70+f*~rpy*nl!-Ek;w6U=w2F>mrEq(QJ zk;k*y`LvRr=VxM^hj~8$;gJu;l%L*j@ZPw*ydGw~bhR$)Uf0L4S+-lGq)Ycx^ryus zquA$<!Xa?UJfto+@0C8xS<=5_`LwX#x#C)Ad@?M=->LFztG3*Df8d2VtrWeM29y5f zT*KsDD9@WZR1ihGQT{Wq>p_a3vIo-@n!%b|_;iv7q)4nt`uzmi_#LOgj_IukC@Dei z;yvmG_+vuKH^n#^T@yIhtdiW{p@?aNWWi&Q?lmGVLw-?Y@ai|P#Yr+*EmpIbO3ptu z2-6cHZJ3K}bXjM4Wj}!qJJlF(v>4`7(VT>Pl+5HHO$YpBd#^AB1rj(W%i?Dv>*)Ov zrYvi~gkQ*M<&bL#VHR)wtltEqd!~4c;rqmWt%9sVIhn{(5486NzqI!h?^wB~8Ki8$ zdD(rx_fgmA-uGn{^b5{!TXCXebV&DNh`>oz;2=Nfe&_u^ah3^F^c+WwJ`DyN!F)si z@P@4F$%%P`;bJ~!U$4z!9R6$blAIjMH`9G7H@Wbu;oZR-_F+0W5B4NEJNdhhPnY%B zBD8!f$w^Oh@Zt^X#L-D<ODFw2#Vv=4%%`8-nX9+&tmsblldI6<NnGcXB?nNBE#8g> zEgk*#qpxIqsLFahV6i|vM@E8(INvzk`dJ8HwYwGCNd*tQ=~&9=(a-2h_y2Uo?Q{j~ zneXs7wp+d3?{~n3q@bh^4Qwh8P?1#>E9sT{7IV)TEf1wFHlvc-hNmosM(dcc5)p4# zPV-v*N2Rjh0xYS2@|?*Ehn3r$k2%|%fNiM$)4CEB*=mSLZH~p$PHE*+JZmNGtj@7D z$gDN~`)E5=c$OMa<)9#)Ugn8D9<Ur~z@heK!!u<|H8GWI#RKuh80VK=XI0*0WlGv) z0F7C5OwEvdZ8ps^m8y3rLPtBy94E{gPo;bB@r0kITK$c^bYggk(7mJ`%E{~80snkO z=9{_1jpxMroe4JKf_w8TShYmyZy&GCf1}F0bBj%<$1&*(;v1;POKBD*<?F7AaEO*K zLCM?6%T(VHzSl*0eeQYyM!EC7G##c?I97q{&q}LfeaNEF6HKs|<PLA`i&NU%e$JUC z9M=gn@<H(f9O{9BNwZ<ofL6BQFxFw6G-*OhM?OqJwwZe*QDG3BQ1>IyL*Yayw2&{T z5KL}k7J8Z~{m?8Uk6RmLWE*Qp)5{k>YE79iDoB<`>=*LedtFG)4s7)6(~7d0h8FSK z<j886FN-#(kiopD-nmDnf&(+?k&;EczVW`Q`#$WhikYBdM}2Qwm|q7ajYhrNP+^-! zb7Y5;<2omtVw7fisX9Ph-xlNL{+Tc30TCYCu4u0#=8YteXP+x2u@!28iy-?XW+H}o zDKJNl^ll8DGij3oAr)RMSvT=(>J|?8PMKtdnhH-9_6BbpCbI?rtF5VNC>viR|HFuG zTC%zMa;)o|8}P+UTgYAzumMeh=AgF%GL*27!{2bc61%&hT7bMR5thTLb;A#dd#E9O z<c|u`NJ^E4c&H;qG`_f-GhlsS<|BUg1yAV0PJR?pVa$9W+{wzx!m5HlT0G1!UGB59 z{F%HfAMm(hxfcyDVv3av`t=IQVZI)s!?pl-6mhSNs1qo?DZ?3W->Oox%z@UKu~@my z!|HnIu)x9?6T|7+&Ka>OgWIY}e%SJ)z|G217M2(gg-?Gm%GuWb;UJc$5Fmf1k7z=A z5yVyDdudr&f1m)O7F*^yqlj(v#t!qOGN&UMlY^+dZNbdEXl&MA%d)I~-1DHai}R{l z`oR(GHF3U@Qlj!3$k8_Ooh?4Bck8Vq9L#~4R4^7-%>e2ry(;Tz_&Xad?#@-Th|NDL z7#daRB*uPzo;X6Mc?{N08uO8HZ+FdRQ!Ph7a7&`MMGR99zX5l)Z_zgkNCTp*K;&>2 znygny$xw>>rn>;{W9s>-jjP0kY&|)1xY}%)Em9=w<@4?Hp?GrVVhb0S&U7oQIqz^X znO6G~e|<T^;e{MC-8uc>c~RE$HC#>M2ilc(Yf*${ir5?~MXRbXm7gveu%<Cn;6FJx z#m2_p<;t45EN7Md9z`rCYP+^OMueWT8x_6h{sH|@3*9%(p8nSX#d11J{p>gG%nfa1 zjYBxN7AxxhR?|wC#k>FtL6VLPvn#nX+rnR`8dL+g%l1p(+COU~8LZ9ntCrQ@v#}2y zAyC}^Sv1GAaR_OFEBgRa8pj>$Ks<C!?%_o9EFcKrJ;~neV)~Ja+41!7(_prrE0h8X z*#S-cZT|8gW7><xDL7rxYpQr8VM0@{U2b=+HAejNR}2g-SKRj>Y4eeMo~P%nU=vg| z9536nW;ngPLIpgiRqxw~;QJUPGvp6`(-)uyMcO>%s1y);g6uzBm>#bij^_y80;!1? z|AE>m#}}UBJrb>thVdqoq!EBG^hu&3ncp0n9^=en(*1)&{_v)?sd4r3A^!-LlGGTw z8S8<>){FBGjf^)Qu^3D&LzDx`HU3ut#Jekf)8V6`_=WO4%_y^JyjEYtvC&`_C|QlL zzGDXhR!_fpw)wN=KSM-FTJm6Js^!J8iDkAl51#|v8HV38IIu(o7_X32A`VGwDII}T zF<+ToVR9BoKuqIqAQ6udcmT8W*pJ;(6lFC7$&QS|qrjoi&jd>N#XAawFY0KnG?TW5 zc=GX78Wb!a*YIz7v^#LD))T9+KCuSXxXXN(0Zpc8Bt)gdhBaQz17=K2MXN^`?InwQ zwY*9Kt3#a{m(4c(3>KmOTPUVM{vbd;a%99b$D4dMG44N{tvj&{&KGKIA<vgC-%_^1 zMNlRoeo`4+C&g0EA1Tsf7bea>bB4l6ri$c$nfoCwvE@0B(rW{wlRPmo#s@StqVE+^ zCP;*9*CKAR1>qujz|Q2b%L_kXwO)Q+A^+t~XAtVEnZs0tzs=Rlr!HF(TL&m?b}-Ca z>*eYrtN0%vt+Wda!7L@N0`FSdFR!KdBcZyL0-O-<HZ9BJUGF!cP^ym+LWgT_f#Hus z!PBTQva#luPKt(?3{Se0+rp-j)QeJ-!gzyl?H|5#yfup$eaI%g9!k(wD7{6BQ|y}; z$oQ7eWW6p>-cgA|`*k=y)@N-iH0i31a_-HrDY>9_`k|%FX5}f2v)YI65&VD2B~Y~G zis^)c3sA8M6JsCt=pBAcp`6eCjy?{h#)Y=39xCRDG}Wj^=@}id-1z$~N7FF)0Z#(B z)r=>$1`dGSz_d5KzZ#U%=Azj`xgy1Ee3y^?5nG`hT%RxplP=gTmOmSVNuO1bwr4pm zC)k%jj>NhQj(31&*EzI1h5p<gjC3>g1YVv4yiSkz+7jH-t9en)s93>E;zw)n1~3Y5 zDx4S2n&o%T5_DE=^{N^aJPqFy8|F6if`n(1_8_Q9TcsXc0z9!seUX%)$_J^QN5G67 z+>3edL9L@F5Q=0Vi%buCI$q#k!x-9i<twIm`cavti<tjWoHrZ2GD!JDEb86paeA0` zkX5bl9R$)KwzSPQwvu7w7cqlKZWKemeeYoVSK@aMyt!`?%mPD-D{nSBE5YME-%f0O zKOZ|-am4S+)#W9eR|PtaxJ(N)?lcxzx)%=eC_}TQ-XvT8{I|m48B|B&b&Ge`p|J4q z>bYAH{kh@rDsIc}i{z9;ulJY(=|jxa*%xxSlL8@b5*B4wcwV5M(r7n>7vsEWO>|zA zuxypz!A-!>AZ$B_33vP77^g*tvRA7|>F2@5w?%0tMW32JCGB)JZFU*`*tp9XcXQU| zb90kK2$Mtt1RztiXG?c@n~uC76SP=Z=xY%dRnxw_jstUem|+N2Em1VgWJ|GaF--~$ zB~7tJ0N~rdM@r2(T+mgW)scQpH@UZD=#veEBbdT=!1QbKCDZSG2<oKzdG~)8E!%Nx zf;#`;$yEgZCF%Ts7A^n(iP8UVTDmo5<FQ9wZgMeU`~mCwjM6@dBbOA=O#35UB}r2) zLh30MwX|cKBPF$@WkXo|jld??hi44Dzz%Ng6DrfC;P~3JrAX7Vl`2#!9b@S!@qHe~ zj~9>Pg}v)^j<p>fuB3LnczH4W6DL!oLZn$dJ@wprU!N~mcde_NwN~ake_!^4Rxv-_ z)IQ1vPtm*&{QL)urveh0<&BAFaB42FoLE#>Gm5G@`f-Gpsi!I!;Po(VOd1ZUoGPOa zokDW0rz*zHlVUEe){J6@+iL3v!5*`&AZ1pK@Se1c^kQ)PjI(@}s}2W8VJ6A*MZnEF zHX9e{HU5YyGDUvqA>gegkzjyI?v1`MAh|xwwf>3n^<={V{Yia>%xwRJ3~Lx|1bg}H zLw7(3d2_F&hx<C(Szn9WulK|bdlKDnr<MR?2>sLhuBJA193_a!Eo}G-OyMo&UXMdL zBr&=FmX0ig%7RNXGzz5!vJzkk$D%c5t<XKuMfRwr0uI<$DC^P(Xro`s1>u&_D)bEY zsFvXta53i)<8i41PQjkuD(Ql8g!$o@;4#|}$11YYIn*`z#1{6%X&8uj4$Z9Wq%xa3 z;_Q}x46(=l(iubXg^O~Uox^;Rh-?_515BM+c~)su4&?!>CbO)hnu0YDmeNtFQMsUy zQd-%h(GUy;Fn8y^Cel{F0C2jXkROxi=C%A(b{i@v#0Fb<cqoYh^8xu5#EbEKxVFRJ zcvwu2^i)kk74h~`MBowrO~d`m4mCjhN$@rX-<r?P2f_#|^W1X^i7%Et)MNe{2I&tq z>suH~7uTc@&})hs^J+jc`%8iG#$o3dFY{3}k6Df~0w^(1E@%M{?C@1i@BPW~(6_6) ziyJ_fchR}|=Z0&U07vY`V7ESSZnz?U=h6gqVZB1QD4V+~?i0KR8@wWq^_6_EfL_NY zqHzSF&m)~*0|bGWBc<OR$vxv38WGYBfXgJOK0MI^A!aM?NNy5q&e2~ZAFf%)dH4Ki zV{E*>1n{IIq(N!<zC14+3L`1w20+wH%WUY!f}(QnEl!4JaFxEdi62sI=cNaIXdEq_ zmDA_=X~g=*y0`TjAIAp1&*8Pz+{w0+K{~$eX622hsv_+2Y;?BBT>Y}Err-R<ypQ=u z)x@iVX_HF3@>i~&IojK8Zl>H}1Jfw%3-M?1gky=};=W7LJfa_tdW{A2bT$30CXsC& zIW%T}RaH7gD_=SWcg3N0UVsaEmvTBkEsTC7Up95tpuAPBr*)<xm&N`S$C4%$sG%f; z_CTDbOA$%CaO78^vBg~Mu5K_9&hC29G?`47VF9BPC}3UEt3;y+XQapV<1OY>nL8SZ zJ2!eXLBji1s+M|VZdfy7<R^PjMnr&buX?V>F{%7XZ4b*NWt*E@zw4$N9`7TF7=3&D zIxH7jFmG#0GXng3E(AmUA_G&>{>nVX{pizpKF|;(H%adEWya+-?xxG{*5@_I?WS!N z4ZFtt?<RNc3>K5ZrOCmlBb6J|3qiO^N<GAYi1VEQ)7fOj;14euXakik?e3&A3mmUD znl4Kz@$0tCBK%ypo>15!nf^X{{*{$&cS%MUFe`G;rWU#t*X;xA-=Z>fX}eC24ILf& zE_Bvx57hUKZM@xU%O(mV;OjX@ZX_<b?LO_LtpT(57eqKI=KCih$*hba|Fktp(eryP zP58U_Y03&G3GvAh72{#K2NFTXx$!)PYrERS9`DgxVVD-m$aRditAg-YO0`jAKLi-y z@KVPQ`5)|MF<53`VRy59o@&&MEY%VP8k(jxB!(L4q8Dc%Lgo^I6@La^7&r<kx`Fvp zyP$m+b*K`He91XCcWLQ7%KZicEgB>sW#zrDUlfj}VN{M_NFHJ`Z!u8<F%Yn<g?CB^ zZgv31nSjx)>t)wr(~w~I+&uvBo534^j%2O9&lVL)mSXxOex3dSBI5q*{VC|rBAk3E zK$4ou`=L{W0jw)6&)?)$ek8$zG?`!KrX`|T!Q_svis|>q!Y_f@0<D1AN2toQg6Ai+ z!uyvXY!p%Hd!-T6zJu}!f+iA?KZJ$jtr$b`bU7;PJMo0}5fSqmH&FM1t}nb+700y7 zXBq_vvfJ<x-3FZ*;OkCFc!t4LH4`UIVpvTSTB{Xs*<e_gV}4}_&YMR|IOqt%f5ez@ zUF|B8f(-kn@v&{_w+zJ=OvTZVYaRJ)2THvVr@6>yrsw;pFvp;Q4X<DMo+xku-uZ1C zJ_*fVXMZAce!4}j{~)rK15#uyqH%{Pmw`_2nk|x|36!xlXhUwiBT?@3Pk3Nc-cAD@ zFx_OmEd-{4ta=2Egz{wxM6)~SZj43$k*b&;M76RI3<_u_G_M^r%HBHkBKPZieUW35 z#k93vI6JkVO_TTwr&)zM*=|7l)Pw)y1bM;69oYEX5=!iRwEwa?F=uM3)*z)_CH+Fz zxTqVk3<n&HCTlmHQEfO#MsrpwWHCRHB(TY?FJ{t5kAiaN4Vd?i1IDq873C*5Q6qsY z%XZzcc-hvz>pNF8d|9YkE6hAmyC~%{ZuBrq&UHxMyYxZ<Q+-paZjx!jpGyA7kQt2k zaI`*OpVSijX~+;fXm`mFJJ9s-*NeM$Ym92p;Ak{4vgTUsB^#k(b#$@m!Tn?6u)@6_ zf|>OS<t5GslZv6Ecy>3Ij96X{KNw{~Fgy`?E)uLzAjR%BP=ded)94N%{QY)qG)W^7 z(qKmM>{Jl%on16%Y72g#hhvhZKCgZ!v=|na2X~7jpy(qXWtEMxZ?JgOhof@QAX>^q z4WYAA&n564P7Nk{GvoYSBm%aHy^27?VTJG`pb1Spa1lu>-zm_9`_GiK0D)Kkvph0j z7e7CSaoUm+K?jIki<U$Hk`z<bcY)sv9Fpw-J##!a;eMQvK1~5_-e`U|k?;dL6tn|i zHYwJcY5?crLO~Jk2qr%YuTWWW=VHo$L;=(_wyA7e-hFWDs%3!<V@)GVI>dh1L{~I? z4w)oO-ylHjFmi#=c2AJv7cm!@))&!SF4jCwPU}0EH_Z-6!y+h^%BtGlCQyWn?5dW6 zHKE`E8pE4vxvgUkz2G`1-|oTenQrXRcp#$|4rvFDr84-ZAUyQWK89tP^HIFeFsJf# z27eCotpFl|EPr=E!TvS)>RI`5+c?|tya0K#WWCDBBU(%DBB%Fb@$gH&XKUHD87nAl z!F<((>EJNJpG0{ez})D>DFX6p<nW<Cqz6vj=Khh`3SSs0x)YovSm6M4_w7k8^SsbV zO4QmoM`+epPjMx~uM}%%6LvoHH&6>nvOK>KAUw{ygM=gm?4*Q{?mu0SWyK<-@+9FR zT^bw=g38o_k7#JOM0`kyk(ByrpIJDH9XZ|+)n<r!yI}|V^G(Y@|8V6((KNQeGbv0` zc@6N;#g(RX+}VWB1tJ$&!78x{0cOZzsFjvbv_oSi2U#EzA*yVEs4!n#14Ne((=cS+ zFpJ7FPNIY&b>V*u?)3utVZzz--!QFqa-2|t4OO*Q7Ov%k_Sr%H1|A%`C0OlwqSCM> z@W8MQPgWwnsf9Rd@&u}%Xjg%H^dA+I1-T}4M!4ua9}~%{q>-UqgVxk2w|m`o@A@>4 zl5#=6+zQ?2$s{;SG_5o}t#c;!Fx+Ja=wQCd80KqaX-0;%De=r!_C!NJpI7cx{SNfQ zVD<3f$D8<zi-3#O0FL~2EbNhkZHvY`jhhH0*^ML=7iJm8DhN)iA?H2@L@5`RadL;C zLOwt#L<x(62D}o~RwD+?83gns)}qnCI?9le)6?2R5mj(Fz;fggzL#Ik6UaoqE2fV< zh}Eno^bgghF!8HTETN+SbZiZ%VYx$weYF_9-Rs*Ma0_GySfDNftZw-uo|Kwi6?!-F zEv;!u4qyECR5if?{%u^0O{F1jJKo{g_=1p+m;Ol>2D6t-8@`N^4i49FpY~WYmB875 zrYik606;iPb_3x5bc)$Kd6%8}lbV+&=OWq<b~oCg71X=LAYCDp^nkcmp4WUN{}d9^ zq4JQtvgm71_o-(fj!M=u`$*|ma*Ry-{erAZDZ3=*l&6=9lh}-dG&Cr}vr;mRjh!Ba zN%KR^yL!k{D_~_`PA#(PF!A25K8~Gcj%4lROS!#&^yw{M14MVWi}8-bzxexW^KB!p z6P&MbTYv8dB*?b`zihERyhntbxv-;`1Nsf!SrP>b;{nd};o~lChEGk;n`_6P`*PL! ze*CktqUPxV{*J9TDvX2(TOZs7AcgR6GP+ohp+}7M9U2o6f-ja76z0lv1OG)7lCNF7 zmrj?mXTK?>UTfr;{8s;sv~)JpWj^_I6sdHmZT$S0(q*289HfM~E0w3L<V7UGCrY+l z<9QxcoOUhCAUVzom`Z;Xhe>a^W2pb^c}{!TioDgZdzp9r`9h2skPdK6^nrUweV(aQ z=06!Eb1^}VXY>t)r-}`fk^hE-maJ=Y=uri3n0S7#nVsQqAeux{HHQnE(;<f&E1h9z zighF)a6^7C+`*OTq4u4#7{D)v%j|@Li?cUO<G4{x^g+lopJQ(=#L<C7aF6pcGWgFp zv`OI6xFmv${lHNIV=iinmxwMG`|7jLl1R}%Nku{-7lO9Lh>T9(ZGvP97qB8SP*IV` zjN=m@9!;;eq+}P;8h+oK4{aro%p$FSN>+>*UwH@Tll6r}f<~QelOAv7EFkyORtMW; zmDTE;q`ykn|9D!^JkDQcco3K@Jvt<Exu;vObMmY-Nfo_vZ2K_|WNtA~UfKe3sHNpZ zHeNy^rF$}Is@WsLmA<r+(Ho)DHcL%0v*p4#0DWaNv1}UlQ6j8Unum8b1g@32^Fd{@ zPgPI{46g?K$1vop9frwsOSP{!iW^w!#bNtOkOfQ>;A`K7M(_IkA#f*H1P3qTrGnei zn(g6$s(U6Jy1q?J&A`fHW|xAF?4sNBs~%zzVs)Bkl{dC)9O6=Tl{e!_{5`Ak(sRDg z1yqkG(!9Pcco<q^&!v0K(Bnmv5^Uc3Absd&%txX#afG=!A<&L+iNhXQ#ZKQ=-|}MG zs&VHF%UkQtoGs?2sg>pjgxed@r!`U=;t%tU!6GP4%{<+ZG|rTdkz}%^wHo;QABv|& zZCr&nFk69p0MQ#`VvXHA5_rN(a<9)K#5HT*&>79^(%_59aN+1)%>3SCzrE4BvSvfj zi;v&`ftLCYr&F6N=Gx#t<UjTQG8O$-S~qqy^z``0`ZfJ0IWhmYXk6y8{Rggb+I^>< zxi2Tdjzlu$c0p}amMX=OwUJCYBdfrNg#r>sLWQ^k6p)t5{@vN`M&AMiS8~i{QJz{O zf_L-s`gHB|^78(<GRQFpU!>sN8#iy+K#5|p<Td~N?V1f_iB5cH)JAXoUR_)8g!^;% z{t$9L8U+3m*8BFb>EqdhdJC7I;=-+$hU@+^$ipcI^Em*AFDJL2=7{nY=XbCFj{kWJ z{2coImkXE03;ZeZ$MdOVAriq7whgErDgd+VD@**B=VEkES>8Y4uhD(kxmA+rqi8=@ znXaod2gcQ)AN`u73P{E;wRsWpI%1ElnZwX}NM7+3|B5e0aaExC6$)08&{HN&VfNn! z=iGN`Fnn{&QyO{m;qJWq+jTPC#y)wCkwFUj28#|ljwq-T@_oTfLVwabi<bTt7bKuN zqkc@8hAB<1BKli8z6Lj*{S5rZs%Ms1pcg(U_e3Y0o58EKbb9x(Qfw@TP>wALoHb1- z|8F9xq+86mJ)aT2N1CwPD+t0dOOh!(Y37xC=pi2CI=!=1P-k|UmncVz-R=*^1i~n! zz)lJEx_nT9VA36NhpE!+zfOGGqr4!1IqUMLN%(a9a%*P?=r4<BAD+&P@5f$eFoiIG z-p%O*L?=-d_)O}mr{p7H^J5YCqHE>-{0WPa9$!zB^z8x7Pm`kVr(wA}yUd7PSvzvG z^L)MeJIvJaYisHLjQEV$aTJQO*pxD40oIv9sla&bi#zO${`3MUI|<Ojtq=T81+)Xk z@c|q0S!`K7N{kF!GL^9kohC-^Hd>4%Hl5Xf(g0~vE^tXZxQ{R6amxq##&u%}(DS!P z1>CWNK7nJH&%^BH4O?bDuSsU2&*ez48C~63FmP<)cX8l6t&L_W_C8Ou?>3D@@W*(} z960lVF9t}zUzsOZWSgER*3DPW|7rHs0&w#d);6FO%p~C<Af(u+Yhsxt_V<s1T>K=F z^C?~iDbSmdTPy}}8L0T;up|6(ltRK$Awa+yiU{+0VHBSVw_v^V#h}{K_8+FntYt1# znz<2t5M=eBVW2*}tH5N4Z-SHP#+12geL#gT#Dv<8G*`qL2qe$XR!khA$vQ+czFp*O zG&A}naCC)sSWhERc-@z7(32C)lL2Z?e<Z{rNUVxR&Q)q8ODpria8&m94z++-YJ~TM zl#c96-`5!iV^NqW&V=p^;|c$kv9=n#A~iNwY$3S^K0g$#V<>Z;p+ulRP38iw&fa$y z>eywV)l6joeeq|4U<H1Wku=x5p|=DTb(sJ&AR%inM83N#1uzyvTWQq{!Qq{5i$em6 z*7l$1TPTj+lo91j<CU}u#yDN-+3UxJ&sjUFD2CP$(q6&Vn3@?U;0Qp4w#2es5-^On z5}=JR+|^q-$8@+Nf3+atIh9^W;1I$cA)BMovD~1bDp52j5-K-Gqy-&J#fd%xI}P~m zk4rQ{PYEv=(=}M)0*BVFZWO5oc28Ts#OS{vnadinv?q7NCgg0tqO}eG+AvR(+|vui zGFa!VcK|dufWkKeI0iqgV&Q`F&%l1=3M7~oYEU0&Q-OubED?by@28$SU#@Hs>rSO= z9G<X{$a_*)=)AjiKNynsgkmdZsi?-XaChJ&%p<#EW#W@PfIV!)TvNpnTyj%{M<78e zv~}%Q6d{F@b}RrQ65I(~uVLOcYefK*j8%X+qb7`#U>sy|s4XZ*n3g3t-wjDr>Rd8V z0u~5nh}Il=P0?##7pXzQ_{&KVvsTa#DaC9b*+3(?jNW|s?+4fTGT)-vqW1>fvhOHL z5{m<SJo{0m3mV|vl7B1`^&4CWoF&yqzLs2F{VoSR?g|=zD)$n|he8G2#IdGR2v}zK zfyWP)Pan)-Aifzkt}CYYAbo?s*>KYK72^kRYm_m)ve;s`rLUe-*Z=s?fv!As2AfHd zlbJ&uT2~bQib{YBMc-~DY5aY-6WanaJoPp0cIRINv)~{qKX-%#lN2Hi0qs6%e-duH zGqGn+=#kms`o2RWzaP0B#UDXOX3VhR?&at#ZpQ=eIMIVxD_cFBH@V8`>gD-X1jg6Z zjiKMU7y)GM0Y!<<6<=~^228_9dxt}V`%7<fd7Lu;mWWk5Du7?~j9TbZqEn+|Qyko8 zAB5<jVS4#>{mJNv_}ij=3lOTq&4#5<Kbb~azmZbPCMOj-?T5h4XS+>dWFz_j;m3BS z-oh8{D`vxMlJCaK^^Hido&Ae`@NiJKY?XkX(a%na`prqdqpUsph-6R0QwzP_$2#Fu z{Np$A-M+|6h6;*{V;P~8#ZE=mEt*Z<s}mDJzIJE$CCCaRk`_Np5FV3Qe%A%pR@8_$ zXc=Z3Z}|`<_FmT=%KOl)E`Th<2smq2PVjmWD&)?_0rL^W3y4pIk0<3_0X(%ZDhUAn zW!#%D$!lL0I;BKe9E~1=cTtOOV30P&jWk#T2DmRpej+JOIBzPf(aG4JEB=IltciSC zli%(=+P95iC32-I)d2wUKJF_E_m48vd7Qh8tW5CZh{R4h>6@rSdRnvvym?94PYB2m z9uip0r=PSq*q829+;H5JR^xn58Tj@lAaIrS{_4oRIJcy5sxr{aM9Iiv+FKi3s{^it z7qK_n4h}YjES+ZuwVHS&b(3PApN5EO$NBDUYOp6zYaDfnzOE2Cn#F!)+G<^i$slBv z5s(11%9iR*lWb3a3mJWeEDM^qVN+Y`g8Ns6H%vjw5G4^a1XZLHj?|X~ruoBewLz(@ zNz{4a{MR2{O{>zH4jAfuZ@SN^;JfZ1EgpLKdM(djN!Zu+0_#dco~z|<MEj%#CtLUw z!YEQ-R0Y7@6gz3QN$3fXH$~|_kkTUI4xS4&1`HiSCxjNaxVP&sw1+-7*?nU2RQop& z5V7f@i#9`03-sb>vDx`Kyr6nitR${$A6S^Ky7{}W1>)k(8RV?P*o?v@^{q<zo;USC zN2od#7O41T%K!%7<Eq0x=BH?LRQsp}As~;fR~d*XAQsWMjU;ABGV%Uv$zO$aOlA8| zQe}$^ALnwlv-ham<?1k&)IAKkbsp)}s-9-ti<E0)Fj!i5HD!W{*~qKVNxaUjw}tY0 zxh3#4J)0W=fIAHaX*brln$djaRvkFdZ&D!^Vy(&NNXPtcrYCw>3Ku4&YEui@MXRY} zDip0!R<=fJvz6jRqJ@?GP4;JWSG<sVW9-$2<yS%_*@4(|-F2jS+LXc@WFB*Vhm->d z55aSedM?TWqm)aKKv>sV(XJBZL?72AwZ3DNc-rErJvL|h^YC*Kcfc&GOc0zbMoHy? zO8SOM605%u9oCn@Yxy}?gzN?Jd{TbHB?QNOahh`yYY!;2?z+rk>nv1E_#GW8hnLO* zzNK~DFa^3?3gh3l%b<fq7k|I&u_VjW?LwGqVyQCVwk16xh;k}=FejZm<mFLsbB}c@ z5c>B~Soq-X8NPFIw!r`0Z931J3;P#lOr`Q*XJ$nRTP}l13U-42HDoXB1*39;PU%25 zi>{#&xG{88dY{${-Z*(;G6`Z1SD5i{M*(ei_)N~Df@V^*)=FemQZ!E~sVhRyl9No! z?WYS6=j`0pZF!}6z_3Aw6bbwFDT2}2eyp+zq+F@uc8+qM7`2a4bMp}~?Egm4DOKk+ zBUP&QEshsnsW7AUoQR?FGVTFuf^cYHoiHO8%f74Bhb`$Se?3}sj+?LcLkMM*1J<&V z?Gzycpm}lTEz>Zddu$3--3GS8=exq~`D*VL=0z-`6;w<k@<0u7wXP#6Nxnv)?BY9N z<GN-i?<DiXqS_{x^V?}jXboEgi+SRse?#&JThF_03Y~_Q>`seHs;9uY3Hg9A4}aqG zMCl%{w7Vtye&Dl<AfOdNrwgQsu5e9KohHU?OR4D``v?QP(uf&p200?($plQ`4&&Hs z-QDzY4*xDJVrejfGZdQI^deeZ(cBJb{HP;>hX86;?ZUL1w;SY37<SAcw`pZ+CUSzl z(1Au&d}l>1Jd(?KR1t!xs@lqux>O);^rx6I&w*rvoh_uHADT}sHk@fP6$?wy`X}XB z2Yd_8e`m}`v@@X35a;A*g-Gd>9wGGE*c@(=eIovA#XVK+nK|vXe&}GfbM`0Gi+Zve z@jS!94tK<ubjIgxfuo8x?0kYU^!!3Tc_5r*ZXOt)67tnI)c~$h7TiA^7*aW|(u4pH z1xP(|L|tM%h9dxZ)Zs)bMeyyiq?9LQEig=4E}LoIq-N_8!-yyr0XL8cju>`+?LzeX zyn$%`Jxm(PUBp;tn^BpGm|}r~b@T7Sjy{F*3E^5ErSgpjOokRY#0oH!XLw$;(9$ZN zEw#aQ8nyNT-$Gr(oQ#A2N_v?_VZou%+tH{-NBu}9lB!>RLHmM*l&`fb91xcL!hP$m z3$>|55y=s}8q`z54L9y?JDlTPh@5K?by1_>ihG8!N>A*wT)cW-&(dl9Q?1F0HIH3x z&Y6@0p~o1I9<G0c#Q3f}>2WM9k*_pM`?W7uS2I9{Zs^je=il^4$Z>mV62Pq%@<q|B zs*>um00_(G85F676!JXCq?=MCOrE?EDpFF`vwmZ<x7NY1!G6X|4Dt+=(K^BBJ76xn zirAoAlUe+|Ut;lD^vcsH;`K+~uiu6FN75ITlU%l`Z>g6>WqPdAA34`0W^q{N-jUe! z(G92@{W^5g?()rO|8F{);oie~PZS!DdI@1$Zk@24qwCI@jfo~s(^z4)I2Fw6^PXsa zi4++ZaoC>2rkvrre~i;_!j+eOAGic5pF>CIACR0sf|d6i^??<HL*aDJG%>OG$JyUw z?8ZEM=S}wlsXiN%e=Ik%4fm;y&eCr+v0X8V7dK=^FV?kCfDp(DFHx8!G)o#JWwto0 zJ|Y2hoeR(Z$bO%~1L~t@LZM37LH#2VHo3&vA%BBVx+2aot!!3^gYgd}QqiEkFNV84 z{f4>U=vr{2)}9%KZE2)$9sIBu!S%$ZvjXu3bg+JK!lgTuIcB4!=8M3wOn+Sc<$(}5 zkSPM0<u!?jmpYxysjii8x)+oVZB&s#J?plov>4>&YGJ?7hjtG-h(SkY%b78ZQ+4EQ z!d#3f;=ltn$cr7`{efwDo2eCjMZ>uzfb}Tz@pWqd{dlhO+s1FgHJA`q3swRIni<-2 z_nQN#f{TWzSpj`1+adnvB<zGnff(6a33#wtgc$k@jirK{S{|oN0dKd?-|x!B!NQAP zq$aJxyNbM<d9I?KS|p4U=(4a}^u}spT{$TI=&Kj3VkdB)f|FKu%&66m4+SQt3YR59 zHv@Ob(mi;|q|uu7KAt^kxZv>NzJuJnSGRjmKs025lMaz|zzceDX?P#d2aQvyL|FgS z$lufU#qeW4wSivIRzSqO@?*{)Igf+^slsdY_4tMoI#xNTM4ID6PX^@K1Bb>nQ}xQj z#pwr*EBaC?p^WyqzQy?YcKVnVaZ|pa^96_lYpLn?XX#S_bVc=;JVM|#^R6nHga@4! zw_uEk{EKhrEYW9vH&oa*w~C}V6F$UE@cK$YMZP4U5sW0ihy`9+fmii+Ly@$>hZ}Yu zu#)Kugr~CcFk{pc_2VG8y#Ap?z-912`g3}!_t4n}$t3)2e{l2P(sJD0TP*`LFcfnr z2|A|QNfjs&pQg=I*Mr^}ZhHmbs5*aOGQbCht|K{t!PhOvg}X9UiCZ@<z_3fck^Ar} ztFm`cMIWQV&PrnYFR&UbiV8(g@XDQn^&IPnwJzuTq(+faP`oulzLCleJ=8oa4y2~) zyINI!<*Lw;Dx@NKE_&s`EX;+|jLSK%MnJyCVF^fqzH?ac#vqF&I_#<#OVhX{w= zx@_<;d`}l#VDloP-uT-mSK(EY$GdfaDMf`QxbhBY5s@JZ`84c4*0V-rE7I+Jl7btE zxxtVXHuLr=1C!+o8f}ugj=M{l5o~%Kdeqdj&j6)3h*a0z2FB*WX7lqyu4;?%zIZcC zkkbx{5{2_v=f!r57u{?qsVf-G22+Iu(4^v5v3<&CK7>*!&?-pGD^G0akO43fg(H?< zD&{0fH@f<qi0!0OMMB-(Lumk(G*avjSZJ^iyEQ2t8#V(l%TnqDS3#zoz`CdhnyS`h zA%;`a5fi|A#;Y?^bvJop)d5BWxf+d{ne=m`Yus{K+TtA3wyI<1a|(r!s#D#rFFV2< zxpj&%XMZa6UNBN1w@DO5JZcGzA|+M1>VX9%6-<$O0NIf&gTgkoDC{g#SGsa1Zdt0O z>S+WM>XdK7>ME-!c0DP#$*w-~f^}9^1DU4Y(F1L}m>(tWmxf5_NC^Yg1v+|_h$27j zpp>gvJK%U18u?=6jI+u3!b$W|s~-Vr1iCznp-Dn|rKZT}mS%AH(s)&g#jB1UdKo~B zO@?bq@<E~d_9j~P48grz2PAD_Rmn3`M2FeAQ&<jGm3(?@w!FmoMn%=z9^oLPSKtDh z&_X)v{v$-m$Z15REl#^OBgyzu7NK=lEKqj!^sb`CMC87oaoE6NUDmGurmL&kbiZmE z$M}j}4Ed|-P0<V-OIN>N)u^!?e(mBD)W9O$(7Sl8-ZEi|Z&#(8!i_<9?R8aDlj~o% z?_}#%9EhJdsCRC#7!O!CR#iPQfj4dt=#CWtCgPJSZp`bHI6Z2GQd<+=<XhMaif^Ok zKy-{|X}HY7tv~95Avi_eQ$o5*!rM>AgTqZ<)gAh^{I{_P*%oYI5+B3H(9;+93x^jo z)!a7SwN-W%eGE=276&1FQg)(d8HEl~nJUL!siI|ON_~U^mNIGorj#Z1#gvAopb1Ef z_uFWx%ENq^(?jWTV`u4#&S|PzN3Y}qSK}a&fk-q0V_^+m{0M0bldY3=-W3lrnaWJ$ z=581`yBjAeQw-I2okDzoA$zKE3q!hy9$8&itaV<HY?Pbkb<Lg{G8D8C(#sQNq1UQu zP^>uL*gm#8{Uw6ZO14djR54kF&SfDgoKoIZak>C^z^O4O))TGMD;Tm9LR6Z>NFga- zI?wAqHGf`xH!%H7uTm$7X}FMBEGoH}^7vH(O!(wva72AijO!+v!>UGgdkb<+`Bs&x zox<~E5IbyfwExl-z{X!!OpX`&E2!AGzC7F<QY%lNgGvKTn;Ag}on5M*oZ%YVlnEq% zUFU|@Bt{T6B!<pa!P=C1r#PZhDwDD#8;?C&<d*N!NUS%SFFOkjS85b48mL*d9PHP5 zzP1G7W!k4%RTVllwuw`H$ia15S(1b{ZJ9};9??VZNbcncJl3W>T`SdG(&kZ}%E#Z2 zE}U4i^!cnBhLQ20_qGS|7xzQO@=y7jn>C&llnHAUd>!cNC7;5!NCGGiC;7O7<(*Z7 z46NZaR^h-4&eNma({kefRAcF^?M=X-ek>{1v<(TTOd<99AdN3s_ek8f`Y$G7moX~e zYa6eZ669q}cp{>dCf|qKLbs7?CS+!&xrG0MYti{?oYXEmBD&ZTM`}u(YMeW<L7k~& zQXw7lGVK2FV#qjW86ob0vVa$Z4rkKnL{XO_;yx*Dpo-xmEPyxMAqJbCoTdl=d}fjd z2xsWrU^7@pfs?~+^n|88klWF?UEz=CU3Xt^j&8bJipt5E^=N-;dbHK+jEXiz&g&gj zvHTn2r6=8gm*OKZ#eowHZAr~d#Ng9p(Rd~o#3i!Q7vVl@yV$bp=9tG#^NQ|q2gL8d z!VTIukg_9xAJsmTAM8)e!tk7nAs9E$y;}}0LwUm1|E~H|C&6$-5}7nEZX=;g>|Rxj zt-g#U1K2{!-FrC8lt)oLYI#_EPLD&b@NE#@Om2b!U<@x&C<TrNcF>=^_S6163|n{J zhht4oHocYat~I3nJBXZpSo2ra2(*%I%pRmMYcamJZ9YYfqpA0?*wYWkbRInT{vUe9 z|8(*>!_cY4|G-@QbpO+x_1~Smy`iI_?Y~z3FP62_Cfh$K7budvoC@(`;`Yfx@dp95 z>t%&?XM=Z7^yR)HiHU<u0uAJbTGrR=Ca3@s0O7h5dJH~Medn6)Ro0eAvpU-Q4v*A} z#e+Ztt9GfRdDxY2tMq^B_)hp@lc?=i_p(M{>bHM&{1QGq-yQnT;lZZvj|cV2%O2f1 zr(WEZ$48hul6<}oVNls1<okj_zy4QT?==2HUbj`qm!TbaYd3Gt*ss^uKwA__I}AlY zypTOul%M<8>Y+VI&od~dhdKnmWTOk-HZ7(D8E*qW2AtdeEFfpJM*OFrA`@S-zkRdb z5F)9$Z(`!EG(XHj^nA9=p4kA%k_{#*$>d_^mOkQJ#~3B4Xoo?ZuN;4(i&kQvyoB6f zxq$}@Jtiq4u`kk12`7?9KPK&pd##KR!Axp$A6ZpkF|_af<2vel1{uq%v7_S5Aq7F1 zqCiq0Q3rhI;k1#YFq6JhwDHlt(t|*(GQm|Ng)AQuR==klo`qf?>$*6UBerCt{6aPd zpYV(m&;yVT{F-jknmKHxby^Q16N%!$Io%=*h!&72!aZZ8F;iJF%~@gerv#Ay`1ANx z+G7<aW}Xk(>fyPwH{0hIqJMv~VG5suAeEMB{(HQ?MtfczYh5ggFL$P#FJSWh{`mR$ z6*H8*HxoB^M;FQHsWKB8`r-MNiK7cwZemo``SAO3g7g@vXiFO$yLCE^{~8r2ZD{hl zqD~vcFD6_wz{){9%{Mqy81~#5AjV_=VZ$>tJe^z;HytqmyVjRPA*iI%3VECdNXx*& zO9GLnQ>Bk%B8Xky7Xt_de|wzZeHzSOz=%T=z{jXV=82DEIvPx0`@~2v%*($Na&u?E zaFtXwS-<J={o!&-aevB4D?oxTJc`Ez_^Vhv1^z<O3dm0f7+T^L#iQ%+V`c8ZopVW= zomTq>FM(bxDFkeXRt-H+DvH=IMxmF^N9J%*^kUZb{%({=27?2`{(RUL^mI85Z76-F zY#=^{=YK=kS;s5|AeML%J#@Z}%b=$lsF?~_Rl6c8-arRR>Uhiod&5pM{T36e;i8GP z1Z`>1?IEKHutT;2G&i&b>zI1a5BeDN3FXR^qpQ=$YDym*LQiEfKF0(+w~Rv&g@t0* z_hKMVP)m)w8kHz2<x4ap*!x-#w4a3h(OpdX7vWtrYy?!5;KxSTnJf1+ZLgRU<OT7Z zim)k4+F|N;*O~tAsl$h;$KNW}s3Q>hX2+GwUBN)P=wfJ#dqVD=_g^>3;XHfk(q~3b zl?3R*pye#bmxBkmlJCUJm*LU)2&n@zJp5$w1zGbly!`xR5*iPl11I2tK{XRA$4Lc5 z#SVaLn8N+p#=P(n<d0@CQiU39Cuia5?7?zqa(8h`9M18Z>p=D3$&`b01x+My%u^5y zRS)@fa!Dls<V+s!lW%7sPJwUZnZ1;b1dbByPKU)4mZ|4;I1VC=$24@C&F&To6#kdl zeiQNC>yE|!H-KZCNovh2Zh!pCdF}d{TjU#HDGqh%E(hdu7>uo^5AKC@tpfI{4#?}Z z8{~5vj7@+cq_G{=f+E0bB$ch)2U7JBbv+-BL}hv<kF6XZ;o{Bc4NlMo;1<CEus{Yu zbIsr<g251K-QO|4Zu650j=UJU+_sR!DEAbFMehl6$j#3=l}yF6k|k_JNCJQ`qNH7# z50GL+lLd|f)Q6#VO8>ErsxhI7z>W!(5ds#@u5fM?9z>c28IgILX`G;vW4lnghnP{8 zV`Ta#Y%_N+-f#IXFN!0zJNsr=pZdeSYSoGGxyJj%dz5|~NQvL6!w;t8Lr*q&q1=e$ zqQ%ab4L<cuM4~B%Okp<`U<{U0Wp?R2S10$j$M1JAu2b09TveIX%b*(!1Fys@t<026 zMQaPjZW93Gtnzu^c2tGjvu5sduSHx8XO4(fDN=|f8c{{iFy<a9rlJi=-W+(LHV%6E z<8Ecb6tpEnHUxo5lh}E~3NoJL0+inUt)rs;H{i$F+gg>}S#XxP1=Jn~_UuzIt}D>p zidnmuI%!}GX3GxOOTY4MI=QlK2Ly5~4o{6pgW3ZqVH7$<8b!3IGelIlExUn9Uc$|D zr%m4Hwgb9CW?WUSc1H2*R}~NxFWGqvuZ5!_)K)c?DT-3mSkzRR0)|Q<MAxB3!7-+8 z!x7~Zv8B;J1WR835XZw5OkB3R)IM<OO%?no_7h2f#ubLaABi-5akGnCjSu61dsC37 z=9b#wTH^f!Xhk_-(AKM6f%|x>kP;oMwL`@1o1r=c!OP>KBVs2U&klu?3MJkcpQoRI zh&G72g)J~!Xj!vPs{TB1HCd-Pbvo!-29!es4-umwh(HW{9!1ZJY3PXHfaL_-Qv0on z8zS)D!d770ervNONO(GZxUQbu*!xv>zbC-tBa{QDWOiKB5gMtMB_FS-Nb!o25BOTl z{#Nw=u=P$+qCiWsVA-~9ow9A)wr$(C%~Q5*+qP}jnYz7ZUeD{*zxzLTL}o@t2+An# zqVdQezyyI@h|WuGPa6z(K0yP;s7m|Hon;G3weEdOt1C$+`M037>3Gzg;<~o7B(uM? zEEta=rY<P@X}zL#8{ylmPeN^OEJXV>b`?h!vcx43QgyO5X@>yr96lBYPOXk$vR0@y zzwMps2J0qncdFpktW?nHFNw#k^Y6TzSoJxB1dQbJ!z<fRSbkcjxT{1^G??|C=tF?& zQcpiLj6V7Ufmm#NwyJwKhcta%C^8&fGz!r<v;>}v!N*e9s+0FK$|W_?7)zOErnU4( zNy{|D!hWj4KW-Y>DJvi}&J82l&?%=pKFpl!W}xxg?x3{(B^+#pJ$If~O<ZqW2a~w& zW5YVu;+3|qvMmG@1hf2A9P<ws@g&&p&BIxnfBBs_DD|L$Y_^4J<O;1dnxJMktLEa4 zxd1oUz|5uUDVfKwSVs_(MZ9LR{{U4B5ZfUryzY5gu<3D|Xe9~6rJ0<eiE8dFA^!Eq z0vDi8ZwQ$)l#9?XU9RjL=>6gzP)y~Y>-0e0aXdj|-xl5skOuK_L|sT8(Eo+OM*tH7 z)ds5D+yc*Rt&KCvvi@c5<cxG0EAXR9$Ncw+oK5rmgl&CW>Ow9u48zvPeKt4bb38?{ zX2-zy7NPxA)#1zD-j2CgHQcw~iJ2ya`7R^Ivhua!lBs{l1sZmI*}rVUrQK0N{QXN- zd1K~qG==;jOOmrlGkk%hqxYm3(Lp)py*L59VP@`vIL0^;!wy;NMkj2w1^3__<(*B| zk{AV<$`co2_Z_-rkdJHY#TBxyxr$ct$7vZ&)Su1FXH`({TNGMSiU5a%MZ<Fe3ksfs z4&=b?RdJuQ1>m+oocexr+5FGgx{wEIsAYosd*Ez-t%QWOGc?Ef>`5^~nM2EH;tyJ$ z7T)C`_*X-2+<z;z)O+apyp=%Mhn}@lmA=i8sT;J9;%a;3prVkZXP48!_4mUO6?9TX zctaKfdUL{Rmt4j`IhhnV#?(5aX*6Z<h^oH^{Pe=O1?JFNUXInoDMDD)uFab%&0?!j z-n7K4E2gc?Q5RJ(E!|Vrx%o~D?`pC=0PHh)GIKrpK0#e+$=~<~JiB)mRqEuxZwUcA z8{iX;SM#&T6e751TF46cj3E}*avull)zOiTvUeBHs^D7-Ge^G4@(<KH_{ScZhrs@k z%xX}7zAM~qa;1y#OZMIS>zuR*BZ*eVIb;r4j>3}bykkH)rLaSsTgAVsx{S#5;?0Xw zy>1S2Yjp`4GEVb3Pk@6Y;k_ek%>;R)s`41ICBQelneRyN00=jt8#jpO(F(H<CpiM$ z<)0P{DAtz=gQ0#@!`RB;P?E18(mcsHGJD_@A^uF?cs=K9=4D5Qy-lxWqB|TY^iu2_ z%Of#~YD-LZl9CAAzhO`5AMY0ZJ9#Kc6+@Knr-qDsA~LnbH8I*iFzAvM^}Iu9XN&zo z+K$kdgM}7^QX{q=vYi_y$G1Ek>aUqr_kIGTm3<G#+I6P~?#0OY^OQw43t+gjfLJkz zSb-gp2DYJfZwa<bWiE+jRr8u3{K9D4m#g^}A#%?fJNjr!%>{+9Cx!u4bqkmEh}gb@ zk#rM(ND;;@qK1iVrvk~~u8QiUbX1(d$3s_?&YIIq)-_qqeqyx3x|MU1&1FBw?k3}u z&CWj{{gyEv+#X2q5S;Lx@URYyM-@sn-vaT1q6mO0YOr7uQyn@`=(B*rij&3rj^UM= z3?eW$;Ata501_Lq+*l$9IGwH$hdx}&S?H?sN%Ktfq5#Us#9S_c6kxxNlOXj5E&f$P z^+rkW*U*$8a@}^}w(wQ#9&D)66D!h8Pw?Wn=@RDasxdCSS5C47`_fLyfN#Ax>JA&0 z@z^?E9D><RAUv-RNtrp4e%{2U?jP7wF?^%Cu*Pnh%EbXyuSQ(h!yRN}K3Oh`s^BdY zs?Hl9N~FMtA=6f>!t~d^M3Yb^jx|8jw9>$iY4^g2=}<G1_M|Fh*wM3jIKQNMy-I`U zd)mU=3ra0UcyK+nyV(rFvxLOT9flQk5<!$XtzRNHWJYR>><=;%26nv)^owY8d#$C3 zl>RWiJ8apEPxXOzT{msVdw-rua@L8$v<6|ou!3W6e>w~D_MRn+y}tz)q{$ROH9x~s z^1Uk3nen~nQ5_OcqZ0B*o!=%?MKP@%<{Hh<|A<><#tB)h`AtRc_)SH|`akAd|J~Uc z+1WbTS)2T)w^PxH+h9lWnXPT(dIV@9gi)$iM!g0W7K&nqropce-Bej2fm3H;b;K!E zems0#gTybnw!~jSiuJjDzUO$|IC)8v)kvR_{0pb%wSjvjTDh0HQM-|RA^rE6i^^ul z_mZZcmb<3AYp$Hs{OsOkX4Pg_SFH!GYRQs}_JU-WRr11RxdFZ7lQI1KxC^TLvtzft zsFzC&-lt;+?xgrI=O^oJJY|{C6INEBq|gxTv~1`f622Hl2&%MA_0XuN8@*w7{Zh1+ zv)}4<%Y1i1KwY_k9>+7d3xR2vHk7PUDf72N1I;qmB<wIfm6ixCYhixQywzY!uz@Xm znc(S52Ifvt5FMpSB+RU^L5zAzYEs>h^2+=OptVBL*PeCB1b{7DcHMXjLC)v+=Y8Ui z(=cojGp(9p@e_q&4b)94)74G%aHv@m=NqcfsDZ9iegPPLqhKYT17L3f4;$!-^DV-K zjpbB)Qvq3HY&+qZh&Hq{JV^%6pBUe&9~wsD0`42pTLN=nVR3IX#f3;Ejk~Vof*^i+ z9~@d<=~U>8xV$qXKi11QbU7Z7LyE!4*RDXMO<cx2L}Sd-E5Ie(fm`^-H{jGK@S@TA zgK<cVShT~i_w3Ll%x8;@JX+EFhkCxEb4S*kDSV<r4!0(6IKNzj3BZ=+F~bpB<c4tV zFXTu~|I8`#!55rinfA3HjKP>q+#jR;VpXeJ#Qsy77xAOwCfM_Jh-}o#-aqA9zBQKO z#3`bL-y0$*N_nJ6e68W&Bl1Um_>$E!;=nrU!Jo;`5jQuT+nuhj(>iR$$6ffKY;0`( z?{j6EsG5#yD$3MO!j?J7w&@0xvOz|)$<(eIdj;jD9`V@S&s9zaEwT0?*VB}JY6_ND zGj1U!=Vof^HZ;SH!_JZYCdL*zD@tU?Pzl47C}6gM1QO~IN``k0U!pNlTwC^Zl-=L6 zqS_G_U#K7gR2mBMHXi70=tK2RyZ=PGfj<PmVn5#mMx3~f1tGIYrUNIri=W!uDi55; zCz}xiL6Z(D`C7;W-NpN?W4yv9Bd}csP)37tGL-Gqo?u@r4k(02jc|kr8dOW#);l64 zo!(@PYkd$W8-`RUI8v)Tsw`3DMjpoxh17?kQZ8s0RyfU$%qy501}$y<5@Xv!U)h$Z zdA0}qQoM0?Rqa++{vq#)Of((*C1_P8Na%LGMA0zgtpAD%d5TmyYKdly^;6%mra>Qk z*&J~xrF%S=vwuXYK>hmvSxx<CeuGMOX#DtVv3Cpu0PuSR`TvGR{CAZ*dDt2W{eKF} z|J1swjocwS!cVRq15mZOom4^gjWf`FfwFTe6128flb|N$DJNXB_;v0z0MGs5Z9Q^g zQ<J$|M|eww*-3_(?jSGjkE6IYxgt-t;?2S!-<L!a{&iBXu3mYEq4wKIExIo+%<8G2 zYp{}K>j5k7@Fn_iiH^aG<mexCV9)C6yKBGivY*1<*d3B5qea}<!y*EhUI+Iz_UCXy zFnj?-k$#u~e22FofjIkBO8tpNqPGCunrQEIE=$-AXUDD29J=De&~M_uehL?R7AdBR zb1X`kKT{e5&kK-3z&KQD<}#-X3kzr9gJ{8<OArF8Wj7g^4x-dK$Yznz;>9kaGmhlq zoQ6~!3nRcZ^105(vyLeMThpNZ;{%DZgM(?8TpvWq^fX1A-l-C@YKhP$A#7%MH}Kcm zB+Oc%Q3a>;lpJ&N!08<2%b1Xm?FHlpG`Z(P#L2djQ*ahSv?tt7LgDD1Hgh@(Bic5< zS6Du{#)68VTkX0;`5Xv{2aQvVnUE9J;*V8_g!$6DVvDtGZb}z=yNj<s?pwXNJ9z@@ z(=5dY5-9SH^};8}g6g4^tw1huch`>GZ%|1;!)KPv-LHT!VvCoP<H4b9Mi+}Ve%!dQ zH#Hwd9o^WwJJNKW!pQp;AviZP^d$gV=Ee+&vEx&&-9J2$mIAa=<}<k<k&_|bKn$S< zS~b26_8F@1grXFy8r;Mgi3>GCv!aD+*}i&;cDicKLd3(JxF6Nvw551VB)$jv@X-a* z0en+UthgO>D*`;lRdUYW3zxX~FTOlCE@!q2x1wHNUh^nDSCS4zDKj=kVD2MT&!naV zBdJnNKuozp`K@J58g<sStl@zIX`*l(iV|ej^2T`Hx`osyj>Rp~YS)#1To1s4@l<cl z3CiMwG>cz|S<wsH4*2c>;6;TQg5_0qh{Am_+MHTVxPJwMJshWaH^Sc$s@}NJBf)oj zy0d8q<YILDCLm7SO6}NfaCAIl{vtTiXS;X|H!GJP#zu}=1oBrdE>b*5Q6W;QrYSEB zJ4{B>Tq9IGW1Nb*`g{9Ur<mu7+Hqk<1JKaB<vJ2OxKtE3#J=-Shzedw^_xU8l<V(k zyLbKN6v?`8dO7|x`*%`_GpraXd@54M5;ab>6AbR4&Cyf$eRpn8ld@k2=K;Ps-UOi9 zN<xd@Ac}$l7W2&dFN9H31p0vH3qk&2W1B$OVXZxRBArxXdLvC1!_S)LAyMKB9oLgq zwjr>$xgK@*XusuGyr9xf&F1hZE+fJc)^xxJYU(sh^TzeFCMH?^Fr8i-L{^uJJ*dhR z-tK-SfbSf|_JaO`CU_7dmNdZ0O%hMO9JY!N{toACPUfY`Eicph@523~MfvA2zoki_ zlf(XwM4H1P<_n}T(@ka&qSqs^D|A1j#n6hhLbja6w<0PFMh}ZxpzCg}I<>IP%TU9E z+3U3NyiQQ-G7PpNW^6@*WlUM8t-gR2P09Va_nAKB)gAmpr_&^lZx)fm>S~;=iUaLI znqU2$)|C&Tlnq#`%OFUwFi)jaBk=t`%i3#kpzC5?ho?;;rhJ@DZNf86b3YT(m+$)4 z^?iW1s?6#x^>2I_mjBlz{{epRNWy5-Qld_P#abdm*WwBqk3kkjlaH61Dz~*bG-|Ni zBuw)P<v;jIbozgkY17TEo%_7`kN;!f4R}*~5c^AulzwRu(f{&c+FKhqo7y?rIGH%Q zS{VI@9_1)++HSHV_^hf;k-^uuHdvRb=bO)guZL>^mmhuvGMl4oYGR3O%@y-2%IX{) zaupv@$SCGh045Nbo!n*b$B+6wQx|<=(|uC>F4$}ejO}5%d%fZ-q9?Oj<=4AjN2)<a zjUBFk@bEMRV?42P?p0=6)tam2D(9|Abk4~6*u*p2IIr-)c14Za?27)n6@6~N{aoVH z+&!PWHf29`&&NgNacj7Q>jo*wSN_dNxVJj!9r^_P4q=gQ)QrNfbgX@sF(_cV893Kx zzfyR`65T4z^brdeiy@wVY2SljB184AP*1H`C=6wwmDKX8hO*6Hx)5!oowKV!?Eky9 z!w_Rur-oWA9XJw=UHM+x0I>y>q@ia4URT02@oHP0h#9a66u`QUCEuRcl~=vbBe^8q z*R=tWI{+%DfaSa&?dld)+6Tkxh0oxClL`x-P61?^O6>tQHeO>8wlRkzi!0bD6NDMK zFlVsBu*&Z_UMuDNN|0_NRFt;dO2o9caEMkxA^=L5IK)K<VvRr*<UuM3E-+)yqT|!1 zT}zOwGpN#~KGeAUjLD%ynS|=5E_81rkumFUY(aLN`<E*??lkHi94bO=G3xwc12SD& zt?}^~i7X8|+yL*7>f-$ek#3)Nce)<kuRNQSQ<FEWcZU85q(vop7>4$6KzQa~CfqUt zOM*bZt9V!z(Jmr`C|k|ezmtAQQoAluN83hsFmCX2YY4YYrE2x(FL51ruL?qG6ReQC z+4!#XF4W|=5>mf`^t<dkazRSm0dY*J8(tHJzCGt(DS2ou_#nc{Bs)}WY;0gNA*O7T z!1)dw5=pgc;7N<Jwx*N*lRb~OcFi)HVy11O^5%luNW;?#Zsr2oNYt{otW#6(xfGv3 zJV{j{(cF`LS5T6e+S5=*@ZF`J?1^%guxF=mcM(k97xpg`N@utmS~%~4-AdZ0=)9LZ z!aMku3+3n**LKVz!3`pUC**PO$)b#y4vk}Tv5`c~hWyz^CrpNwk<a?a&^#Z-0LLr2 zkWIpOHQzum5@9r3QX%aq=CXb#FwP3psE5Guy27iY&F0Bi?zhu-2ea=Kw?iJiSCP-P zMzH)WDKaap*{;^lo!@@P>ViGBz07fx8og<D?yX_zAw{&Ac<zj^K~&bnFB)fZDo;88 zMWj1#@(*KRk6f>VC_0}rh!uYJ0h1$8LgQ9>$2AE5zYQS%Lw~3sh}>3x=@0qu3hTeK zvi@)SBW-79X5#ptLRPi;Pgd4{xQ`_t^VY(XiA&ky%SV7?UDQ&MPJU}elj00JavhfS zjDxw;MO<$^vN%NYbq*=P{S^1FrCI$nL-vm|l(vZA46lIc!J^)EwA&SK5N>U49VQ{{ zN2#9Gm;J>^*nq2O<J`j_T6V}L@Bm{CgjdL8S{7ZGs=||v-*wqXVDHQd+S`tHZ0R7A znR9P}m&KH(@Mu3Hg*wV_?RuT@7CZubTB6e*TMP75rnaLswgdKV22MUk>FtSP)U5MC z<YX;`?L4p}LJ0j<?zH;Q@<M(nos6WCyUYnuNQo-bG#Y<gy=buV@JWV6SD>~@Uj|4_ zf_Mzt;uHY{u(YU|q?SKu3i-^nHW@Jxn-hqpaYA6^_T=e4u(xPLCaHa%408Xzs(mu$ zhP`Oz=D2e#qO=qGd@D!vBu;)UL^@`{5o$g`XDI4L^3MJOQSxMRx{W-Rx2g3BR`{Ry zW{PbbB-4sHeZJ2~V-P{kt#(bM0uDl?VY37hdXX{3=*D6j!ZFMqSTemEJhC}V-htK` z^Ce7KyxOt#DO3%I5YS|G8i{v^@Kn=<qvQ^ew<5L+--7s=={;9^k0y|hpz%63JfVNK zAh>O}(PTk4gEnR$ukb~moeqBhFp6X*E#6uN5Rlgd6Cx3@$P$_Be&Upuk`<+h(i>3~ z9XKLUNk_~ZX&>Ft=oB1J*b|*f4p74}iWzO(R{}kU|86I4+*MTAV2I;2?VmzF7(P%E z?vI9kK^FZn9JnQyJZIhdyA<D<R0VAB>*3(w>v@0wRR{}zD7%M?i|bL7&uvgHWll;Y zO*l=OXGN-#3Ur7wE~-Il36=~{6srcEc4#^XlFOElc1qTKEwL>p%*;eW+RRgK!bq!x zPIN!q7fFf<)J)9C`^QHo3bqQVBxAvlx&k1J%obP%c{opTgGrP`g-%P?dL)>}T;Y_$ zCS2megHBJ@Ll(Gae9f_n)%%>cM$QutH54Gw5j<FM1j-lqpHb)Yc%xW6@K2^e3!wcU zJTl4^?w_6KyDmY;&b{i)X?gUYUigvi&i%U8oZxOguR%!dK?$duA*UL|5oanWN@<J_ zN-_s*)~gNG{CH~2-(cZNT-EevCpC$Uc1*S!?WZXcvCXln)Z|u&ygG8{lxpUpi`Z5X z?V`0pCbc4>kgC78JKW+%2{pvuSV6Q`Sdd&a+XP1p<4P*Yqu6;B0AWN_t|83}(Onhj zwGoK%wE7Cl8{ekRm5|!ZeJ%=Kexo#s*c1tyLQhy9(G9hh+L>EaEST1IH^O#KE7EfT zD_;9&a4!Fflgy13;IRKC<!FcF;+|uN1(Hc6QXa~Y&UbV_mj(xH=k9;x!@N7=Cp-Nq zgX33lGJh1>CgZFeS2cO(OWsTh(EO+#<V7SiZ<+Yy)nTSvf}*x)8Nf#1((Kl0C%fu7 zxDIgW#@aKqc=%R^bF<psK<Q}%f9bQvHFw5N2H*IZ>uBtjam|VPe9GB0l1{;`vdfRG z?bNPmWzN`Fg<qfwQ957dF8w!XNXiARW+vvx@oKTJs`cu6DTcH!bsgA;j+f~jF^s(3 zc)ZjEskg~fjiuQQE+wASqH}OF;o#<sT$yZ_fw{YTs54sYW)>mmXPY}99R>W?>(~yL z;OT$x8~qMK*`!}?WAb}whw;Dg8z(md$Nwz!x7BUzHdzsVZuA_?`G#z9NpI>5?Dyei z5!?VbitBJuM6k>wg@?6G#)->GHa7nCa3vy9YEW|OV}xRc>y33DZad9xD|o<#{edH- zL(1KiDNsJ&pKW4v=XHmB`gj1%R15#(Ju0{1?eSOd&-4yr&44*Z>>h=6FF}*1=ruGB zUvBmQdRfTrlZ4+5tS?W6+n&-ZyEa_hQ|S-PbKDG-#u9@(2pQBNrmZj3v)<ohfZmuG z%udTdK3dn5JvVI7!9~O_&fG5$a_wQFkD&gqp|L79?EzU7H=+$7Ul~v%f+%Gk;lS?D z3JStlM+BOEMMz&QDllz<WOA_(0$?o=-fHveDP%H!8w?7v7Nkh!f9_5Wpmypr!pZ%g z53Gj_UB?WQq{Pn<a%Cdz29R5-nnnV=RaNkH6m#~)?g_nMBMy3fJjh6XgVYWBarLaD z@(>uJk=*F=SK@ZTH>&X>6Xjsv^PL39d+jZql&%<aV6=we@Z6JosREQ5nx;mK0RwmY z-rtkQ%UCDq`1^z2?b&)&d_AHD&6M_O+e}80c5awrlNhPtjw%J0#{1jr4^QaI8F|^g zJbHe`0BEO|QH{$`XlYXEgP-q?KE9sMu06r8YLl;Nm5l)U!(+5D`->1lks~djh3WLD z_tIb_{}7X?=9_5(WSnQ|+ZhgD&(woWnksvk95fPk&oLC%3f{2Xp*#vk?g-c&MNmH} zNnO&G8M03u=tJ?zDNv8|m_U3><ne51+#_GmH59@bvQZQZ+Cr`2?7u7-Ie4?b?71-q zmo4#N6cw!R>HCQ+L4#chQA*R%z)aa>nS8P3L6zTPKpQ3w7eCah>mSg;g9Nfg6b0MD z4OPM|IWgo($!J9C9E+teD+`P@I71ch=AGqVvHF!MA6l9TBbdq5AVyXwxV>Ja{pcpO z4Y5eB<?*m&F#FmUU<|cVsgWcnxyb;Et`H`{iz^sKlZm(zzjX^SMwbYIT@g>{jWC5Z z0i~Emzf8pMgLfZ`qZ>*!pT`3t?gvMZR@;IkM#7!Yj9jAcy``7TG>3r36S&hY(1x*3 z8IKDoZdo^0Dq@&{(2p5Jns?m!0-$`c?{UU6J45yN26BZyH@4u=rDF_%2@{f`BWxtL zQb6EsFv{@V2QKP@z%Ix_491*l2IfrUV+mO@a+fLbW4oGGG748MWB?>bC;W|t=65>U zBrOmc05%%zLo=D-Gn*+*Y$|m!4Uyxe6=KiGEs6x(^S{)ihTOHRW-vJC(yboWc=|-8 z%+_krZb!^$2!^G>t$-GA>t{lJmk)%&r(xS~<pFN#>orV*%Q;dY_-3Fb071G5luQHZ zWl5*@W@~dy=!ATBV9>-3Pv#a|K*@>BL2~kX#;vwG1x&Er_oy~dEM<^6iI*5G3b_Ts zCRLBNfet<7;JjU|v#awrc%#CNCT8)BO3gOz^m7%ADy`pfqqVOhJC=02T#zA5k{b-r zZ0wM&nH@MwTJs|i#&?2J20dsc)0|7U9ds2~8gd&CtKz4C*e@WXJY<%Uzrj|@NJ<%8 zy)RLlgfWb6S9J<xef$?KqIR0PV|?_&@Je^{v(AavT+-`ehL|dzxj)*@uDuBYQgg&= z@d<khDqN?$JL4EToi}+3VC{`&VgRk;O-Ir<ieZrPD%V948p#oOy^I;QU$*k+)sc>> z;SSY#SOFFj7@%=nFTa1R%Vdn!wd;ykS1&77m(tJi32n))o3S@zKwSQGJS>Nvh@+SL z(7y`dBzB-OPUQy^TC!sk<A|Yx<(dow3s{aSR#vmxXIhBvj#05HMxQZN$^#2^Y36#R zXY+_MPvSl$*Vv%0gu~QRjK=sCyxg{R(p#)5BDjMy%PMSIM-&i`Dz)9LjbyI1%0;mq z*1Qy}c`cOjoSP>_J-^ll$$EHLKgZvlac*SAk}zM(L*5dGcIfPn%q-2aO(0)dzAU-^ z1egk*5`Kt6-Hx)enXIuhL{Enlq2|@f=ECUBm8#9Vp#NLFXy=_fzGgIg$%L&|By2H~ zfzpa(g`|~t32<)~5}hi!Z532Qa|KK^^FV4VCz?(+uL;V{#m;r(;5{MH1*D;1ACevk z%-T23lHCrzD<wZSSgpT-^yQf@(#`KR`*M9aLE6pvYa=DR<U@y%^v_K&9h>FFn!DP! zq8YRL8Ae7MdWtsNbYRYp?SlW=xgSw?4LbbKN8Vn1j5*jU+fGbCt{kGlrc&xltDos& z!O^aT!fGh%Ga%a?5^wVn7S`(%!}{u&=0++G(<eQzu<RBC3lrG1>Eg{GIO27@=*Y%Y zQ?HK^BSATi&3T>=QNW2VI?iQOX)`PHwG!#ed*)atRyM$&0O@eSU{})fzz#Q+-Y1I9 z6U(fkkANF}c=vxU`W4}LubE|@sN=KXJJIe?ikn1J;u*Z#wc_weB8ID@Y}a!*pwBNy zrgDqXRhMduS-01guni|s0;|0vFA1_?3t~KGon&m1+f9n=O5QPFlNp;Uabdu<KTk0^ zEz^Y_vNe<T7bLGg&GZ);5H?8Hzc&O4Xhgd<;(SHTS65Cgqv@~03-ugt(EoR9BP81p zzzGHbpp5_kfc?J!xwD;-k%5u<e=Ts-{?Aai6@pYp5~@m8GvH0$vu-j1I2P@i5bbzt z$f7Z8gJZP7Iqvh8&4^28cg?7zQ5bo1HhOfH8!xOnk5i?bb5Pp3?RTqII;!ZdRrl$N zZkS<g=nRn}>$bZX-WtNRl$&R;LuCCHC6~Fi&SEn<<6@7ZDX<hM+qCt2XS{NS`I0N^ zdAFs$|A*(i_C0`)>lwydSLZkTGB$&GcFb8-bi8OC_`2_AKr}QdkN6QC6K79rv%{gt z^^r$oN|_bQ3c{0?eQnbZoIE2I^>d`a>wtbOtHfhuKM@kLSB)mZq@X<z4-U#kA;>{h zu;56%9&+zD!Z}Q_)N=xbFEFEuz!V5Yu0gTVTHOLJ1B@&&R{2Oj@La--Sv3MA=aK<j z+gLGBTIO`{nAUqQkUDkHg=MM{gRUVxDlv&;aM_{`=Mf~7$;d&J;YkO^o@}0BF#|=c zk11R2ZcHV@hn)c47W1?bR#BjjS)>NwHL49Qlq)Fve1v(c>(ev|(s<wvcM^z=Sv0O~ z*dq0m{zyKByZV8(ouA&D6W_b51DF5x0gl(j&bA{hsFN6^DAFO7&+(Ef3uVk3sEu|w zIM?9pXuowaYe$UvJU3e}8~(-|*z7cDa?$rUmfSWUdUZRi-{bbB&<l9Am2Fk+dl4aj zmXc<0e-cJ0a)t~^L%PjWLpL<Icd$4WLo>H8oySqycB)YfCVJn1+O$?$n{IgQ3b7wH zN-VyFpxAa$+2k)O?W&UGiHz!|J>5YaEZ;40WJE0o((Y=w7`~ZC<j<@lr3$vJaXF$b z#U;=c?$zz>^-b^Qrrn@TFSe)MPS<^h!_?#g4M*EWf%9QKseps1NwJW^K2xw0tcePW z;yF?%l3IT@)ht$iM+{0;_jB~P5RErwJ$?JDcC6@G<;}!`R7!RqMVgSk(bLWPKEnR< zT?h`Wv3KSpB%ZK8t?|{L6Max7!=^r~3u}K*g(0fsv;j+Jn4f|DR|~4y>9_8<Ql5>V ze|sJ%bh-YAoHzDE&mox5h2nLPafPX;9u70{{TuY=xSq;+;Xs}%Ad{iH2>togq?Y^a zE7XWez8bmb8TB&7ceI!9Q#j)!LgyCcjIje%YW4EDh6z)`r9~7J9=R<7<74c+J;^|E z?U{7WI`K;oI2+{@(~i1G@bHfo%4YIjnspo2?M~K6>}>wHcU*Qt3;w&Bt{mSAX^Xe* z&bIeB1r_p$o;VNWD8}y#f=dV-272}Km7wXZf>Ykxha5q$hm@=LYxB63?gp^ZFfdEe z53v>ff(#>;XH>-wfsp&6z{zm&%B5wPX!)9KOEmEA7nn7&ZSOEQ2vLm$ly<k>{{|NT zH&KRggs3?i-!XEm73o46MxOVnasUN{=n@krRQJ$qZ1NXsM1BJir`dY~S1em>b(x~o z!suDE5Lr;0w5s4}AZb#p&d@V)eEScPV@kd}t=;nMzcddnLY@cM(@1mAN;G~@9t8)> zJ?2Ux*%<w(R@h7?#lk_g_3t6RluF{i&oRnJzV@plR|B}-nVoxecyVmge*A90-YtN2 zI{|ApH0LT8l?IiI7GZ7)O0WxB6w)d!uNS9B`0vW2ph~QOw3JCsoZr>Eh}w^a%wvZ% zT~nX1XuKNB&ORUhZa4Smef%Mv*(wQ`mr#_6WbFHHNeBhG4L%G~g9d9iQmM&NZ>uwW zM{JgN5*!nz0?sp+#R{do^!1vV@3<d{bk{q?|G~F-nQDbqnN3u#%l0Fdc8_7qT4H|4 z9!*W7HuR7|u(`^DCuSWIzqqtJX+^W;Nkc2M<vyey;AMHFuvr2KHRy$QoLSHjIE;F5 z6+5%zi=3*)6Zs+ZfI0oH>v>-tzhhENW1_#srY9z?959&r1cRa7BM6;#5w0>5fo1r8 zf8#R%ZpeY9Fy)oQnQ;BFIMa6~hMikjs^PyE1Qn*&8F+e^8~<qbbBUl*!SrqQE@Gx7 z9YtM3PkMy*b8)PDp*ae%rFU+np>*_j3FK?YKIqcx<7-mAWH+?Q{M&%Ac5-WgYl0L) zq1Y_2LBnfpe+IRUW8v5iX}-`B-o&vD(mbv;)Ujm?w28B#<#?{Mlk|HLqm~jUy7NCI z1LK(iwcNk6aqnN)!Tet!$Hd*)-p=W_d5lrkvBTm(@yXM3VD$iK83ZV&s>XUY;4cuF zNTk8PXs}_iGUeXe?iXzdGcNpk)AfRwE3UQ-;OW6X-EpeDe%$3Ona?SS$E9;yQ+2I2 zwvT<ewJD}Tc6>%Fncnncm#~+`V#C9Cz<`9!v~ZbFv*FWS?tqh+|J4gPC)$B0cI#cg zgx~o1`HvQ%PusfuI}G;YlEd=$#fu%17^VKse4Az}7ka|M3Ca}7!KCCP|H*Ubnp0CB zyeeUN57<!EtXe^v7Jx?I)~%IUw0a7WVe#4v|MU{tQ1KvSACac|QfZ)3(VAodBS~&) z$*d0PSFKDj#hx>(;RsV`?>5TRD^w&^BrEVBi(WR=(1bJSH(pWL0JQ!q=5cIXG6k_! z!$C1N!hh`h=*vCoMb~Z$YCCB{sHh#4EH#+JRdgn6zQR4&@PH?jHt3uO92)7LfhwsR z2)$r+)yCR18X~k7wr&(Ek0oQObAmOLcBPqY8xpu)WcB3pB9@35{M2UEOe$z4ND}E* zNKto00XzE}HiBRr9app-mh}#E?;a3$Z;TXY7A3`4S|qL6bI6jsW?la9>%w5Vpqktv z^!8}U_{LA?;OESfNsAM(Z_e72Da+86K`>&&oe=}}c<COv`F`|b>WK=dbhGfl^5qbc zfV?KEfXZZ>K_Pu~g}$ULRE~<dVm(^kPKnMX89g7fsoJ~NCODpQDn2qwr7L(8KM~rt z7&sHD@<;1pD^3TNA<+WmKqjs#{i`>BK#q1D`ByCv%tw>FK=?7C&iG0i6>uX`yK3{Q z>*hsxvd9iKGcyy|PKXuTw7<}eyZ5@}A_3Df0fBx)Sv2^3=PQs{m$*@K9@#5&c*Mw( zT|v?HrF3|)gCu__g#cpFA1y#@-m(LBL&ZhW+9NKc{+I-ltNkrD;^avZjKV6B8H(-^ z{xtrutuE0M=YlmGgXjUF8V>G9_YxsM`|q$krss0MuZUziVx4e+0X)rfz{=AF>y@wq z0iG|MkJJmFgSNT!_4o+zgKLOrh%XFE_<6W!SF-&=ULf@gK-i^7DNzA5552-cQP{R> zjlS}!bxSus3MxgkOq=)G!rKB=5AgqHc?ZM?j|-px09U^(59fa=IU_q88v|S8|C(Pf zt7$p?>U4ZxYuPt>0b<%q7SClDZ(s`M=#zk;N!G7Sx(3Dsu#G&7F$Kx^eEG(~kQ140 z@LgLn`&(jTdy1Uq$?qS^JTw1(C=0vb(NgMOwnt~DDf_69>dgo{KgTNKD*Le_osx=5 zcXk%pJkH$>ZNlIw+i;DIT*NDuT&euM*|s}6er&LCTWaI5UDRQKmV0FFJrM9)Wg~t% z?coUT?!axbn{|CD2AluT=N{`CQw{Cs<N187!rPym)_1fx@zxr#BCR>eoVbR<WzC$X z!mB-3H`lAzlC3_}M(lP$fRgn=llWjUVbUAPq_z~oIG46!M28%f)TL}8@CJ)?k~Gd& zlfM7;HAwbGOE_RkFefc7KOteRH&;!Y0HBF4(zh|TU<Pi>bqY)n5oD~(k^5%)7$UAw z7aw%Sg36N(nJo&=I)_<_q0e~4lv#BZU9B?6t_|ow>XU}X#6?8MP-{A(63Byt6|^NA zb(Wx_VzN=Kf%p-u4Lq))H10^(^xFCy7{`nlJD4$n2|M8rj-o~kWj;<O;}#cM<>$|! z^Gr(WUk}#&mg+E%5v~3?dVrXqFo}L3oy{L25<M~lX+?>8!jfWx$m1${fh=u`^(yNg zFLB7<%zENFWN-l|ww$kH$$Z){E2~C?ofRGIZ&M=1a%!Z(9xNl42JAyaQpk3g7EWJ^ z{vl1w)VJ7=KCvE8(9Vk@MH{I*Ja|?kqf4Goc}AQNL5ULwL6Nv#kc3={OodmnEJfFF zDMx>2N!wvA7%sd-2*9^G11_Ql+H(`4OpzL8oR@DUv_fQo%bFH#e(#ufKDXYg;P|84 zWj}+|W{@rGZrlb8C!#ry;DalLcy8QSc>PlM7>`xXO!!$|i%Tx=D8MUP#-ew=#)~xl zWi^4iSu}1R&bz8t9tA&o&z)LGhT?t%oZ{+gJq{C6kn&H#a&kB@V_NxR(t#{(FqSPB zCKSWcxchPDJU>SAo(`;NF)p5s>HQYp>rkR{_lDm&Jwg`jGzYQ64rlaUD3zoM^pDyO zN2qV~=gBuu!RAyeJ`<k*wlGQ4X$mqP7~MPeG`tVy{nlQM!lGw7p*n@FjliIF4}apK zUt6t}a~JCx4eWC+(1fh8R(23oTeuSDve>VEw4&EizJ}KHBk<60@2Mn%`=Le^{E`Xb zh0i6v;r@FnZ#Q;P!sj?KEA0CfBsiCA6PzQ%?G$*FK!kt7?v<vMGXuEXk@$M<z=&}{ z9@dFui@B+1LLw#n)XUBhOi&cK#fKtFOYBLgn@)`B&WQXC`2?XerRe^Qj%H&Dv=Eid z6LM@EAfRHz+l2tb`mdRfOOz_OI?vz+4IfukHtiY+V`<F-D4XxCTr(3QBh%vACZ*=! zHs-cXeJQKqXDObO07!e(6SOUa4)fq_`xy@l)ToS-w7>JLM*2gnqGF0vlC+ZnULEJL z=WxPFD2ISkpW^U3OKVmd&lAx{D2$~Yw%s{uN=$l1M%Tg3IJ~2W0a4G$QDE;xN=`y1 zX%)QIL`5@r9$)JRK39<r=^bm3qG)O}2L18ECjo@4WENC8uObnAi{7-VdUiEYPt8?Y zZtDH_$ERY7M(9*?tu|xQp|{W;z>*><>%p<QB?+E0at$@g9%#wv>*(w7_~+8On`rk- z<2|QnUCY+bbic-f{D)v|cZ%|UkWEKdzg^63wM+nzpEsrJDaYE$gb{-SvN5#n4NxSw z_Wjr&^D<RsC4<N*6Ih5S&wiEm`{=**AJjOP<1=r5n06@UbrJ91$V=U=lXxwo1Mk(4 zoh)inp#;2Q<zU+-)gQ<nR;SLE<6a?L4z5+delKSJ_T;IaGV{n;WQ@$OFSM_z_kHYt zAP|MwrwLd?*|yS)sr1j#TD_cV(v3<Ql)#F_y6Qj!0K&sJOODRn@V&p_p$xrTJZsQ$ zrB+*4hP4my$CW-`!)U{fV@x)WKg5VYz0`g*>E3FV{{4@R-)`{Fh|e$ey8m^w$Nyij zz}n8pz}mvoz}dpi_Lqcpt7$21ivAZIKrYs+1Y0i_T=S>LI>5MJ_*-Qa1k+d0RA13P z)R;C0vJ?L6KCPllt(Q2LVo^_XdVkq+TlZL$MqbW#oHsrIJSfSPQrHaW#((Wg14M5W z5_f5PrB<-y8Y{Rwhn$!khQ56xIl0MgcV*H=F4t$#hR(eC0JW`2E9Vioe3U@XRn>Ga zBmY)qd#lv2-&=e<j=y4sUF6nzypNU)9|3<LcqD3s$;i`wbc(^*%gX6LTAF&ViB5~0 zJ;B1#fqv1t*4qoV((};6aF%t%{L&0XG_&7_g!C)c-J4Wr0@Wdb%8`&c;SNwA&v-!d zuPrcyLBhNcldC6IpFr`J^EU*PYdTm|X4=EzMr1A_@&_#?*G8g61q{680M<56@Q0Zm zT^~lxX6R2w@2AfZ-3kMI%@D^Z_iE!rOyYpn?_kC%Gah7b1(YQP^2(HQ0Es5n>jzeX z^d00SJeoX8XB7v9l}kE?n$t^eoZBK5&ebjF-0arlzyv@CbE7kIHjfQIJ0OlDN@o;D zMk`H_L7;$H{T_cmUIyVrXS3hNjNwF2$|6P?p%SI@(#J&68^U-8n4>+0>=s^x+!wN2 z;t@-kk?@<#+lmJ+`yLmu;|^V%M0D0)!<6~ht`sl>8LXVYbKG(Q7>S-@Wboz~Kp<KZ zG(-U|<-sF`8{gGeL}sRi(!b%Mm#&$81I9WrXdIsWMS?^_Q*YsY6_hytFoNQieFcXq zR9ZGA$&1RWjXCrlqd@`e5^e{4gS}C#W5mPcuy8*tiE?Z9ga}aw<OVo?tKMzf>t;X8 zW}7xFx9pA0Ry(Uh=S&(Ft$ZUQ{$fnwg;%1VVVdSL3>5)@Hpcf3_2R(KP?IJG0YwXA zVZ_IXOq62r8Pjl8Z^M-0o|<JrQuIBeBpKXah}c59et(UJb`?w7N9fJ)EuraACRLJ= z5P~nHlq4&mKuWJz)?SsWA48cbHu|e3%AcdIV0_m4EI<n8g1yqiba~;{jP)Ll>!{6s zIhBrwp*iRh(yCu$wM_qko35au&mnIO32X=)7=Wy9LIl`7RN4=d&d+7fV`ivgq6{xA z_BW)p*cA!`?p@_y(qXd<_I!h+DNX~$oCQw3D9?uTSWUlQo9(4B<FKel9G!;P?TJU2 z?CRH;6w=>~r8>B2C}p-M?y^9mTH4k^hc!#-H1iV^@DFy{H6U;npf~lIK#>T8eSkB$ zk2G}KR~(@Q#-_#{5xb>Z(_&XZ28xG9eTjqV^l>S}P{GszjR0#Dd)u7nt$X98OK*Fz z?)_tPL1=H=W?jS1vcZ?x4C&1=m{21(Z`tgA`!hJM?OiX95nof~KEbW;w!IA(Y{)1< z>@OmqQFO&R?yBXvg=MkdxI7jmc+Wf+8i%NipP1u4>tzD_(Pts5EXI+`twNG0_7s=Y zXSKl%0H-bj`*P6jLUL@8P0pZ6TeG=;YXw_t?O^EXu2-a$2R;Im+q0ghpsk(nRAgqQ z(G#qUN`Zz6*B6^X{)6m>g$dRB2>zhA`95tcI2wms?3th$&8&ElD|BfrAyRY{B<Gx0 zzO}O#ZErBg*zd@%5w*Kj9YH%Z+}rN9nI_c%l%-0fsvJ?bI!x-ZkMEboflb)YZsgBI zv0!H}bv|a>EjN-f$nA$L2`~HGP#)krjaS(gM4o?+jLzH7Ga`?U9=?waTFTL!=qZws z{bFf9H!ZiV>)PKxly{exlHqX8jvGn_SC~@Dm?jV5?E&oSTH)9j<H?gLNmYt`tIf+s zs!_oKz+(3m#26Z5Fd8XXoOD`Q<sa_UBxb+fKWupP-p_<%Gj3Jzmj9G7rPLSoi==)} zC6VE%uasiv-dWfk2H3!vzO}Qw5|Z_*f4to7*)AqkthbV0;I3yJ+H&?jlnn9yO_lbJ ztD2UnNH|?$C9GRbZP8`&nKF%|NQp?GM{Jvt?lLqTI|>P45M8&XDqhPMRQrK_TMWg< z=1pWQd(OUki}GW#pwc_g)dn&cuqT+S$;RK8%=c6j1dw7Ll}();ne|Lo4a=Vpj=9BE z3L33*@mD>5;DLIeE5GtnDd*Pm@HiSq3{}Q8r;`o3TA#`Lbki#BjBwT_dGLU`n~DzN zi#!x0krMS67>i7H{K{!6PEg(1A%<VuNrn?^6G;^kMWg?xhofc|>IZuW39DYzWE1p9 zNWcHa^RyRZ&F_CWyFwJAwBG*eZ%8BlcV|}{lmD!ouX(K0HpNqS-%(kn*PE9aM#u=s zuWcEDLCj}J;z1kEbwi6#UDwU)N#jVs)17}lcf2YkE7HEi#pOKRoMi*6D>_tMc3)Qp zFa0*MkJnFJvaKJEfU|f}*en`aW>|Z6^}n4F$cyl@PzPhs-%M?ACGXy^*;IK6x$pSC zh6l*8pSTfCvhGqrr|I>x3f}AFTac%HjdDJ_eO|Pdp?*et-)cYNzF$kJ4E!29gI4#+ zP#1RNd(`a^iKYR~2uuk@!9x6?&-KKgF}y7y=^v`ozkE4;#t!CX`ZGTPH!qw!vF~=7 zTF}wIX+FTsI=vc*yuC1Djb>yENlgARM1g%fYu-g)4^9>%G}GB0WXm)<CyOA1;fMXl z+BIxgC;1+KU5L}@o5BDSf5;<Yc(pOGu}xoraZQ>DgdPwJ7XNOW1{2`!Ae8CMII+=L zTrXC3r=B?Xjs~l-weiwn%dGa0SI#kZn)nP??}W{}uLl3`Fk$Szc5DD{DF8dw0rPvp zJ;nsnOMn@Nx0x1%fGe><i+X0gsq)?!6WC*jCm_sgKul4g<;KfwPv(*TFl2wXL>YYn zwm*bYSJbGH>-0L!>EL=>2thuhm!J3j<9R1^i`N6SSFe|Ai<jg5Wt=>wI;P}1I353R z5~aRxpT4F>G73DsbMW2Cp7lR7^M+2huaCC_wd}tA`{D8acMdLY9;42y>znoA`=8F$ zPP41)&c@cVQ*fJ+84kE8d-XU2RuKIplsfjk-+tzib>$ywc;?{T2(T-%&mR94ZyaA= zA5nbU`Cwu&cG-CN2}BAt&Cl2Yq0~a*@J$1Tdx^MCqTyp?1+8oL(<W`pc8I2eBNy0E z9=bffKF)}czaP8oV%6}=LYMzVaD&bWr`EQuS<z?HqD{TqY3FtGZO^CeH9<tpD9)NY z&M_O!#j8hdB||dMylznke=IZbgRw?p#h*iGW}uX!9w4@<50Uq4LOpEL^I*bnymW6V zy&*4oLxr6<BbBAu54l$1dHd9-C}!N#3K$a0mD9qywsH613R%=1+0Rz1!YX*;9^2PO zL&<-~B1^q0%P+HZJ3S${UFr>V-g8znP{t9y%y@c2(~jn!cY$VBRt6Z;{vk~AUR+fL zl<8n-F{4jE4fmnIVLZ&5(!QJ+kC10+Bg<IvmjB2kk>D1=5-<_Ch$u-iF<o0jr||Le zaB_i~V&7a{>pr1+T!vd;%|_9|?_8n)N|PYX@geVSz>KBhG4~0toODs{IMVudyNK5I z{qV9O-!6v7cQVcdyWL&v>%G1{v|XG5>&WJLCXLdW!i9w?jFkr1zC19>=Jl_qZ~p9G zE*9M_-wfNnxw`$U1xMe1zxUg>&vRW_;m7c|+EBa<c3_lVm#cbjLVa41f5pe?;^Fc^ z*3JHT-UCU97X4cf_I9xIV5MOIiwLn{EoRWbb1-b>xe7B#l6glDv$C@CK>)_VG`1jJ z`!DPjdYx~qpDs(D!&kQ`4ZXLA2O_TZ1yb)g>c&e@?frXsonepJ+s8loV#}?$qE_xz zZg{fBpM6h=-rE5Q-C%9%-F?mQK7TkejFQ4y*d7`j5vUf%|M6(;=q<KD1t%r}N?ez& zl#m&|FUIsR&?kI^DfbXWS?H=57hWIbzRx=%XTa*q2o0gY&79pdfR&kIwI^cy8}z6u z{1X|jfsvvt>TZw-c0Qk^$kaggB0R}aAb0wW`H(|8qKVKkvlv`(t_-A0xh@AcDceS* z3W}Q-^N*><0G9lmIvD?Jcdw7zA>GWIA_0}}U67zCrm?<RLrEVY{4#*#C#6@`3Bv(2 zy?THW%MNL)gl8Hv)rr)b4#Wvr;uJWBZM``?KxLpE%LYWhWl=sWHu+cVgqHDfe?|S` z>skxqnKi6)vbN14hK*T3%d01=;t^St^y0Dwwb)KFRTH>&=i_}+Ji>>+HY7fljX7UL zWN85A_!TX592#`$7Jd^|C_EL5f+8H)3tS5I+BD8vQ(o+%HIpn9{WpULEsYGjsv0kn z_f{XBB<#VMSGRZ>fZdt6t?EVY!}6Gq%XLphDC9)NVtFVqQ^F8<VVr+qexUMp4sv=t zhj1Mcb93W#(KL^<Tge|t)7t{ea0q_we8}e+LZ?%D$5Z=iXko~%(}H@|&WA?XJ~a~k zK-f$$Hf1QiuF{uv`U_}s2h|NZ5ovngMN0dCB~f)s^wN|Z-0Sjs$Z4q(e_&7owQPnw zYTj9>_>)^(1wOC^GbMUIG$fEp@aqOW1e)b@+2uz#7dry)`yyCZG5j`(J$qJA+<`$t z7=WVex;PTC*v5;5!K+Hs6>KMa-@e-pDm~%{qapUTS>l~5TTr}}ep8!bb4Gp~mY_YR zCgOZAJ<q5m>UO<3O$JESuymp@3`nTZuCqaD8f-9?ar#?|W)nD7wZ7i~s0o>3B+~^I zv`jH|q=NKY{^3#yU}jVh^y}NE2*_khB`14p*_-Zgjr=(70sp_rpjiI6V(dt_qy>*P z)<XOOANWwR0>Vu6;+$v#<`O)}a+e6K0)NE`-6ldYlC&PeA}NFFh*Wr~!>?Z+ZK9p# z-CFVi<9#^=)JVuFik}}@+xzo(J{lR`$;CGuJi&({_j<?Hm9YG51%hhi`-`omP$qjI zaiq_|4mjsw&*7OVxi5CZWeq6MnpRJ}`r?(Mb44m8;R{V``UD_K)f@9n5mwRANahHN zg1^M1@x$wzV>rz=`4df%Js~n>J~ly)S{wbpx!9Y+!T>*WZFoKdcmN+4e9-FB{%EvP zLv^a3%@eNmVBM2#l=S^|ecIYQ9XoUSq<m`MUPse$6<%MQy>^`Co4%~&m^Ne_maVU4 zN*|HqLmb;3$|^d2GVS!PC$CVa7dOp46I>Loqwhkez2Jx2RUF9lv`yld^qFhFb=F)M z#f~+5mw9`|%)8HtvL0dKAyRI$KD=;JipX~GPcVv=R#kySEhiCh29O9TL7VTaYDC9# zxoM@kk!mFs#~Bt0Lln+vu4ui76DYVy8e9fKo`y}K;)bB%;QB)};SgR0c09kwG`qEb zmfZglNl&}tb7Sc^XVH?d5Fa=18iOawQy+M2(WSOtIkA?XupiSW1YO3(A&Rxb_zWu* zw}?B$vBv`lYT7v)cdR6yhX^E`f>F0U{O55!m`yd{pJeRX?Qsz1vN0Ucc3oWF6p>O# zj|4olrT(h=&N)ZADA}texHo;?=<ygg5N*LB#viV3Gqtsl+<r%|!O?iG?ZeCS%+Na& zcR+0{;dbjWYpuhI(739LBjOOBgumL=3cSbOb=FB1Fhfv;Xn8c-5}bIGU~1_Zh1Skq zsrh`X)?ZDnt!y}~sxg|}@Q7C$wVgi4Vs#6Zcqps(3XmH1$eBuZxV*Xmom%i&nfr5m z&iT+^^u3lbCFi_$0jvAW)sA(#`p>G$JS7a8#<RF<xo87WRa;XL1jl{JUv7DwLhUG3 zF)9RT0QpMMjZ<j|fOk_S61Q*ua&g$SIhtwP*SfFosBftyrS@efDQxR}4PYYxKX5#U z<Z=(^Xl<#v9#tIj&N0T(gSe&9`_8)F2d5%BDAu0(8B!66K_7peAJ>hoJ~__&CwJ1x z1&JGASGu9%Q~fH@1+5KR)B_v489N!3{J@0%3{M@Uow*|pWM6u?W+<al+e|w!x8n)_ zKZLyllPJKFt=qP3+qSjawr$(CZQJhNZDY4>+qPfNiyLw8nV5+A50zC}D|3D8vS%32 z^AfN8an|sF101{x0_fQeL7(?$a!8OTLad7{UQfnF($?`!bBMAEt9HqHna7EBlqo|5 zrOjQ@5^O=a;U)rf0<Eg@$K&<Px9C-)aYM32kmkeL>PVI78g=HLgmB3k(In>zj>39k z0g^5tcE4xhVr1YD`OeeEH_mGu3d2##MTMy``y?@=88z@zR5$TR`-*k-1;(WmLoW*R z;8RU@_eVl@7ao5nucr?BhSY3)i9jJMRrS>;LDX;%iq_qL4IY@U0gVO%FKWpZh{#1T z{6bV*10r%l!PTp}Ax&(}f3FmTR(0){iu+AS7NUpB7c%grp<9gH(E4F<rX3t!k+vm8 z;E`s^E4dJ`F1Py|+<Euva*r`l!Wg_Eo7AkFM}8%rq7X5`vyk~BUXckV(IdilIH$2z z4gQJbsa`uiNKm)!sF_9jQ%j<=VYwWt>A`$klltb_UJdFD=}#dP*6TNvEmuKYrjYu8 z;4YVbDo=4*3bUZA4eCqY+uCgi1GpEa`&SFRaOiXM)(Fwe#~}UEN+}P#&n&0=M1ZP6 zBaouVPH|id#uJla6I60z+ntHZ)-r&#K|_2Z^AWNV+;-gz{)=MZBue+MQc?q@nU;~H zp0bYr%d>OJ<0#h^eDRyO8W~#c<o6mMaU=DPm_0o9{)kd9mA08%SAqi~_Rj6)#!PWK z$Ncbl&x0Z87!yg67}>Y^p8FLJ=uEq2-RCEoRw6$chIj*V528?!dnF62k~0}B`8sra z-jj*rtz(gvO$J3DCcG%7&3uYQ3hZQwKFQKAO^E;%L{uzS*`}&2Na&ir0FeXv$&LLk zU8Gk72x?U-56jlkndB9xfu2zNxfShr^3krOB#`c(;#-p_>SxV18U+~6go;<+$C*Dn z_UK6&HodO(PyL+DD~ebMDQq;zd?ypuzsczSh5MWq`}+{S@0)|Ex@1~SvoHs+f?aVN z_(f$>CKnBbE+vkZz!#(au<5UU-73dv&5}X29vl!ho}7yoI_;j7kC)+lR32JSJ@CcN z3@2uh<@n0X><m1oNSK`Im2oR(_K9+v{x;}HBd7@Y;}+Jpz*m*)naze`abJcvx2?_6 zM<l#kfnFuVda#+uz=EH6@_p^3^YIHS&rZ^8&SC-0Q+utH#=BTS!3z1hB^zWEsa4kZ zbHi&m;bKaa7r|YNXOVL7CXo{f8L4F}LwtTJ@pbbf0a)4E{7<|y;>_@7AHBpwAy#0b zlm}84m?b3<Bos0b9mCLDD6r)#+nPrHW2Y0{7-DsY1VyX267dhU%<H^_(hD%BPa#Z| zWseY->3mF;w(mSyR4Ku{s0CXV1jzg{YHKSeLFPX=Gz`_Wi)wg(Vyqvwjc6vA3;HS@ zYW7<S<wTN;R}Td)4bu230}puh8iJLc|C!;*?f}!OKN!_DJx!G5z9M5}@oR4*N1))V zOoDFg=EXa0$-J{$JVUwFFOt!f-G7eDHZ6b!DE#aR3F9SZ-yqCiDO9@7mc5&+%1=3j zX#29j2?n>taAk`lpP~zC6WcWSHRFV{Rl$c1@=sWc$a7DZf|TX3NPL``Wh<0VziE8* z*8mH;AJ*<BF$u<;+zl)Y-v0W?u0df=F}r=7ZbRWPQ~tpBFS>BqD!gXKZo5n+ZY6!? z$;}LOZ#@8ed`{U?TXk*ma><heIi$?jiX9b39V;<pkLUw$`h8Gf-%%y|Rbk&%E3=Qq zI~q0*!V!t)gq$&;xH!Hb%<}sn=ei+pNouS|>e>WhZ&e4N6A~GD9Vx3OG^+Hv!mo6F zX+gV+XP{K?<Tz?nOqdFs!c{fVT<Zh7DVn4qNF@A#;ej__ts2DHwJ9}Z$7Drh27kcP zpR+o^uO9PMq%U+RgJ#NUg*8gytg39NtO~7gT_O9@m&Sw!sP2@E%;P_*OnCBpa2V*$ z&-U3snx;%PxPd3Ty)1lAo=9rUpfcx5nQ{Nn52Ln>w^l3E+2cC$I@;f_&Pn7L>WnNd zwTOOvQN)^>oWWWo(Gf>#flASV(a);pgG(=UM*9M>8&}?(WQ55X2>8gSm?^#a>|r)1 zHOhB*KDy<No82!qoQgGox~4`^tDk<Scyo<xn3nGQQ=$~Mr%#TE^58}>Mm^ZJ&$^v5 zi#fUoxP<*>n~i~G=qifJ1B}ti(PWo;KpxTr5%G0`V;RgJLWPccMinoPqz0wA`J;8p z{wq>ehZyk%_f6}{6=Max3x_Cg;~PG5G&fOwX`~u_&#f5>7yv`%kgp>Tgfo-jLy#(- zv*Lt!@hCE~av6SQX*g~y7KhRaVyt#!bR6JN>67nUW|*T4OLT78uJRpk+VYfK4~@?_ zqe9&omnw5`1}-9ybH{@V*O5}E3QBlLE<&TD1Bx|8Ye@}4`Izgf#F=2@Fx0MGb5!eN zz-nBS5Zc&89mqT=2<EPsPRXHYV4oT4A0LoA+#?UQI{h@fNXf9!f7p7wGB7NoCc~;+ zs_2pl|4YOsoOoZ*N|$lrk0k?L(7LZQMv~Nt3bL#k9-lCaK6jyJu;eegJ@;WYuQ*e= zW#Yr-e}#9Fhthc_Z{%t{ZB-BvD%j3k*g!jYQJQ7Z7lycm`+_gf=Gp60=k`Q{3oQcY zhd#iI^e{hm(A`2fYW$1%EZ{OGZgRchYOd^mKs4cnbwfAKQ0(UR$>s_=+`kS7!C<fY zBc=;M@?1x?M$(@=|443irbtrY%m>_t8mBNXo$GrH_ctYrkB90t!i8j5VF#O=wCDJ2 zpInobxZP~fDK+^br63Am!ph0VotINR(}|1Z&1?O^*u$%*JDL}NwtvTNG*gR+n94#6 zzNfaLu5#B!L~-iXDPLKzf@z12H#qV~q5AeTHdwshSBHIIz7=n7zW&hM5L?E#<Wl+& z{v?uMLDkyQ@?#u%4t03G_FtD6YYzn5+jwlaBiJ~n-m~!pb?>GntI6=T3g|WTCrSsJ z9p)dChP*=j?^W<)!3O<dm`6JoJNz{@RA=Zp^fa)5FHvR-FMTO4uGUs&7U-{<hN<bH zEndK5tk0L0t&~h#&ku1twWWYk2x?G0DgZODq?V>Lsb92W=mKa_^P_kUyHTeYSu8KC zw$vV+alwPpDMkmgYC2p=_}#Jki!DUn1c_RA^9K4bYRS1gsIJrjLelwsNHXX41hc=T zJNXT3ZR7q*0Ll=H-3cf~6b&jm@tCV~w3OuoP|F(#Z#m*j$Oo(Jf>syW3t$O&(sg4- zSO3KpBLz&y>uJEAOBW`1PYm*D^JX2kP+9>-n(uQEovICfc6Q+SdBcbVm2F{)uKpuo z<fywwRjZ<IE63}RKK_h<cqd=PLa4hz_228U5dYj6f7H5B%59JHiuM*a@8B@ma-oD$ zYaA0|xf}3aoIJf`)FMWvd*E=NZ1lIn0}3BewwV~mQAl@wNRHG#jzCO`HiQTvRo#Je zC#sr{p5+vJ{aPu)k6E9dW-8GAK5)3=c-^SzqPF7}%*g;NI%h&M?eN!Spi@;OLyo#s zdsSRH(Fy|?y*r^5dBX9=aG`aD>5$qHlrG?6$;o>_L7D)GrJ@w>NS*^>c^`HY>|P`3 zZz~M=P0_K#Ovls2Y*mBw?Kz}4>s*-E?y|(5w`tdBP~2j%`z>ihRfvdAN+0hFf274s z@QG?h^z`(MaK~FV$#wuC92*tfh!0S~w8_K)onBIyvBUOuV)xhy8Z?JF@p)Jy|Mgd4 zo^(;8lJHCmpq}3pDKv;>wF&5oZcNvv%?YeACFpJ6suW!pKP^}^Z?b8<rks9r{@YT2 z?AI^7A(0rBCt+9~sa_M?e$&^E7S>MPCR>#n*+5Ak;4g>dqi3+B>ae3btglTxon`i{ z$gCwJBh=ik<wOt;AG1<R&TZX@(Ld`q5+Mq2Bi!aL;{kN)PtjUA85J~NvpAhTTXtf2 z6)xnv183nIF~d(I+mr<>i`mUUW~#SknJD#A(?!*O#AcvGO+jjMK^t&+2!OO)b7$S0 zs2dR<Lj5YSVGeqTG<eqYdqOPUjVo>CW$F<cHzC6T%pVoeB4qpK2XNg0;U;;=9<2^x zx;|{fPq2;1?PX#!<Y(w(YguiRQe>dM{;%U!BY%r9{1^n<B|@HML)E!Pt_8q1`W+Y8 zDJ+12r6l$ua~_YRbWEsT-ic8vM@%43#uYCvE`2h$#4z7&VVpgAMkctNwnx2#I0V^Z z2_@09c<0`#vz2y1Vc{}l1mqLRun!ORXulr7MA<5EpMLm&yKQy<70j6}jd@sccq_BE zU%Fg13(&gH?s3lC;)#_sPgM#=mD@;{)YgKr-EI~I*sl{|vhO@Y)0pZ%+h4R-u~c^B z5WT3<L1)oWC`z)bVx?u%IE0fO0{TayRAe#zt4WDL%FGG1ziKpoOWcC(HMiw~X}}-i z!MLudCqQzr<r>zhbN2CKl3Yq%2_3{(U!ZU)?71nx(Pbc)uL&mz(bH<SdPlfP@SRzd zk^Qr3Dn~j<V+hoE|GO_}@i3=G1=~yirbXtPQh;+Ch~scD0O<7^E4+7Qhl%f#;6mFN zh6OGT9ax;E+AgH;a9Aq5LYZlP7k<Qi_raHkcIp33pd|=#+@RKRb8^%&0!Rj&tOPAw z<kemB2y^#hUyNV*K=7iSoB8qi^oBTvW44Xg*$~Q;r9IfTSWA%aB|PKc>)ML)a`u{7 zBJ%|<s7YPdraASr*@Guj>0_v2eb2XDD~&eWqty}FQP=dCN^T>c#Q9|o5^se{zB2K* zm;0h3>i~2?C5Jm&tzahnXo6P$)n{5($DCz^M@6h%p~be`6-s=1lqb+Z41))Loh_ne z<G!c7(wV6o>dL3(-b}w5N{4q4UhI!^y%J;LL5Cu_yr5BOM@~=Z?AW)DmJcl8$7=-? zj|kb+szn)K%iqmCC7Vv_VU&JDul;zd7U$x3d-jEz2`!*LZ^Kg@Qur&^jS3Z8xn;65 zUMgB@HEt4Eo2FA$04>(3ZmU9B1=uqbJD%I@5LLPE4o9on;vSwUTo*FG>2i~u{HuH; zNK*Eh1cM$twH~>JG*NXDlE&WLI0L-^k1%;)3Rpg@n)Qj4Oq7gUx@k^Jv4+=+?p8ov zD@q-}j|iI;ozMbMj&)KA_tyyJy!-q6`MipNAbw*8B`>34+?PQV<ia;tHTHWsvL=#i z=z_t+Kd=<lG$V6hRnUwpPrwsJ;F|Zx(epaR!0IbKoc+NIA_AjY9|6?muj2jrPobW0 z7S{hxNOiBIk_j4=dMk*JGmuIzU5K9CQSv(5ar00e)xa)I9MvDNSJ(8v8qzv{nbR#D z<1F*BS?=q&@V97kP_f?qWw$mbtD!Eg0Um|z42L(yloUF@?$Ax*2Wc=1nOl@iZWI)b zrwh$vONLsRD!f+DnL3~!bB8qrGRtAM2g$|n%bVC#kfzgVrvxxM=-%=UpY4nH>pT?! z0D(c+L&-X+n~51?(tL6N2^`z%0p7R<P(0gIR~Zu#P=zZm=w>q1;na5@dMkg1vGc+< z_j=-vB(njO(<Atxxi?19$D=I5R9BRa=mYEK9Mg!bSY-^;>MQ;6E<PwH{qhnjbnzDT zUUBZl!`q{on{u3<I^HeHX8-i*y6&^M{8HDNpR}Y0r?a=wqFtudx{n-gtNk_{(=WUg zVtFCyMS@W%b=T!cw8Hxh@~{u?fOld@g&cNYXNy;~IsTt%t^j1<l(?ZxJ#=Q1K;ea= z2dmUh+*5Yji;KD$4N;ff^E2TytCX<jr&08Y!oerU(ZGYU#Q_j#K2M%=t_0*0^(}47 z%%aM-nwTS@b$ST1lhDRxgo}trQpT$RTQx}AG~xql9!zdUPA038Hd6ZgS$N*uo*65{ zl1DnV3uWkKIV+L9)$xUYJ3Lcc3ewHy9bl`tZf=sN@b7a28ijh*omHFxG-RPm>+9_s zt=)vh&nr?4>EOFPS8%FRDuaK#RpAIPusJ)=t}Y2}-dpCw$|K&9nHy%4(Th<O7$<!G zF3#SSFo|5Q@qaO;*<l-^m<ykdT8ufMdsV5Vy}AT!3mO?k&-X-}BHYN*!iTJS&62u4 zrgV8gub@t+X_2eOY3skxHSPo1O_4&g6medn!4DHvw*s!NzgzKNY%?~Ooi#_K^JHMB z?%r`~XCRr;h#WW0PFK(bQD)P*{G})`=kPK1u&6{<#(0!4hCGIO4zEIipc4DUHJs;_ z;SSU0kN2=TXr|E3Qq>Ix%5Q6OuFXBV6gbefA03tJ{$<k8O&9NSCNnYLBtbnP;2mkC zb$qEx(H(72fz9xL!(ol^RPSozm0{Vw)CNMq_*N|`!D77$)huQ<G3@jyob@)@P*>bj z@pmtol~;0R!ChK-fJ^<7fH}|iKo==scR>Po1klL<#qSmxEd4ycOhGn7`l8P~UuhRq z^4m=S4)>gv^vGBPI8vzWtCKt&##OQZC0foxR*Q3+l(;GyjUWE;3vcO2uA|$@Al&)y z%T53OlFVd7003D0vgpwMhvlYUJJauoxaGfG$^Q_)r}Y>k48kqVHOKe-gPh(8s2hnF z6Ld7LS#L2fBegX}C~9pbemUdcFVmNFdZOgAwW#`In>jfvX1b~1b+Hf1cy)z`>E!VB zTP9Ws>frW|X~egp2&6CM@n(B-^v#C2yKp`|-U0Uqd*HoyX>2<<6*Jh~ZqZe<f4li` zyr$sYkF)unLBZt8kY5#Z2JGHTde5Q1J+v?TZfqRdE^(`5o-QiFmZ=<++2TRhp=vN~ zzppF!<>mmtPt4g&Rj~OHH*%t{S1?zT__}am!v4HIA!mza(69A!M9aYv@?8yZ>@%1} z`1c;s+zzuHAd$7D8)sU!$11K$I?%6y-R{Uc!c{;t{ULkfUX8%<PW3+&Og3fGJi-j4 z08RxN6+#Mv9iiBq)650=$D`#WK$wLhQjRx$!fro}Os4^(_C^)!-4^bhTbv!soGcr4 zmI+?JUV&^@JlHY^I1R#NszH+I)<?XVcH3tXIdhxJfx#GB1}qdf#Wb%Cv>xT`qwEIG zI8j+-`}Zj&0Z=4jzY|T1#XJUQZfKMu)?k=W&Le#ku0g=?)u#2+-lHk_?i2ZwO_yfm z;i$|_JX(H4=ev)!%DhQ*2Hf9NBGs5%IfuhLn~n_s_TQ_sE2EY#5%9F>#M|RL)-)YD zLul2VA!pX6b~L)ZOH*4%S8fNuO7@~6pZE440#Q?p06iFwkwSKd$PZ*tW}&46fYoy! zV;f%_o;+hH=HIPu2Kxr_>y#LAZI3%#5ke9or(FfH@D%CGu;f@Z1sDC)*IHnH_=HH( zJR|2%m(a(52Q*L#KN>W_&b!LRn2FSBF@RupzgY3P+p_-IfUJuKt8U+~b*w>Ni|9(a zHLByZJrNSjKwi@9V+X{sWFm}sN5YxU7T|xFIl<+jGRYzv*?oqL>bkPY&_)h^aVg<K zO(y1~e<(^ciNI9;Rp(RSA&Rx<X{b^RgLzL5q+Co`SM|(CzvcBK$f8YDQF|YYUwY8| z`6o`pOnkb8)bU5lp?cZQOKR^0CqIu_F?V7+$0Wf!_@!KasQY9sM6-#PUNDBY&Q8NT z?vHww9DTgAegQqXVUu8I%pbg!aFyc^9+@#+s2oQUgF^dXr^D+uvFtDPX7tRvf&<m6 z>1~aa4kqF$MS#v3gLc}zGQ+AK(TU`*=?#6UG0oR=^}|`?bg`OWtt)jy_p;(lBMrZ) z1=MLaa#SRBX!xTkVxdq7l3OX`PCOyqu$%%Y&(J`0!VJ%htOw5Xlg0aNQ5Gcr(boq* zYCFCY*+w%-%yP>C9XZJ^wzoQhyEb)k8>fD5ru8UbiP-?Y6&T8xD8&;r@m9yA^feWo z3#n}k!i#RCx7Y8uQ1Mz`_(41ONRDsE^j57WOOo<1D&11}C;D+-0^)c;V%zfM4TzfZ zI3K9>PSdF7tkWqLw(6RF5ULQMw}@fBrfe5r2vGT0F@P4Mdv-9<tX;afg0`ioZ(D1m zrS$l#b>?S!Kikdy3&0d}N4`c>+lcXM-jEJy`%1KEg8i%XcIl|Sh-9alp-j4of=ybu zd^7b}YwIc8Z_wp0)jJ%Df}Qz(sXJAZmu=lK0<lr^iB9K8W#Oo-@iVuua=vUqJ{if8 zjH8aG&ZRbFDs87*QhB8K6!AdlU7v9=nl1c7r|w3<4k{{gVh1BXka39Kxk=>Q56D<@ zGns};o31KGPs9KfC63J?{92U4uAKhutB_R%s`<-qTfjltGw<4&?{Vki^-ESMLifE@ z)@EDDN3x(n88qv)KFj>_CBC-<43=#zR(=NDIA3|5(h{9~ezd!$XH^F+&ki!;I;g^0 zF%Rh!V5SL<G~|v}6h<B3bPsDfjpg`@H;#!a$Gy2{UV-A3>qVF{Je0*0FDqM2^3ZYU ziIm<HQH;vi&p(ey;O;U5rg>k>SrY2Ah}l68)H+%n5KI5F%{ka^rmhl2ivmK$pI-^{ zGqBjpYKj>4MD0tFUu{mf#$=hXaFU@E5wkc{k98$<m|#vEN$Cx!XT0Hh3lGeVoFkKX z;lB8yL;ZfdP5I~=0PPd+0ff1+S!%1?{(0F_Ni1RZOW?ggN(s>>8LnOmQ!G2IDgLiY zQqxJ@yQ**_lm{oa3|i8){qo5~qM;OE`G{ku-iCuxa_cb+u#Q?en<{(xUEpARh7Nvg z&UbDDr5un^WcP6MuAJ62vLWftNT<Sudv9tk2qh|1oq+U;h~{e^Pp#?g0Hew0*}fgd zWlS~S(X1HH?G4Po6@f>*hf@`H`wpjpTCFVvW6306TdZ$DFM?+iR<=>@KCQnUN0##) zIp3M2%8HAjQgV=S7e>J~6uJfuXKpTSRL9on&}hnC5P*LNlenw;Yv2aRptLUSUdEG@ zmbfxA9(fn0kQ2>be0g)8vW22HlJagcAO5IOOgs3pNbL6+0CYgiKl&4i{l;MQ)Bl{h zBtM9CSu(hbt!V~Q#VO%FO8YiTmQ?9mti&$MRhlQ4alhNFjk;LWn!ixQa2JxGxYo6u zS3L_AW#?8_m{X$ha$E*l30tc1u}Qp?P2AgeQe<%3u;2NrVe=Fv7ARLPjZU&fY5Kc= z@`%T%em(0L<M21?NdDDukzh^4dGeGdN%s-UUKf2<Se9DaD&ecNP+i46g>l<(xM}`e zDj)jTwcTl{0ipd80<h5Q&hlAev;NSVAnZyt5~Unb^Z|YqtNj(57Iyg-xoy6es@acI zi7{Mb@^m<V5_DZrU(hBM2lZTlNOu`tGcijjTbk{vUcp*CD4p|+Zp#pL_^X)Wc3IKi zW6Ul1OE|it&Qn!WN+=}SGs={89I;A{J0*pdCUTia<`T@=nhom<B1zfLuPEzLyNyia z_b2_?iS$r!_m5mIP?eFPqrS?G*3W>%0cNXmWZr)`h%<ncR(}Qu6{F;K-v1kC1qCBh zqUG1LW6kqF+q3obENm^D_4NL$slm4TZEEg1eTQ|Uvx{@3Hy|U?WL^A=R?&euM_a5x zERgC^+7s0kwDIs$U1WZ|%uMmUX-zoOh>^7Rf4xwX(_Sm!{5Yr@o-EJ@#CSVR##!{D zo80<gew@ZV5CiTG<B{IJuWsH8-2RB(J-#N#4toK4x7gr*T*W8koUR~tYxcWvYYAF@ z=~c&L7J6%UgBOq=n$v-Kuh>6n{Hwijj}RZ5+Hks^e^|tOb>8RQqc9@C4+R_vDTDfF z=)T+_WBbbzM2fa0kI9MFO7{#in);3Z>Eh&N;|#>5UAm-yRJ?GTnbn~ZcyCM>#WzvY zqh02OpuZB0d5n|YGEI{%UNKFoCq{~%*I;^Qmt{9ePd>z?-K$wsLmhiDN_ilddSFdQ zW;ZdI>Ehr-pdeNo#2ssSs|^7X%%o-a6J10{aQeI*oyUF+80C5*cG8(DoHn@?%p61? zIK!)srmZD{Tep^AqKgkI&-KxP5Io<@57lA78}OLC@J#J;dj()DGC`e$M<l~`;ZVw9 z-a^|86Sz$f(bJc4xn4_=0i%rsyHO(Pn?qs*49j4MT90TX+<73zAb<ii!KeMT+u7M_ zY^sX899)~4T3fmrRRe&jgem&Wl~Ug00vrQ}S(WVO*a12V-&=Xe8q-R5e15;*I=cE} zyt{w@eD2L<f_`JSirLB6+1{PK+0ET)u;RwPa#MB!XQUKsoB-2FI(h7GO)C%yIMdBA zjuZR?k(CK(q0pDQ%^NoL<lzn<?4j>4<~kD-CDKKJ2iTUpPmMOML359|QA~I$Nw=;Q zxiF!F+c2@}CU#jz4sbMF1p&f81&C*_9qiQShX|PvyK0qi1RzVqZFKoMJT~^5?lN(Z zgxHyt%h_!<llx?AP@{M!$Q~7bFftGdDh~b9$gmES<uLj6NpX-r8tDUe=-%x?wM+mW zG<fzj&FeRIEP6@YqDeb0nwmdA(DrYFiMM>2v_|kE0So!jA7JK%6JS1m<V@6{#|2|P z*TZVFibi`#oQ)ug^lHk)>w!Th$;UdCaQ5%BDo;|BmjsY*Qcia6ZZ)eoZ1_KSGExvp zig}!jBagP@cP|n&==74_d4#b6bcLaa$>@rHjBuEHq6if69_jY5TutCE<nKzO(^Oq& z*nvt5xrJTeJmyik2a!PT9`!n2M<yu4LOl$B4rE07u(K+xLwFA&82FP%8CcPQFy7a# zBy4MUh8r05kiiho_G7EBdo{SyR+Ss%IPXZD_7Qqd035{hBd&up-t;6ug}So)7NF^n zo1k~ha;-hN+s<|DMEQgw1K^gq$p^L2LC7uvi;h|~e_}~O_ZW>{B(ir76w$|Tr5$tC zAE~;qbpS&=s}_4S9=|^~V6{;jHywkzb>u0&nL%_p&kV@{fqU#%g2@>L%Kf~rJQRwt zT;ch4bY)2|YHBA*8xQRDvy9zcT^(KBJYH^Z^qy`)H<j}Ar&Eug&)4hS0J~>eo?r8` zhHV%yu%a$`0`}q{u;AWsh@8=bn=as(amU19-)5{mNQ}XW%55Y*UoJ{-mA6%_lP8en z&a$}~5o><_9xxTf7y8rV^#0?4Gdcp*fS6f6PM%;9x@ow0f#>;Qs4y}|@<XRx=H~th zRJt$|5?Qel^N4PfOo@HJ!*!WH{Xqhh$}8*ue(<`)6RHm2c^GRUIiU(pQkF?P>Md-T zn)E1+XeV)je-A3l2LE($Z7Kw8gMF>hkEawvG;X5-GX14JV)15;7<Xn{3#FF&YkLr4 zJ9s8|b0RNWklc?^5WZFWq@jR9H)YvS9($<GE31kN-gj58J|srKP$U@O1ZHap3a{Wo znfhip@}Y;wVuR6HG<NKE2r99$W{s$!$={FDHR=UV?IW?{-%#J`m4G0={u!pX2rMVt zKGChS%fNMz`FJ3W!zk%vbK$rT9D`6+=QI-ahi9hT_)$|-H?gWiw{^Q%aVm0x9*v)| zqMgrTa%o_YnO!L7nAOFg;j({L!nYwvC5K^TaWFB^$@*brXmH~lKt6?$wHv_nV?7y9 zZc079WgdQ@Euv$J)ED?9Cf$9;fcLZDZI*)G1dn&K*g;lGBaN8&>TAIU^7$(dcEL)T zz#646tRm7v%nh)WD<w8ei&+aWsbNg8^n>|JjHn->tAbE@2;e;N2nlK_*NF>DL%gfJ z_@z-QNqE4O3T5IMVMq{MTNBKY9`xC_EFj_1Luli!f+>CoNPMP1w^6Q#>K;}~d{>jk zkP|%YTLY8oBndy^E%()<9)Nwn_{m^QeiPQdQdfXeN6}HPoF0b*4*JrnSGK8?>LNIr zoG;?yUR*9l)7~#P^%>POmO;T%d}zbGBZK<BK4e*DmkjMMJX}io1t*0L`lzK`s*Pq* zZ9#<jMW03#U>q*U*b%SZv>b=u{c<8ieXdfWt&oE_DN9fyi<O>vl8h~qx&I{*Ue1sr zyr_wd+ZD_fWA4;Dc}dD;IJ|Ph<83YQC&59Wi2_OJ(KHod(VE2SsXR*-#_87Qjxl$K zKl-u~SCYMV;)2vj0FKvOLM2e~I@(N80<lq(jjdQiZ~x+bGhEJ^>m<dePWkM|L1A?$ zViIH(v{pZ!_4T3<uk=qS0vQVAYeBXZJqzYBZqJHL=M}bKBHdyj(HdADXfeqG{Lb6u z6@Qnz!lj|4%9LxTM2g5*Kt<MX6xG{{I%M|K;Tu+AxKeOXy=Mt~fL*gfl~t9_1W1&s zLpVvja0XON$KY^U!XyoA)0M7djn?w1wEv+tmW{c@c!)xbS^a)c0nyAK?8D^!mYVQV zDopb$SlL)tE7)yVH-fmOXL<z9wks^+9Kq)ox+r_FxaAN0fvhrxjtj%tr#DA}EpZp6 zV5c<3KjfW9qGvT;SKTR<*P{e~&=aIUKrH4_9aGc^Cf0?xrfV<tkT@$*h)Xc?*=SPm zs#GXMHH!Wi4uvqp!WX2mPl>D09g1j`t9%tf=Svp-YZd2K{Y$$5@jW*@4wo#hb>ARU z&R%W}vOF+OS7%@p(OBezv0mj!^Q4GgB*u)K`@Rd_1$whQU1_Q~D$$xmO=?eVxlW}w zCTG$Q<-jcoE=tjQ-HGLh>Lz~y<3Wj3v+lIy+nXy9CY;g~1mMH0oQs2MvH;Nx5f5p< zLnV9Qp>Q^8!Wt-Al_EC5my)%Jro+m(Q^LJ$Nd@}XXC_ZMCnE;|GEPFp)l~lY;X|Zd zzj`c+<IyB2#~C<ID4i?r(fGOv;x7O4`Z$qGo9U|`nJ%U_u^Yyj8QNzn0W$lvK8#z$ zS|(m15O<*JMq>EPd3oWz2+*IaV-On1*<&aG*VQ6qK6QP~&f=Krq%zC;swI{oB@hkY zgGEizeqGaestKkV9vfIqDC-Gl=KNOO@k(@66Tl`+hbttqV}?%)I5bFK*A}sAuN1Fn zvBRcK=ejF7+=VNSY5VxrKL^x#zM@E<Y&QKaJvLfkoemG9NJ;P`?TQSVDAQJ`S=p2u zm|F{Li}MxFbS-y5!6mtI51vo%76itxfK||N2wyg#$QYVwO0MA?5PonJKlaD<^Vbvs z7=&bWFs#fGB={k<rHZP7Hh>d?cV`$$WaB}}21{d58^=-+5laqqw)x<pqqk&W3<bRC zT)7gX7$Uv`K11f7i~Dj%g1jY!nNn~2jpG-aXEx*d$o4i^uKlN?4!Rm96t-l3vz^ng zkMB+wy6L34d+LJ@Qnho?ursL=O@z6fDJX7TE$2c~B%gI6epVdWzMdF>BPW7=dH^F* z{>x69Nd|ef01sbXfJk5%Y?Qe4+h^v|r7Yg9nb?XT&NNu;_>^as?wk>)k=32ua2L}u zYxdUFyoH%3MEF$IpQZch84JuyB3zR6x$G#EOgv^5<VrZkg%DcMmZrHFcux^tYoRId zNAXoAQC?VCw*1<}x~)1`0TB&|Y?vxw5X`P@TT;5bU45}?*my>^PWud0x?S3{zDyv3 znF@BX%&Dsy*jWjU5(DvswyWNuP~4I>0*}D%lQ2OC+HxswDRA{o@LvOuScA!8BqMPt zu151_?H}1w@qUWfOp-N%HFtyBqXUbK{p$&6k@`HiP7pJ4vHN}KA>+J1=aZPmipR<n zEMB=`e-rCv8cSzcOoK8D{_x<b!#e)+H63;FD!YY;NK9!u#CuJgi~kxrU5D-|N-Sav zXvHnUDn4%a!89BGi~0J}img_Oa;wqMcO0b7$|~VVB44uVQ;H&$!bj^Ixnlh9o3T_b z2C4!uOaCg8ATL(#sEgiJ-MiWR;x=bD5+xJVF!gY;wIYbF)BJQloo6nM1BI6aKH?hD z+6A;=M+UbdX=NGq;@G!x>V04Q$z~`50L3$Jt)xL!rrX&RHV7Xkrbf>lQ8!2g8&Q;x z&sEoX^)cByifz|BBhs*;dXsCGQlo@KR`uRBBAakaiL_265k(IoOc$Kga+#ss(E}I! zhK)iMz~E(i%H89c!w_ggFAIU5gXk|WwO@=d-{^xM^+56pZy@Xa3cJ>sh|Yd7O7iAD z38m+|C4Kn#A>lF4zfEQEsMd2UFT3_!F2GLS@RaaxWl)MOKtM-QMW0rHT2cDAz-x2x z)`1M)J}Mo|*^zs?9RZ6yzBH&q#@UK>HYpPDmL1@!qPWr?Vg=i^lJ{FsccxDlCtF)m z<v$)M(<!m5Q1cR`x{CV-iEyaIe>xmTh2K2cW_O{&y+veZH>lOEzt+`TI}bXrYn1~~ zkJ3glpu9>m7hV0TZR(V^w*>d#D>4lJRBj-fI#V4Zw=`x(xsF!y=SRP<)g-^JYLUDy zx@nn=m0GYBTHQ1-WXaGHc?f;Av0P%R|7lQ}ai*0|vC^uH=)!Ux@lXD<S+rlX;^d;p zjpzW!Ci<?tZ9`|rusekdSr6{!W2qru(fG_Ho}PxM?2_<Zqf0gUb&qB<%1Y^>*U>de zwR0fj<kByxM%QSD1%3~OMOt@$-AzA_Qdd!q!n@`1u~fHw>*!DhHqY~st%Til=NPIM z+3Q`Fh?=B72ESE??mUQ4=VH2hI^c2ow{o=O9*7GixxZ{&=K0Lyw#1RRq?+8Si{Ok2 zB5la%uS%d1^_~IWXx`{f0n>M^Hu8wwK~`lf)ft)MYm=&_GO)8bU^(e2d!@0@Dgj75 zS#9KVd7z(s*5;`{%Zo@w-5REeUC}(s=qNlodM9j~WiiNh0+$v`a|7d_#2zHEuM%ku z*ojaJ@idV;mSFirHv#8$8*|L@-b2blo+19uS&me~ZTc|8_fACO<7;OO;|o&Awg|zE zkBZpHgcYU2iUe1cz+x4ZDvEv6H2WqPV%ZQOsfJ`P#xW0W#?i2AV`IdVvE5?a9q(P* z=qS$#=6*aK)XpNFA~<I9E2AW1a7fbxv8WH4NH~>J8(RoX&6KMJK;&VpD^MEm(dhF| z)dN6nIt)tp(sA~d1Dy>B>i{nEsA0n(zMt})dA$9dX;2*u0QrlGf&AWYb<8Ap8d2X1 z^XkZz<~P;U<`Rd%hF`_k7j89+LF#Ql3Yayj!igePQ2Qu7Y$cAvKOIiGl$nmWo=4*R z#2PgU*8FeTx2e5^>L^V_r-+hGglX)rVrUTVYZ*rLbszl)OOwDFvEZkz;Dyri-vUfD zrlQ*OEy4$mJ%U>a(>H_ZspnN?K@EUT=##yYX<_O+#f0Y%`2WR}fSXB6ZQcJwbpZhY ztp2jLx&DXgjh>#p$Nx{G)6=8>?*x4#dk<%GJ6l?2)?Y2eC?{#kc0mAP)XZj7VpEJ3 zUr0Nih6GN~Qi!yi1E8b^K!u9bG7>;fHMUzKo5NMzPVzUu`yGr2wC)fZT(%2{+?34% zidMV6IVsxA?Bpj)W2bT{d++)${1sE5+v^ph1Mg_cRRJU*Pcw`Vupt;RFb^=sTj{gR zt@I=9Ee(X!tkG`Du8Mh*6PR&XdY~=l`jh1MKaZ@4*{jm|DG?+wi5b{=kuerAy_f|G zg^VgiwWp9y;;+wQ>^}o<f{o|Z_O5VnTD1HaP$9aaUKPr3^RC4}o3xuXSB531A5hTI z>q2;<0TAEgt+8SR*bBj6h(r)VMCkL`4V(yx1Yk@C<vR3I&=2=zu~9QW@$%cg`jbl- z4=uuxmgcgU*+BMNx2{|NR$PF1J0*&V_+#S}WN~INx0;y|0xW5suZ)bO@tiNj3`~fw zJ(qU7Ue)3`EMME#GDI9!FM}0Iu^f`6V^?DF?QUbjWachdfj8GJ=n^weQW`bbu@908 z2RwouIeO(fSff*RdKRBY-bz7hIQ24Jkz;_;fxOvv7ySW&LzYSI&n`m^m^-*eXwS#< zL4dP1DF+#31}A%I+Vn_#$<btt3-z{&0FKDVrwZlUZdSxBD6p<Od&IR1UP9X_$F(Ve z_~FPXbd94Hej~vnaRams8BJkgYo(tJff5PV`E*hDpK*9XUqbMqC?U72nx9+Y^m;hm zb<_*$yfq5bq@3CCXKY(3ZM@ZzPne*Mcou`QGN6WQ7b={$3Q2N|Ka>1O@Z{AfAxfw^ z`&HF_U+zU}$(C%eO!wnJPC^Db*({J2eoUtMWk22VD4p<10Z$qwp)8?k{VL~oMtBni z-_v9^)Eg?`SHf>gd(>hCDjV1`gw(f)w$P}q<&^nTnjC#`j5sgwQzFNcGUm<P%Cmz; zOslMy>NS==LI1NRNF-el?0<0$%g_J-?Egzm{0F+>KMNv8b;@Z&1jUbf?A~pmRAPPh zj6hS;YMn$W^o$|sO<dZX2{wX!TDqb%I=-ZZ_)qKRQzi)!AE@jnDbDVWffzbmHizTU zkQeoa!#ZAl&6DqqSMSbE_mX0}Hplw+!!W-SfM5S4dC*MSD~#{p0C;_a@vapDQ~g?T zZ9t98IoE1O<pl!P?38~FpqPzti%k7gb4~yQ^cK!4r?rtA-Y3l~r}=>`=q{FXWS^9M zEO<%)^Qkr<{s~GSeV|@oE8Gc(6I|}QiRK%!yo8S0SghEQ<flaeqcxl?>5XQX?F@X7 z?gkX`3~bP9ir}IaB9Ala3++xy?UCr#bv?SfW%(_;N3WKFL_w>cd|l@@V%q9>g(^w8 z?eZqWArYM|$UL&`WX)4daWk`%02BX)BzwcjAp1L#aPG55BJy>Ea4QK|$~Fz+dvG`# z8V<@ULud}bpI+DjoVn7DigOJi+&j@~L<67*%50}#5};6yGIvFtf=G46ZV@R2A;Hhl z87MU0RtTYQKfvZ#U=Q;#VcR8y%mq~p`<5vEwu7C@SqK9;Z0_=yoa%%md;^D(U6?+= zc$jIyB~~i#*9AeW*|G9ciQ=R}EL2)urLbAEPV|5NG)Lo+Q^;#^V5*Ck_HwndW>>0> z5!ddt2D=esiMx34zPo&LY{F}-D=#^Gjo0}%2FTo?8Ii^}OUrJpS5HA#-CHC#AiP5W zDynlxMty^+IWJ_>KT!KvbZ>vxali_Cmmh-yv_(bX<Wyz(Job6s+++T3SmDXq)XJdO zOa*qY^UFBG<syoYz6HuNL9!FqrKoptP&Y4)Ra3TsdQU>Ov5M$Xd2>e(Ko@WWA*jS- z5k}n$Ui~grI^DVf<A-`${(}jK1(NvF0PXgw5oB@*Xwu3vPeyDRFDAydBnFmUf?~QS z4(yOMhuG0b2rbq2EDnCx*+~3{DkmGmU$bhE0+@U!XflYV?{ZzMB0|sSFCa1U2-xu+ zO;PoPY_(TKKLvCVPWB!=`=n4xsd1U9>FyH#tu|Up4%ZatsPM!1F_QDReQF+-3gu9q zjEge%#ek(KQA}t=a&>BWhh(7cVw$$Lxf}xZ-Jr&Cbq~_!upz1_33Y%DlP-)$T?{Y$ z$WMRYyMyvtOv||#mO7R04KF%kDc9cf`X-im{}$b~_`8fu(Qp{kaus&Xc#6nq>A$4x zDF(~G?c$B2wWkHq$jIGi9ZZZ4Nd;j)gLs(f+B<qXJ{@N)aL?>3y$;Xp7hWIW5~0wD z5hO*iGLQM>pc1ml7FIz(Wr_%D4F*{iX|An)hw}SMWgDb<UI{ZkDS)D}sttY9oxC>; zNV2;doROH;_aYbg73Pvr9#pscfwYP*;8YZ78oAwrFjsV)w&~Wfv<*zm=@C1fmvGee zpf<U~QfWb^NZkwNb7n=yq~+!P(!uW|$%}L1B(b&41;JOw0-41&i(eTXFljT3yyf38 z%KBWiWvPb+O8KRU$fR1#-zHQsU^j0SrlI2Aa=Ii67aM<;qyD7Y7_dPnZ!Px|jsy5z zh0}3hYRK?yK|qQyA*!7BCdb^smujhd696A_W+IwdD{IxHBBjh%P*i@@Q$XOPd<~(B z(u`42F27)HB!lFvt0q3(wqD)I)081o=pYRiid^jj_&6zoDm#;gi~Nxq@=_8itBxgi zO6lZm5GeJ}FeClkHoKdWf|-_neq;<Ac~!u{)3z^{<5)D~SfqD?NDhtXo&*$MgvF9o z5)9aunLiv{><q<IqjzG5DX~|J1<tEux!Z1bJ%5t0CPw4~ijC|6z!r8e`m5*(tL+fR zK*6)MxwW}dOW3^cb55#0%!{S@E1_hMpo!%Lfpa`Ptv5{tL05wg3k{10(Q)&!;QC^( zMnU!V6K**f^zt8{E}=Y2Lw$78^gNJV*3nlbpEaJh>s)h4^gDDU@WWK-I%ca0v*W}W z<BrDhj3T;?MMI(f{kNWFH^wl%@-!+p6vlG$PI5R5OogZWd`v_w&*d!*N29MWFN4br zz&pA48~C|VqIi_4t|at8<em2LFHbPBgeSbAIKCBqv83x9a!n2Nm;mK5nbM097k``p zr&@L!9_$Pnl<OLf^oah53hsAkdF=SdMDs4(RYQ>(5<w5{<5kQ;R@yI1PNFu`@a@gU z@seyfXuqUb$K-XXzGMp1gRSnrH+K3#L|l}=josES_L1>_dBpw?{_#JbFCWDjy9EY} zuk2!tm72<-0PI9kID`rkp+HOUV0~nv&PT;~bvjk7&I+ka>sadb^1oLjdIP=5(BR+D zvfjTI{QWdk{^7>2o|o;DurJ@6hohIO8t7YKxX_pf*lEM?K0qN6AVNS}!9aeru9H@c z&47L_Xd!JbhC8mKiS1D#d#(voT9FZxRQZNwArl43x(6Z43^U~u<r&a!d4=|j62-^y zB&P}^ZK(I>F2|i3*4&t%$}`SDe@$2nN-+)E&=ss}`!j$W0JoT~dZSjd?F1tCI-Uy! z96yTWj@LL2Cleg47=)?}bTMgs11WvzzVm3ZTote<P-Z%2<7mZ*T9|`r)TuIPM5|t2 z)@N~(Cii2F6s2%yG`!J|`5ggH^}Q4Gj$aN~sW#fWoJp%DzgAw%>ZvF}B1!n&DT_Hh zXkqPvo?RuK5fUrI^I~`nF2|96+2GF2u<XI4h3Qo^mKgx_Cj?FPI%y$n1ngfBaieD| zE2BV-WwwJ9MWTflz<D`gPu5}s>;^ghNfW_4DMw^}GCovVM7Cq8Vvg3+7g-+8(?p79 zZ80vjFv0b4_v%ZQxGLlY?be9_r(_R)R1Gy_rG!RV7jRr)9gyCbf3)~4h`5SvWK%Sn zP$QLiMibd}iVuF{t5Z~xSvkZb?s&|lo4hxIH6MY;jC^dMQw>TREnwFeqHxjTByp;q zxmCD2$))0dzWbG3^sbV-e4ERhXwz^udjB6{$bWq(CL|pSoqoB89ly;J>;H1@{wu@q z|AhGb=h<^n-Lg9nLD2IfZMb0Rey$B0N)rS^DVD+)02c~}fATCxf)c8c<qB$c?8;h< zFgjV5T@o3E2Cw_X|K#U+3jxo)*4vH9(AjX1%v@Z!yS|*hykTd~I<Q^I$ocvDETSX) zi60sDKf!iy#DowFhgT$)CT|e)mN^HDaA9H(w?l}rGPXooCe)|P{bvz1gqEQ-^fx>e zM_IVW@|1g-s9MICm_qMt$nM}8-N)-I&B+7RL>B{G<Cs>&6PGd9V~q;3P9(E<ViI~F zeo#Bt(}C+wJsx~pz1WGqcYnJAV!6rz=PuwN`$Ru8i1(9JH`xjCumT{*Bk)8j!Prq^ zz|Qf8D?Dve3ONpZPsIYeWUP-9-%CPMR#?5?1!1_KA~bCid)R_wqRS-l&mCDRZIwQf zNd1Hrh|B6q<TWTxG2A`tK1|VaoK(-DK@woM;VwKvw)mppc{qsxoIW5hKpuQsRygfB zT7|)r)<5v361ZKi;42ASFr9%8#lMgn<kjRZ3;>ze5<YSD!UM6za3e2}UIb5c2BQM= zg9H6W-g&ZQ+9=?1)AYXs5x5yy`m?pBracpLmPUv?B_43l1mt@~;`Y$!C^z}M^Fva? zMS_T!I!V6@FqvefAZc1A8;LEFI+nttct#OTX9QSf>lEIRcehb${xXZiBSXyNMDN)k z5|GeQ-CdhNH_L|!{SlMg#Y6XaYAtIU*M1Zzk^_Ux=%O)26RGaC1%n;RY>Fy02;+s7 zK?ehQ1TU0S#g=9UftMWr21kK(eXZtGXz7STsUjG1B)sG7r<j3Bcb?~~dZ=+XHm@&< zAwHV#m#8_W$hEO>Q4PNEB4dw-)8mKH$Gb9eZzfJigSFG*?Ol?pISd+A(Xe@n2uDeL zLW?$Bi>KyX+lyA$>dyCf^PuhgM%b1_hnh+4u~#{fMwXD=TL200TK^tBQlma@rYee7 zlA7|Cf6Y2Eu9-z_inWX>7>%TW8-q{Xc1Hcct@oDUbRV(yh=L!NWQWkjqRzKlpe&Zu zJ1PF)4m?l;nE9L8C~WKa`ix5b!gxAP^|%2k!5x~$fPaZ@tbj7hfOI49YHiaxePRUK zkg&9zo{X;4FU~Ip!9q*+Y$1wZgSDv|4G|*mhs}G^AxeO%18ZYAQj1)9&*RT>ft0O) zD&g~<bs};D`zG(56`C>PI9Y~1(g%6_PtI8D6aY;7u>jG+C}QO=_Y9+E(BIDC+_Pb~ zPu!=2kP7JX4=mw~vGO1D1LjA3p($#BDs_Ne=2r6O#+5erHf>TDnYC*szLw#!;j-8| zbu!0E-;=U-_F$o*W{Vy@1{Z3G5+7R7yE6dumcS=G)kUW60m1y{##<o|XYwn271zw6 zAf!-*Ux3ni>TFp>;~Dqb%?)-tV7eF>58Q&|&`C=8*_qo*ULNuOX@M)GcJ8g$!7G|t zODqm{7Bo>FMGToL0?HC_F2DTEP9-bQ@MOJt9=EKsD^yd;=^V5Z%B(}%v?~I0^O;K& zF2dEn{hb^)aknc!X!WP7Fxaj1OQYJ%PQx&<8SAJvoRM-zndpL+pJd$DzjMv{AI8OM z1&mQiV=;EmMOUn~2>GZbcK=09m#(W+!O-f<VB)wVgp$S$DH_KQr;{{wrYzi;Gf;AG zFt|Nc^`6@1zPy=8hCa@oA1H9nZ8VAQklK@kF=Q>uHd={)BOXMsD-ehV&Hd9Aw;u$B zyOi-f_R}b>PQW*E8Y|cqzj$46(WbNFf0Jvq?`Hw5LF`xS63JFV14~FotYz}OaW90s zh<;9B^=%%n=C`NolpuK2@53p(1Zy`2t$W=?U0wK4!u76pqZ+aj2z>}Jel5<=@csX! z&;Hjfo;3?RWc&LCeue`8VEJEe@&8M*{m)B$N=?oVTNEWv=Vyn5MP`94In|a@nYGv< zA-_<Of~9t&)G~*Hkx~b)>gjrQ+qm1xbTqcxlD-&x`WBGG=_H!t9+Kk{l#rxY(i@2G zs9WP^-C<sel!|TrBqN8N`R2E!=+4N_$WeJ-_VfFE!6EcZj35WSIk|n;K|mwK5|2=4 zav&*`D9j;>mFA)>EC~<(YCbKCNDcK3HODkGk$_%oDz7~XPa)RKRre@F4Obz^6uQ=g zqT(f{fHy9j+C|$a$=EeIg3i;lTrjGX)0uG9syu7Y_JDizSZUI^uG&=c$f`s&1sN<g zQaa+y)TNdvP+Y6Dv&A~bJDQz{${lrQXfky|Uaau6qNP#pk{z|D9nY0wxM`0j0v_N& zi-3cW41OUn*;9tP0ww8tGeh#UH4%d=_~3L#+t7GK_a0{R2BD8Cgf*W;x`3Sn3qc;r zM7ALf+#``1%<V6Wgqo?^4S29D<+&HZ>qdP%h6yJ}@(>EAD<2L;vB`qcW<<_&SvhXq zTlL4Fvl$7m&^1cS^cK~@u0*rJ;ti9dT<x)pTY1~H9BnH19DZu!LimNsGP#$jCJrXs zvJGbQ%?{_|l=_^rv;<;uKM)%*>p$?bWASb@jKfYmzeO5#cK0v!ldnAe>M0ggDr|x+ z3bJG=$X==)gA8>SY_CNZ_(VYAv|}j6`g{>VDe8Oflcr@18+2p+FA?Y}E9M-{Fs^%c z!C>jTj!S?0pXftYsLzYoTvVujMRA~X3|83DOHQyd-$pE1eCCb(J|3C!u>NVp)=_sM zuzH|X&BP2KegoU)8~_F+(N8{b?9+spcYvDC09~jR=KeKCss&3^(_mTGM=0kWVdweq z3Ej+BsY2Q$-qlN;0Z7xa0FfTV+bhZ7t<hpZ7L&&2couZ@!~c)4cj^*^TY^N(wr$(C zZQHhO+wQV$+qP}n>Z<8`=jof5v)29#nHiBgGNKI0lM0zG8CWRS3_?Cp7h?ticT=-5 zdk7~w#XPszAw4(-V>UV!+C+VT?wVAP%r4z&fF6=zD<IFRoNk9diI=ElKUn!zDAFQ5 zeAF+qO>^#yalUlzB!zOq$o1W<Uad|zvEZV@h%6zR*|9H@#ugg^$+qrHV?qmd;O1HF zq5SV5Xnq7MRl7>O&1HUoChX)JCCD->YPnJ!>}~&2=fhIn-#q{Kt0sb`O&hkm6)EO| zMq>_MEz@aZA{LCs>H1d7(8<xE@HVTqDs96~Xi=u=PlKL`0&q|k8Er6j4ZI^$up{|9 zF;iCT5j8Aac;-Q8TF_eS4Tx5S+gn-i?P?8zFd>x{&X}U@B$X8CMNg0DMNmqOoS2?S z%u<%bv<i-UyPyDoA%{eW^zqu5hk`N)`Q#lKFcS1KXup4+9uvkn0_q@=Dvy`p!6se3 z4VccWT57(xu3bgb%G`Kw8T0^si!U7aV5p0jY0G5a0gD`nz@Dx(YD%L9;pE8mFI_8I zuGT$+a)<joQOf0t<@~$Vm+k!8{qYez+`O}9ttkdvU~YUtkkvBvn?e>2Op?TvWhMLD zES1TZ;Z9uW!ruNcwq#*!%&@j8F-1DlP@$3;%*hP?-WaF2mmZ}v;SMSg7H_<#{gh)d zaH>6IDx+kk%dBH14yHN&e+L>j@dvR5u#|KPl=0T&BSgSJS-HaYBdi#u{zg6!bajGF zEbxfHb4MFRB`60a{J9K{o%H(K@MB?oHE?5TB{o6u27V96+JPU^kqA2W=qiUWkMCIr z-G)rnD|C#Sh(4aPfBT5yPM`UirSVN1*uX?pbm+2Y53C(D#@3>3tN81q=)|b4Qgq-g z7au>NQWp^5$VC^T0D!%K<k5>Q@wc4plXsORe+#)S`u%t)xQ+!8MOz^@O;s^AEg7T# zK0rF^M#*rJ0wXP+MURqa7vZ2_M{loouTr&gOdM?J3Qb$2Ac_Ru=q(O5UUa~*FnNB9 zkBo^<PIPoZvyPI&?`scC)Sn>A)&G4D4N6pGuqXD<<*IbyzAXy+A%#J@p4zNDB-xf; zUSr6J-k>kv!Ou6!Tex|D13bGPx>ZGOcvKwvRc`Q2VXglTbIyW<+#2oNvTN9ywj0n$ zHpOf~yTtHc*x{2QH?q-xSI%iiMco;bljM&hI*z>>6tigN(xR_^F-ffic4yRNN4kUo z($4mW4j|aEc=p~jjZkvR^_R3beDR04D0d^;c;?a>`ms6Pk;pzIgwX8KoR)I4QlK6q z`j`6uUEzMu6w=!KV<CnASO~}em|y=*QvdG^^Htl4-x5LCYxx6zma{D`O+g!>S`u{{ zxD8E(UkHKHq6!K!zau;mz2U)*zQ^g-dG&l-2vyu_|4sTW?RNn9(BBu}VPIy=J<DqA zl!<*eHhpdH&wOOpwZrB8eKzOs9r7(og^%s0KP0~gP6&Y+SS+GJQfOk9m?%oYw?)!8 zF-=GuJ}*8<SSY54m_lzT8ymsJdC8jg+Y(onbTP%DAelqMf=$ueog-3UA~@V)R$!L% zhng=>dZb+nt-*lOrURGUYP4wU3YNC1U=FX$X3`i@(iY8$g>R;2j7OJZA}KOc>+AD$ zY%HeeBs6Nkd=u)3#qfv%a(3`NL>A34AxzRHMpy)zmOMH_7HPzVBU{`dNFekHh4(Q< zu$+N4n7nq*CHe@l*{3tX(ZFZQoJr2L?*)Evqe$}x5H8>_4G~lu@fS7(WVm8rXVMY8 zTwjr?Q8JRr0Pa01Yyt3!46$~>uwHaHZUI}wL!>zt4w_5k8f%BtC_cisXy_1_s20-~ zd<XZX*8GN8pgG0`V?C9D_8pdCc~6k1ErLtnBL^WbVV#(glwR`ZJqK%qs6rQp>l`Q* zD;GMIYf|~$I$^1FLH98UDJ#A;YT?gixq3|N3`GXl<;K+AK`*I1sh(IUk~LCDgB+*c zf@g*ttl+Z_*a1mO;mD&r%BcB|Q0Vo)1kH(RgTnje%qw(cD8z9tzl7li7^S^!*VR|y z9<8KlQ<x>C3Xu=y3ReEa%<Q@}qhm+H?*Q?I3~+PJDgC+YGphUfynBWuBJO*AY-~@W z<r6Xo9pCGX%py~ki7eB0R){zF!q@%1zPGVx2BdJ~^`uwBk;B8I=(*dEH$Ki3a`JG% z02V$NsCGElRM5X4rmN3?8Q_%nejy+oa48R#E6hF9q<Jru)-D(6blup`m+09*S;`P+ zDoiX$ASW;ZP!!n{1OyP<SI|?6)n=2Fvt6RE+{Z0x@u|Zu$MM$f@Uldlo0XI<LM6!v z#vM9-aq|Z~Kv)pdVeG9s*vA3Gr~pt8;%-}*?2qVnz|jM9j$ln%I)XY2E)kjrSe+e1 zHLI}RuXCOlRAqDAWiPAXF1<_E#TP&yIPrRo_wNA)eZ68^0S8aIviDP8+2@Nuz5Y;n zd3+b);RdbUV*de7_9duR>9wcf7&W_M9XqLn9W#C1qruI~iYY6Ua0_l>^;vIHM-W_* zYt}Jb_F*Qw3-oA)E0;}YX9L#ChRoq1I-605K!Re~c8-~=rlber@5z}`1a2|snY=W! z@IfWb@9Y*>^^0z$MP9lZ)}!6<V~u6X<w<D6`N4`X99fu=6<6f~Q@fq6G+WR`sIXj8 zaOv`t9sbfd2{dg4HEbZnGXJ3F&J{|hu0)t}rK~@iX>Fc;s)#A5uGMx_q$`{M8bu<T zLTa{ZGB|h-4-ES-cWMzJIde>LAQbiQ;HFT|&f&%zgzX8I$XI5qFtN^jtwz=9(q`BK zd_d0avC~opPd<Y(U2SnK3grZ~%2QJerekZUH8MXb)?2|Y=S4+0$q$&zZ=zd<xzZgk zx<pvDo4F11oj5dsj=NWCScu1Pfdri?YU^gz&}KAfP{n@-QaM*_fwHp$%>4xDFsmDw zy3XY5h$85IOC*mFULtVDrRLCWyuql&o(BV-3YsS?KEE;11$J8PJHc|?qes2m>pb); z>hjD;XUvn_3!lB1Lu!anc=P$a2okTt^dO$FrfE*@ZY+O`W?}AT6lbrcKBzVp3fdmX zm`^gl!SkS<3#^0P3tMA(8q(vne(#k4y1y$`wxOICp57X;SZiMN+mM>!4%uj((O>;` za!sn^qj}dU^IpyU%m3dFUZa@|asvqfAoVZnl;MAM@c%#h^uL{Z1w-3@TjK*~i#an> zj!xDdGMlcnYd%h*OnV(Vsu6YNwUCY|l}m8Ltb%6jl|+u`^?AK16B7yVoG4@%e;=J7 zS6~x7BxLya9vYtKpN)Cs-B+CNb%%-PJ|JV1{On8D-fTy2`#Oi`Ykc}H?C8&g6hCe+ z{t&u9R4lZA4rt5^$JSZQk%n>Ls2A7P8m9l{<uvPhI?NV3))xD^a@*iGm8_~IR2X#i zQl)R~yf#nGEgs~YTS418X6P*WAYOcD;2ozaRdY@htOZZlIN)1v*f9Vo0PZ~Squi8) z^(yj~BoU)i^P=T9pCAOR1=8p&hxd>n|DL5|piFD?azsyl_9gJaZ(<~9#@8A+I55A% z9d5f{PBSn+4$K{#|8v31!Pi^&(2zIWyr;w51Z6LJ-e%$2ZTw;<a;PH_nB1eSh@{K? zgO!|yHtiikkDA3B&y*B)+Di1cV8Gu}(;mF_KpjL^00ETLEG#xK7ItSG+1OF!B<0V4 zp&-WsW_ah3DG-BSNy%<7U{u19YKo@$G}rVDZKK;<F9k~mx1^VAnOi2eM9%+=*Mh^Q zrgaMrNU`+HZmD1k{6jm`F9`l=wYRU9^?|562DVunlm0zZo(;>IvQ#*z6~4n5R+;x6 zjF1M)Y!WNx%dAPg!`2TP#=m;}_g;D#`=z%8E=c@PH~Y2t_?eDOP&^#M4n}t`0IeTx z24aKPTZ3>w^bEFK2-%7jgCQ5;wZEZvK}1F(X*ixp&Rv26uW{Y=87zO-L1w~olRa+9 z_Q8WW2PVqzLUXOj5-&Dp6$P1aP#5;^BMf9Q_zB{Wxm^;fc8V6~n?ucCZTMyOfiu8~ z2k$`KV5|$GuRv<yk?U`P@fmF|K8fTEJ{$rL2S6pCEAG5Fw`{pC&ogf@HpKm&7+Lt< zVU5v50k0j{e9(C>7OG&~YMYp2ajmaq#OH!ejKluktX<i_!&EOV-URDJzkiXq1F5Kr zLopa9b5MHV4J&zNIy6Azpa!HsvMg_-Sv8vnQIBb#3eUR*eGU=kf(4vXUeX1hhlgX% zBQX#N1S)goip{6u#d0*-l|qX$gR~731Aq!oB>th0U7+8KD;07>o<mw@^M{gx7jtq( zpLRp|B!HzC1KWgJPyUmZi<Pz%OW69}5XwLq)C{8-=wA`&B!SKpB<jjmYoPE5*lxNb zx^skLz3i#0eSAc^sLH*!f3K9HJ5h7OYMcofVNG*j!C-*WcW7g>*qt_p6ZV7?6vtBC za}R9R|C0=c40v=_&(<qO?gFFo9TRZfGhD4?SpO|O%LjcBtXQUsYfnwdlb3MZ%=~qL z^CvDH4=f{EEOU%%)#KIm5rjw+ILHKOqwWY0x<L?c$+(Q0c<x^~A#VF?@E8P;VVu1r zXJxXZH+KXM!L1<oUN`iIAkERo=TX7Y%Yx+62#<zl!_Ld1v>d`nZpi#%aZm?)Y@cGj zpm?16c;8ib#l<(2{&7|Jz!>!s3MJtAhIr>+h^&Jf8L%;&k^A!%*H>rQ7spytLx7eS zFHjx*FsMHh7z{sp2W=7@mZkNdjfmJrkdk%pk!#U!*r0hNNojK3NiU_FF~guJOxNTR zcBvXW`_h~5jVARZ4Vb9N;nJq4Pfa>AMz{}7k?vCcu2VtvmylDNq7YyMAenS$yGb=% zVwCNA0rRR5_9@-1r?9xxm@hqlL9cxc!7Wou;Z8Z~*hTift5tj{+ES&tsV0kjs5lAN zVcN=EzI+#JW@lrk-REFpuJg~>88ioA9MlZ^s8Mz;EniK0P_FRddCdU~>&GWh`V`)f z0oxoVWhWI<igD|7L0)$@RMJSzKr;)eK|YB<b3X&l0p_V0o|<eEd(8{&(Q-h+o+xO7 zZiMT%GAtrK8&~s<3eN&tji2ChC=8kjoZ|x?2qNTU*RISkeTb$2)EiDd<%p2^UlFK| zQTNY>u?HXx9?a=;Q%xQ{EQ~jrO2`0OH?TE3L~aEHHdUTAMfSXxkl(aL*@E=DbcOOG znE2WJ85>|BJng5xeW2Kmb2Z;NKCGNSpZ|80-OX|P`d_jnWxUN{gSKdlv_*g3%1I(+ zgHqRI8UeD~%4Q;^*etq~u~TzsoB9s<HFs`%IdNPvn3zFX9crJKRjKKVD8LV^397P6 zFL<!jRC#6=?-i2f<V4<q_T^ROxAhMEQ`+g-DCEZf(x2qUNBX(2)@^ZkwvE2)wO1lN z;*N6qOKzxrdZhop@#UH~38l{oSH=(`W+UGQ;{o_lF}+QrFcVrhWhL<wB4{$>iyzw} zU^?`nciJkKEU%-q;-jy)T;v3u;D;sNZzn192%h$@7>U1wkim<18bq-Vp!6)t9?gQX zxi{FR!iXcUVX7*NUVg!`wVkTkcPNBcdRbq7Q_)wp`2;tHdZj^*qx}HQ5Edoz$x9)8 zg_E-!Yr6SATjf0hr5LI*VFcq^X;!$Yjl>Wj563=%reSQP9<&F!_HO_I%+Fe9h{hRO z$3_XfyLS^@g=yQ^w}(~5>(wx9gG;k^JY%<lXT)7`An7+02bvaF(-uTsH&ead{l?cQ z?fMX80<aM@fwQG&tNO`pS|Mf&_h(`<T?1O76s5f8=f@mpM%MgN3(HjzR0-1~-WkAt zpL<5mNrI7M7Hwsv(CV!&`|>s%CI4A1X?`8N63+)#3{f{U3SN=#G?QGXg4ZY;ybZ=$ zqWXc}X%?cAfmM<4!laW0phQYbP|&?_d!cNTMrTS|${Jr#&gl(;WrEmVjJr5Q(fw#U zx3oUaRxKZ5_xPi~w%RYA&hnk*<72w0Ua_kVT9pWTR|av)33ey@EacGST0L-~Yon_- z>6m}iG*@Q`HPzhX035_sl>b8s=K3s5_1btJ2U^}hjIg%0oR2{WQh>2oYN8fJQ6(3t zO_}*>BM>w_u#TTFPlj5=r7{W|*B!SvJGlsrQapJAMZF_{0MFn$UO}>w*{+#Ve1(6I zBZ$hPIA19NB}u7@%Cwg$Or|xRr!pRLWru1HYmFJnJmK|&eDZaTokwx<b<Wq*I1#S+ zLXri3ww*>!M}7(DoLKRO?v)rS()|Qd`$syNjQcm2NUh+5nz|O0olJ37@9LNMR=59I z*ll4%;u|2VFBPGeHMHJF=E>d|Li)7eTJ0Hjovq-*8#0?S)ONJVJ^yeJyGKADX+}px zgiSE}>)Hz&OD0LhoVBHNciFPGg$a~Kx1NUGi6&aljMSoAba6&*-@3J*+~|RhZO>HG zg1|rV;p$bCB%f+Nj5379TGiIIq+_|7J+`#h$NA&&acf4aNvtbiq?zt7v=O=J@Zaob zw;eV6wVQSy!a{II$%jMG_odBNpDMrlv?)VT?S(p(U)cXb$5b;8-oAfd-$4Hs08IY_ zIvU&CIosQq()|}a)+GI3E#sQ?n4An%3j_yI9+hTcWQf8AAi^?`N`(})65NaFi5L4t zX&mmVwMCH=75xzPJw>m>{xG$J(I~zp-1Dduo_7!a)9+t%JX@P~bZ~xoe~yrEBI}`$ zGgh7tLJ&C#hy{Y2q+tSQDIqDCoNN-tiEW|+P-hQUh`WReL80vKGd8(i#29vmVZv=f z<GwB)S721yI<iO<y_^!yGzj@qy+r8Si)m#dv`1!|KjKtTEeaiN3QQ~YTE|R(R+}QZ z6*sn*&IYq3Sbvcy86EtKT=pos2Evn%j$|y~TZ1ViL$r3c(z(LA2fds0xdi{P>zS9* zJ^=&)m=zI~N#JEcz<2ip*Y|5R5jMc8#5L~EE4Aar{04=i{{=?$A9ImqRHG7Dktehe zvV-U#3&A|zEa#&b#Uy1;wuqkQT3H^AG5{Up3-$7t;gBdvQzRN7ncl37SAuISV*+o< zUA{u$SzM@@=Fsj>8@TL6d=L7Z^lQok7r<TgK(Z6fX#!1&7*WV;qUcqSK;{})u<&tt zZ@r#mnLRa#ke8-LpCGv&sj1tGyc|5`pPPfqyg$GMw+t339XXjj*`?d^WkXrIU<j)* zA6h9e3})8QN!1-Csb_ix`O~y8C71Uab7HoH5$rZJY2EbD_2`8S^v(@T4QmsR9qgma z{F!x#56oqDojsLK%^w7|l5JAiTKjTh2cP~Yp8U@3RjgN4%cHotBZ8Su1w6K8o_9|L z&dZ#B->zWDPk6GqeK}Rx_1sWkUDu?Z>hkM3t;5ylc<WpNYX;P~WNMw~NHl2Aca#rR zaj}{s=7GjcrsHPBdcuy`sPJa>tk-m@m;15H3YwI^Jc=bERZoR*txC>AgC13j>?7Yc zsr#0E9tHK2N4W(`0|a#y7ijV}8f$;WSS8TN)_7^XxOIW~7wEs`pv8r(Ktu%quxJSY zK=(h&;s49?_-`rf_(D72OnB<eU3)h`)8K(b5PRtG-H!Kg2f251<HeWCkw_$rA;T9# z<~V3wF=<`H^y|{O4P*jB&I10MRJ`8_$mDTJ6l#YgYBb!9(oQtwYKP)EDK(QtMpK>~ z%95O_lA@vOo+?VFD;0%GKjQ9p(?)_yji~BQ94uyDdOQBVe}DIW&rdxXGWuLk-uUi^ z;UOOIMUVSPzH@{1@Axr<)`e6GSVC;0(g-WVxY$HjRK_3`Wy_C>%gHV{2(>61vXE9% z818u}wJaO55LaOG%0#HC)tn2nj-Hw=PDU;R%Hi%k#hRgvS|}<-`Q{cs^2^~KJ>{Ci zhOH!3q#bh6R}2l|A-V|E@=b}?gD%VK4;~l|hlIV$&2p^B%FXKP!$n+`I3yQ*WY*;) zw1wLD5MJxcZ;@}B>&5T;8AY9?IKD=FJ-!_sH}FR6yNT;v;3B@}UznB$#a|U}@Eq}b z{ShknwUJd=33HfsJRqzNs*+W>E3Dv!X?^_hS8kPC#Pi*x*1sy;_<Noq%e{2g!OJfL zIv*s<X`#OeR`80k<AqiT4e?7Whg4i)D&q(O>#YJRsW^0=Qptm*{91LjtvK~OJ5-<S z(yU)Pk33ELlwa++PN3~*+uOFSIF>%X*&4@mMj(_~*J^f#f;+YSe@JkOb;tDTxE)fu zH!Jpn`aYo9(Q5VUR_r<Xa!fC(j}9F_g=$uuwhatQ57rJ|<UYP-GW>QlZ`$7miGKgs za#qQ0?SY}8Y>}bG8z%-7X8E`op9Y27M1j9h+>xQ&0qsGFBlJN{RE!sqIhq4yB4IRU ziLrr%ft&*S0dJ}_4Nef&0eTNm!g=WdxHFzq4jc3fdFTkxW!1rSc)qJ7aO>-pgr)1+ zG;#;j&>Awri1Lzdh5I+Kqu0ld<*&00mm;9yWVis7L2?Bwk>JixXVqm4D64P6_9<Gk z1{iQK!6ldbv>oixY|T2^_MD{OEo)uHv8zjlnGL}u|Maku%Xr;OZ~)vi*{yD}CG;i* zNtLx+8y#&U(ug%+1Rs`#a>M!eK722F6`AH~G-BuS?^rdjvB%lx@R|PcItXcMbSi|S zX>cj5%{T(-_VK#W%V?<vYhG-uH3Dy1H)S^8muJAkUbl2L-bpBCEG+JbD@GhdFSLx% zCS!xIAgGe5^h(0eP$MnB{HIS+O)ajh;+TJ8n0`uiaky?gO6T3PZC0PGZ93(`V<|ah z=elt+*Mucltj=n8dK60VyM5mYy8`*BYC@lC-D(Gx(FS_GO{sJ52IB*xhhnyGwr}Bf z-%3Sk5X#Vf?|;#R&V^@odEPeS5CKQG*YW(lhK1HcJ1sxFY=K@g;KSfk%!!8d86jvL zc;rTFbH$Tn68h#fA&EV=XFw&l{vPmRB3fc~bezv@6i_yB1TKYOSl6j{pY70Ywf4Ko zd|d3*w{!n~Y!M}q9)Ve^nVpO}3Y!q~?ogKO^sfH{*^WkL-3t5iu4B*NXnR&0iq03Z z$7-43jVZW;WE@g#b%h+%ET6m%sCAvqv6{`&{bqT~qD%qq7?eWKZ97);0XH31@`B1b zKZUCfXX_Ba?_0WEzxVXI%FMFt62J@sM|Hsf+g7*glZ(lbdmFfpQ-QJkvYTs0L&90l z%$8MdR~l;|Pd~TB>zqm?m*Qr-(ooG{uUUob-4i+nI@Q^uXFWlEFW05qM)St_J<Uf` zTE8AYqW5hzAbeX>$MrK4Hv=mg)FFOEyF612r>nB9!mv0m@yQ6CnP^0~pr6LqmQ52n z5thUdsSIO=A+g{NL#cH}oyh>0gO}qq<ZPoth9}eGRkq?N&$8LO6!zf^Pp(^blj7*b zx=FIUf6w7)r{CZZ(-BBo%EPc67%7{Cgp5gq2_sHw2Hx8$Gw6w(3LGUd1RI+=uL0%U zDfu@%y?kera1m-=i+23<6Z+#K9Ln>p0=Mwzm<IuR!trSM1ew_sVe@1bYZ6-_=WSB= z6L2BH&$T@4r=7gMV$LW~_%v6<P1e!>Q|Hq303;?MTy|Fc6GA3uKyR=`YE$&H3za5! z@X%5e>+NF)<CX&j*2hwdNrzC_m74?hcT3dTUnjy;_;G8D=sT=CJ?i|{McuJTZcU3D zdtsB)XUoTw0VhaLmn3o4nMLEMPej+fL(N^nq1u~5s4z!UucoF3P+HnHkR8y`r`zf1 zQKonLw*jxTih<)2G}p-4$Z>>TA}fa^7(56wv`L-@n4?BgWxe>v9tkqQJ^#0#=}mMI zfJtKZAh=kAP|>nvcvSJAERlzRoW7TpvQ<e*hmCn~Zg7d@%YH6ebTKZ|fQU&KLWRdY z32O(QblMg@q07l|Qd{3y=M9uLS*+%THQ_9-1?Fk6>tbEamlCJpwlg-j(`2flhv8&( zlUgoAtgzMg5Y~X@aDy)oHWrLx8fRQHpb{@)^d04|U-3Rc!yO`VFbs?hj}?fwH&|CR z-zU}h5RZAuB4P+J+<wBnLBgcSbq<6aQHm~5f;6%3Tj>&AFrRXFpjC}e(`jltPJ8|J zyX(2v{h;Z5m2HLP)V~}z)rRn4jB4MzAgrtA_@Mdfj@f4&(t&3RV@HIFVXk%F5YX0j z-bM4D0<L$$0@p<ed@T!58!0UlQh6lWTt=ctXbAwDCex_cI%G>3gKB;RZODVA-~P<% zv_Ofo03qZ48sz?}J5Vrg_q<}f`aO*L<K7yR<IHA1GGO(ldl|Ugi8~K6R8O*}h&{<A z;O)v{4^Vj}7bXI|%mL;f55U=0CXOM8Q&R<<ZuH-N@HE-(BhvGi8_I@=o!KZexG#A5 zgA^PQ=|{gohHE5-5eJ5zh;F&y%az-J^7+DGvF^3{%^$SOVs}M_AHs+LTP9qI^rGAK zA2K};bTLEhlgC%@27!rzN|-S!91Xh~Z+1W~j;q;09n!np(ar5e-aSHLSO>;Q_XL}2 zaJkV`K-p>(*?Fn7z@7WJ3#n~Y+5ViGEOx!>taN$RnN0MdkiO2<Dv8H$2DjHas8Air zyc8z-jC*4qV;rWSF)z%9uM9I$Ws&;*90lY>@0zJ(EHDNZ5H|}lRJ!AiD00hV3>+q; zTmTGMOC+401ArYK{1lr^Q1n7190JbBD_oVfpAv&#Y!A$EMKw{Iu(r1KYiywf2oax1 z2`H(2Lw9o;4H~IR#EIlu<tAz}WgnBW<?9mbEc*}1g`y(z8H4WhG#_hS%hix?Qm$Dm zuFf;bSxh9Iq8#qJ^Ys$k9oQJSO$b>~NjFnw39~y95DX|f@Z%-RoxR#+sb{Gg-3;*E z`z9ekI^#S=7OAc#nC)$RhC}Zn*|Y$}ExT#J3&))D%&z`V9*sVR&3mukI}6IFd3$l` zPWHj?EmU$uE`QwUyOBdMw5NtUA>rMkk~e4`rRpUpvrQaKief0^P#r?qwa+37jCzcy zr1wYyki)W&98jb#W(RYcR6z*R1{FBMlwl>{#j8+_$_OO-ppvjb9*nNV(a1mpSgZQz zJ-Bj2sAUL9D=esGiHzh^Mwz)6V90bT%r}%=8jH>=N4Ta%+rthDITW7TCp1<B$B+lp zYq`L70V0^=umw6mH=*d5Z_=>u(gtL$ZfhGP-g^(AL{N&cnGlykzh#tUKK-vdD=RX| zVbT<zCuNGg1SXzFOD~A=Z$U91Oq{i*M~bR=r%#Hyc(7+hF_}p+U(7MQEEn&=2p#Il zQz>aOY5mDav)tlpmB>L0d}Xx_fE~qr^K*k_Kne=k?rIgv-j^|z^f1sW?cw*}<thwa zvif*3AZ?W=(UJ}EVe0%9a}#6nk&W6Vf}&6@v<g<h`B3g~xAiU;!-R1Sq@M&5Mi*Cl z#FPNhYA+;hY%Djz-641P3&MlohC2|JB)5*{SQ^xn!uJQ5@>~L6H#0LcPfzR?`3%6! z<G>0Gw4JP-bB&j5Rs`u9hXDB=*0F}6Z!O?m>km6)*6EHvYSD1$<F=Ag)1st|=p?hV zIvZjKHM?QGcw<jgq*+XchHkH)vDS6k&}+Nw+-pS_gUx4MSFZTaYTmG3SG|M^^#)aU zJkrY3Jz*m`x%uknsq;o<epA}|ydQ@Z2ms>PrOx=p*kp>=>f**XKwH4oiMx|(XLK19 zz6lR?M=3s_<dg))&2nS04=S@6pxK1teaXc}(FWrEsz>dK46j+F9O7e=8yO7mRyIF( z0ZWW9O?jk*&`0hXB#Sh?@<t9my-7LIypes!zf+BL0bS$@o(+u*!p6ibw>S4)e{5IO z(yuqEe_`{6)j?CsBcc>MK5eR$>sq?iOIMh;%7p~k$s)&V!p^8;jJ$esrQ9K-eyKWV zdm?rDioQbZXQ-^YjSyJZOV?HCCM2_QyQh>~SS$zSCyR>tq%Mk@Gj!w%aD(3en3{l< zUBENj+3!X6@<`MFx>G>mznnZ$fXkl^(4FVP26!e!`nMx|)aMODBWs%-dnpDj$tuHf z?@}z-XhBtwvCf>DJH5x`rNhTCA`pW}=f-fp$r9E8z5#2fG`#cC@I?UAhXTvr@Q03Q zD>N(6`(F|7eM$&{X!aVPN?A;+fNiTk;N?`^hDQKf+-h0XV=gaT`@%+Jp+yL%@P6{; zoK%cj*^XRTClY;r;B&l-M;IIAW{MKq^O(s@7BLzl_>IkUJN8d!3X9c~4=VrWZ9vd` zA38Nz6DIhiB+vEihNnRgIgiRY8*m6UfNKJkv9<uny=no`M}P<W1I=R{^24knui`Qm zlOrJdR@{yIwdL~+TtgB^9Te&NBlz4Ay^)Ue$Aj%5`v3429DGT%-n$SgW`Mls7FsjD z=cf7h%ti0)+-xquJ=P=&yweTva`N$y66kUBEg_DXiv=-39!f*hVhjW80VRZt-RDD@ z7?&%H)-x_w9ImPg{8DM@;+g;(P)+M<r-Z=hrP--C%{O2#Y~1f?d3yHfnxnIM)gpd4 zxWtx;4?Rc-fqrDl&9qEm068L>g9qyzaJgeaSnCv<vichCJaJdKin0u^ZEn7sK18gF zMODYvKIwKS+%z|`ElzIk2gh)YQ$>@MSv_7F2<TEp#GWCf7VbGHu!I+ny&P)C6YA{9 zNH>qCAGkbT-}Dio9nhXf^R6Oar!s|{cPw74Q|)i9ae7<A-D7GBRAu?YQ(GdF-LhOW zG=v=(7BfM-i)|SP?y)A1(h#(h+LA)+?h-8PJRgS(^R^g1ra8|k6V#M(hO1@|f^4ts zm3jf0pZs&YX{?yeNin(Z8`+~I##rEKT^bf*lb{rQ(7;Ew<}ot*8<*mkO=T_`<oy=C zSk_SiW8yl1x;ZnOC=PnPlw@f4o0fnEJph+erD+?I$lF#T!&tK!_+>CDm!H+aYj^Lh z>pK4x_zHTcqwFfyf~@`avb%coiFR1??QY}Wo}RxxYI&L)Y-C8sVs55W%qcr56=xd+ zX<c*b6{l*w6$4O{EjQz~?cg*Pnn63e{YF?IAgT^r`gQP2rTK`a!Tkt96Y7WY8&gmZ zX80}nE;y|xfy4AlegWYZhLRNTumMMq7wLqV1xKOuXoM7)oA3xqQg@7HP~Z#!1F0H> zGit?l&F+ceFKV+*N;oomk<tz-{3Z=mSloc8pAo}^q}iE`10Y>EpV1%9u<TZf4QEaR z{LSj=ro2b~fphZ?O<>w+gx7B0s|16lI$r66D;^#c%ffYC((4##70^yi;6-w+c%&8v z_;REn(HA@XkrTa&3h884&_!}oH?7a@_xT)6kMD1Hu=v`x&(Gc;tr37DNGO-kI0a+4 z>2`^0K!l`>x7Q~Ak2;liy)aw>i!|L+h<^tdtIKl0c4fJI-jDK{7#_nOGbf6GXaUKs z|HBe_Y_CREBL@+~8?nw`M^qt>Nb0y=98pXdtvpZxja>j#;Q&_ETf-23N-*36M7d?I z#7QrNu+(&}e4<b@4EmX5QGv2A7+*Q-1`kUnEu^9HL^EX`63p~jz)CX(`x_eQeg(fR z(e^zRCPuj$uF)@siSkV2$Gwfi|KKiuN+MQ5I(<XmC^;#VSE_IhN)h1g4`D+&e)Gpb zv5y0^i9MRUeh~4sx!N0ZIQfp>X?vb#)VldV5OJGY6G_%_(%{?R1;lPN{&<sVntEC$ z3y+v*M3b}N<@I!GX6DV_m}4=fW7VEXKBW?-aqE~1@EaSNEe)5({4~K=HBHJy09R%i zXjt43&ABbO#|l^tX_;b%+a`;rS2f#VXJEt%TYpfNxtw0^e#jtXGnN_2k~+ABpQD#- z3xL;7Av}T5yMsE@P;eJkKy0l7ACM1Et^lh4I7JYkNB_G0EiiL^2pK_!|JMwk4j$@M zBt?2r@BB|HD%Lh52Fi_|L0TK-=X$Y->dYPDlvef;i(dsN9vx2m4J+xS06?aeY!8~c zuB+^>NJzKmSdHiQyI#0#6rHb1w$ms_d9fm~J(%!L?-K9tTvpH7Fn-m>*94!LeT6i& z<qMTjiHL~n77-C7`vmyYK#B?C)U^<$fDFc_9OX*xN+mBOQm_tpd5bL0hb$D+6XPIF z0>V?Oj)NEbA1cTR=jwPY(Kc9#m`u*st%T`!2o&ga4e3(i?NxD!@^&!Gu@rEavn~t? zr?$@oXW%G#OsZNy<p+Xup~V1j{CvQU3r1~SWeish7VEnBT1h^m$=%}?QG<fVhPF8# z@5h-M=I^o~JNt9uhnWM9H${}&L!kcV_PlvI0GWC0I4snh{x@A`J|DJIpNR41h&#h_ z`*VZ`xnbzQ@lap*<EZ!YEF_kMoUb>4GLWng<;g=Tj0+Gl05l|GZ>V@wsZbTe$^_bD zs1Kp2+n5fD=Sct=nTQUGM%~|GZn6$)7nQ_%%IQ!B|6bj`4M+N*_pdCkqY@0is6=n` z#T+vC4Bh09HpA8fO%yZrq*w6z_W?fPfafnC8wjy3*vqUG#mIsYYB>A4VTr<FfRFlA z6{n#TB?Ha{Sbe1!9#=O{&ySu|6O-AWd@F00(oQ(EDGu}4e05P6?>KwI)`S+SfgAMB z9!?7o<;30VcGRVCzQDRgP@lHE?5psjl&hq>BZcpnPlEv*NhR4|fM@QW>xcSd?`H{9 z2hvdtos9i{r|GJfeiEOH6)LfAtwm;5q*F#+ZL@dX>+FNEDO?vfId=Ri^0}_-ohKjj z72m!DfB+I_;gtPzvfM)0?=kEjJ;eii%YAWNrS%?}y?gdCC{>v6WG@R!a?^Y<9U&P+ zw5{3|&DQoyZkUMQN;RA?m)-g0%cLHE0iA3q&tMhM*+RU$nY&3Fn#|kZ*5_&&H(gxF z6U2@v7LohkuAOBCe#$#R>tI`B>5Wk~K)#~CXj$}+)S3<GzsJLT?ZwWd3s{2Cqyr9- zVg`j*z0&iQ1$9)(+%t8uQ>O+BoVM$c9xfa^$hfoR=L}I3*Y1aZIz)tf^HtL+A!Qtg zBq=fycd?MP!(!V0mQ&gR%P3v~o-vK9I)84=*L#)zus@nJLTKDo*Y-TB3Wt3<5piH) z8lO-{iXpEsUqh6mWR@l14;@}L)h%6uUrlb8Sl{LiK%3XUBX(MK!0-S%S99Q?;w{PN z<aOO&wqUPLe|&5>G`78deoQs3ey3j2Kr`K_UE&M5Awn7jSdUbkZq9~%8{m^Ks>5XZ z#+4g_)O#Z8ibVp8LDHlZa+;kUbekAyXoQA*DU|WMiF?vFd?~44)mS7n5O?8nU~?>$ z4o}FYF3-<c?{ACbUE9(?$6O#fl;B}5H6eIH)Q<`JO2T5t9}WfbN*D9Tr{Kpm1iHGq z-5Qqv@*i=eM1*XL+Q^WJ0ZfRV(+>FSlc=LOl92N<&_{wBwf&a7>tPJ!j;D9d)0)Ly zHu%a>?Dt=#8F-A5wW6SyS<7%~DD7m>HB-!(d_rsZP>J<HtVC=jS|NRXi_Yxu>b^5l z{M27@Nnr<Pfa4%8EI_W|hp0t!)KpuiS4*qc{n5_{boo{4j`i211Rbr|t11`Y+XIa= zV($x)9XcbTR;o`tm8iY<DA16Y*JZ2@T;>Z$8Qp&at`C!OmKFuD<VreCi!AOiCAPFf zaUL@T0=)uT=X6>Gp?$Q|%b#EE)L9#pzI?vqZ{G_3P#JRdtWn$0wr2Iou*`XZM|TA6 zzx0~2uWrHd+QOnue4dOoO?ZM3wOWkqj1}JXSA<Nu1B{mX28r?rgJbGURcb3)!AjnR zP&TiCwAm&fWC0&ko|<v!A8a<7v*MiM>na={Wx1LnXuG<qjZP$#=~k2|{IbaUGk$CS z=|B<ZH>jc@BzFtcA88=(0`f_Z&4Qwf5Y#{s`h(qA6hBw=A?-`z8@VVm$rCmz#!*NP z5Ow)E^YU7w8v+=hsK}Daz!03MaWy`FOYi;~nJemUgRIP5lF7h#*Srv^Mn<mQ(W+$K zTvk?Q=$0OeRL<W}l`}}%j@NClzN`jVS)lRt4!0xFElvLU3oP43J6MY3N%}D46SFVq zIg>>>5s=Y6X91O;B6G}GB8?G{EFT>U+ZRx)d*NDYP%a_^<^{A5SQS!xc*+oHh|F69 zaqNO%8x6P@VG)O9B!`SKy<gpHpHaQ-G=R<ZE<hb)>D4K<hZt2@FtVVY`7Z6GX0=|o z^!U;h6h(p$Cwon5Z@-{JF=XQJc67sRZ}(3gwCOMz`?wPlJUfatO)~~Yrft0g&Fp8q za#8(tJ&x(@k0XA+<Z(8Cb+*?`m#fbaFZB0uu&O8Oxy~pM80~an&=@`@+JQ?ZKncPb zU5}UFd?$m~pYc$r^n<;cj7mE%uOKs~+o0iH5t@s6{Fgyi*!e~+qww{07T~y_w=^od z*a;$JI!IB<V00VtC;$;BVs0H*S$gYx+<z0{ok1Sqb;N03=B&_TZn$ajWN^<U+2f3K ziHI=WMhWWLGTG5D$++7=6?8P9Eg|oYq8Ak=dVWXp%5!nR8OsOxo{Y}Yqo2sNERdSh ztx@uR(Q}rGW(zhuZMt?<VEq1x0K905FJg&=6K<AqSPS4nYb{v2RIpv!dExLF@XL|+ z#xzKk1SpFB7WoaP>E2K%XH2F-Gc;0gmPNy2Vi*Aj_8;-tm3WO(f7#xqlf34yFkyuh zdaJ8y?cm2om(X<+9R1k~n+%j()LQZ(gyb)BxseyCLZ{Vgx%U^XY4cv;!ZP{0@)>nr zw(5&|ksem}DEmcOa<U{fWxlMeY07rIEZCbJF6+hkU<&{c=Z-?Os;uj1mT~A2CI(c! zlb8v}eemc-X$ZhEk2%$kBM3s{)*mvi{b>*at@Vf?hLJ=O_|M4nVZGfiy<bSO*3<{3 zoB=-&s_0?#W*ABfm7o682=s<0-HW9}h^-uuQ=tVr%;6WT_1xYlkPC7eI)$ZLD`Gis z=rCI2yL){FY4D=g!iu?2!tdIn&I>_|YO{tIC(x`SPAJzA%oXP3QPDGoBUn~P*a*b( zBr6N!nv0pEL~!Jl&6O=ahogDiHF^#DG(}X$KtM?ZXRsDifOsb96Kuy8*7y)@%>CiO z(8o+V_(HK-hV7$N5JgDK(GUSK*<aQpG^fJ&`I5JgQ!YRBiCseNp#OsWVHI*W`J^k% zBzL&MizDWs+aJ`J<9%aDz*`f<2QWHsDXU;g#j*R)4-FcG>UK|PB7r==(c@@x@LD)w za?ZN<x{<PWSjp(9?B#|(cx3N(sHG2J1U%7tYB*6Csy?G=l!F$Y&*C;Pi##B^OaS0H zA|bZ}&-uXOdT}`@+c*8b0=Fvk?|3UJQbhLvgXs7Mj0~|?K4h<Gq0Z!yQBKkaazEvO zF*N%DG>sYxwGb#-4vk8q?)#yi9(4qL`9dM%{)@jE$ndkI!^ZifJEXdSgBV0*0BaLF zAIDBgy8XY);-F78{qCS?pVgS7RHXb=6~n07k$b4oyg5SP@3ix9b(}OKGTa1Z40t9A z)q8?y;Arp^kxdE34B{d-Mh1$-f+D<7iRB`UNG}+r<zO_^jiHRGFF7HVaE2oF(?_g! zVKw%2caEefZlsBm(61Fg<#toF&q926#vsI$xu-A%D*3i;%eVT~-3~d-TFYjYE@kUx z2k8ofcOi3E)S|s{hp9g=t+*-sX7;!o_7y9DKep=w^Dwv{f8;t;oz-&;VyLZXO@_Tq z&5I5Ip)UAeda0W0RBGhY<q&*xB5=r2`xmnbi%p@H$ZGV3cL?YcIt|o$XZZZ&G#gg) zxiFN#NgJl|G1Vyhi3jmj_3@Nby@^tfDsPaL&^5g=b4i1X)HeYTHv{Gk1|8X0OAzb3 z5?{Xs00|a0N+wM*Kpws6Y9Qzh_TkM~@0ta)`3Y$sLg*f*E9etdYT$^k^{?7{OLnmm zSAt2tF@^__SA^EiF4heJ@m1vkYvXir!s6+Ir#m)!h|LkJ8?oFt=Jg8iky|^ttXyxE znw9kIwr0gx?Jq?5EWlg^r10iMO#tObsAx^H9VA}mR>F*VQGK@l2`{=D9p*^fu!qvs zJow?O;9#oI_*I>~nyUQTpOs7HEPzgg_&JS}P-Nc9@_n>~dkPwMQS}v_1<Vz<rHYJQ zmCqO#NFTfFsWt1sRv@I!c-BhP7Ql=3n)wsj8a3ht;ot-c&>XE8)D3yC+_7H0YD!Mu z8|1oN<xB6?HKO-581z=_jL=6Q|IlkWTdGIXkr1AW!V_Qo^(R@6Z`mABJ;strVEQ<T zc;#qTb^xXke@(19f56sPQPL?EbFf6T@>C!h2qE&D`^yO5n?_$Q#ug{BBDYmu9~`|; zhLnzGHnTSyEov#m;|QtgA->9I3*OKR7Djx278Y9&r;kF^>k;-?7Q2F*Ee$AaWbHq* z%#Dx=Fk&)epztcXi=b^<))kQ0V!GRU)P6fo2pZ!mF2xjVsA=b>h!nlv6otq$!>fe7 z;etBg)UDqBC+!k#G%j@vD1Ip9>iyRK6|=qCruz+5xy+>m_IlsJy|moBbwRd*c%s6B zospyQq4Jtwh+c}tSJ0t0jXQR{tKzY)2YOx8J%tML^oh^efy>`pCH}PONp2=|c8QPQ zTCS&IyS&QLcAeY-6m-J$e5Z4Zj{Tc6p!64nTRb~_p;k8~JtQ(1s-@Mq#kV2}_~Lk> z%)g8KGI>;)<C0Vo#doS?T~CM$_9_pGka@|}4r&TiFV?_CxzWy);d?TxJToDEmPyMt zDIE}fqP@*{jr^v(1Jz$<Z)j6>?7(p(Rx<Z+UH1(Zb^MoUcX9fW{Nsx=O|83V?PGkE ziU*_LZ9!L64dADh74Cu9)rpaT+Y}vuK563-ll5lXKVqbA$)#$=zAjh;dMUQ`tetNv zFMfd(T|{%n`8X+rVMafSgO1MF^^xv8OOG{>v+%d|Dt-&PzBPqLsrbtAsGbqDvBCl@ z^n4bLQEYAK@_7N8yc2HGtg#BK`5`gNSum?z0JE6}cpp-Setud6vbT_wwG+}CLSI`H zG}0&lR>IcxnhWaF)`_LF^dd7f8;%0Jo&x2%ssVRVa|lFmv#_COG144-5C-Jx1!)tX zC9IFkNDKnAAa8Z(yI~wgq<^;Pb<LuGn-4e)=mcH{)j{syGLdMV(0jmTI(r}hhr-5$ z#@a?BcIg)d(LHx|WJe?UA_0BRNr7yS8zT}dn~5Dgom!H&$HQBS#Bg+b68h~c6i{gk z;<dmYcm_=Q{20Z@>H(OoMmH#%F9*SXF!{Z!y^x{7<{#%{rMM934d=f^H&x<q93ZfB zou`5H&p5k=paN?T*oC*a!{}sTvy?^D@3hC5X35;g;9h73mZgN-dVs`mOaCr-h0o1( z)lIz=>dbS~OrCDK21YWVjg`!EP7nIK;4uApiKL@03HdJNqM|YiN!Q*N1X@9?6Q+r4 zWU?UIfl``F?#SJx=x!0+qenhkXY>$1LYE5z*J1D}q|tu=DJo}@k==p#VB}Xj<+j2L zg+RQ2-U^H=V8L-cbgugIm}sBH)SzZpVnPz5Xp9gdvB^QTHi2rn78F!q80f<S2F>Da z^f)!DjfJpHV1|>jAI3=!pJR@6=BuCnR7luQai$m+b=b}GmrlyY6N=2eW5r@`v*AOP zJ>7ERX4`3ViNKs^vltbOr+k=0*tThmXQ729f?j~=w-8JA&Al0C{;0f-M%Nv?+Tr&_ z&ZsMbP7Ij~CRW4@3EUWpRg4x#R>S8dfav<JEY;^U^{>+rV4NlEid>i#F9z+S_|Dr| zQg(9}CZ7G$GShl;rb;w)GLv%NABjnHDfU9{i#HH*0M9KdLx!r{<6)LOmkTu07DpSj zwY;oJLZ~{;QrCY6U89a#dZI<Ohcxz8BMikQ$R3GX@P$HjW>ZRf+uj!V>4+}o5~3us z4qltS8|S@ZT79Iu{pnx5C9C}hUIg`-f~V`Al~@YUm$%tI=4!h90&CFcxQYcwI9?L1 zk48rXwO51?`~lK#*M>xA0ChN%(OY?JXdB8?o<6(g$nEzQIxOVn{$;ZM^jsSImAq2k z!?6dO1m5sHHaU+UB398zUs=iR74K$(EN>T%SxTy3t}91{o&lAUIUF9d3Hm$|`rnF6 z{L6RIkJ=OBKWbmrLcQ+{J?~eg{>Oy$W}_Q4=jwce>Oak&lgQ7hYe+xI{=;?6We>i4 zr`&N;m6cD%g_;XzCU<fKb-XLFrPm`xWy3Wn0qw;(OvqM^yd`g%UiZ%j-uMi`&#)|! zn^tzWE3m#=PS~SjQAS6O4VoZ+xaishsRyca|MoObt$*rB(H%QciOu*R5OOsx3D_DG z=4F<A^`!=icd(R{&6Fmy-jhr-n1(7t;}I$I$?ww)VG<RBIm3@Y2IM_RarmjT<}A<s zfbuemH#mdhC&c`SS~!DXfbRxJrt+j+?`(5pM!QNamiKqhDtrPbcxXD`rgF)T><8%C z^oz}!rz*j}%E5=UYzCp_FVcjX^be5<7A&n!))wPsh<b}CG~NrI*a}u5V@Ig>6BSqT zD=;M4#S!Dh%RiYEU#u-X-~2q?MK1ef{_J2yC%m#RWd}^o&U1V7#o!i(2aMk5{F#rN zl_Yw?Nc4o6h$$KHcDH=w-4*U-6#cj6JK0yEG4Ht9wgq%@)`b!+7vRu~d>5JDS(h!! zgAUu<z2rh0SMElL5lh&08X5@*o(ZJb{zK()+Wviqx{Vkuw0hj2+?Ag0SmpGrHslQ- zHj1hh)-6jBC#2P!gNrLt0I}FzZ?Sd*9YjuSJMeZ$c3_dRoW^y}_y-BQ+X2ztL{Cwn zWX$wYCUdZNQ#EX@mexz~@H#bfp8|AvHU-dfzVz6FxF?+0={cwG_TWOT-al7v-`U(n zVDzZ{?)llp0f;#O?<dQA+#yUmNcp`#wPVVBG8(SqJU@HhL5mzv*Nvh}aKxwhCDiv% zL^JVbkd>R*kNQWhm6)BtXvDj|(L)_e?d`y3*Wh*1=qkE7`mBBj7d|97(qfrwEhYGY zkxA-|y2vzqQzZ@H+nurC`EPni6j;I2!e6|CZ@}gYt{Vc5P*7V38SXlNC2UlGbp9+6 zl({sp4qu9^7xw!1q=-(`ZGX9Y=b9$83D<M6k{?hse$o`g=ns}uUK^HTPbk%7i3tWp z{g$C=tsA{6<)#Uv@<Q}MtMwI{pA!GxfH()`ugWNp_B8FTsTYq?1Pp8?S(ksFl`Pyt z9alLu6V-=5tqQfVb+3Ta?f8c%K&QV%w8@2xR%qi&xiXcysPj~qg&-f@ni4U^i%w_5 zJl|x=p5?UJ$^ebgqal%Rg!`i>bw$lEXmd`V7|M4=V@G7aw3sC#3pnKNQ2vNl;<DeX z5``8q1Dw8zZcf}HZ>cgqP8e_g5;2&`k&?#r-GDm`K66bDrYVOBmerw6lpc44?cz7r z{J8LO{ShybLP+|p+$+!5+bwJ6`gLaech}iX=t9*Qf3(X>&E#iwI$+A0?DaDB`|HE6 zwAzifj@D1?E%eCXzRZQZk~#8z_9%uz!HVn^kdHj_6bK#8wY5Y^!jOc&poH5G?d9Dp zni+I3=#Qzu?9U!h!WDjzUkQSLKY>e&eIqi~yUrF4<LvE!MidiUh0VhHz{jmoA!l zc6sT}_EM7Kj#!PK=fY&xbp2zY3>fSEmaJ;k-|k;r5%_nT;~X3%sO>ddT=CcF7W!fU z&}pMbCgdw7)NZo&@A7&Ej86BA|LVz9cYED1k*n+R`yco=K{v~g(2VaO(I#D>v0{b1 zseX>pc`!_|U~_Osg-$rqBA_*Ee6*v%9y@$;{yV`wLNuFu<o~#b`YB@D6{T2ghK2k| zc^^AQN;gwt>!y;O)(c=_{24w!f8TKQ{uUPlAEl4a#qRm^|9||SRQ?ZP=g=hzuQ2Pj zZQHhO+qP}nw%xmJ+qP}&w(Y)qc)xdY*2*CH0a-~ZRZo3O=UpNGtIr|(-?=>pLnp)k z`b}#zwVk)c-0XBtq+mFY6H+Lqv?S7O=Cp`tH#$9vIsU=A(-GZCl9w0p#0TKO2_g>= zFxVK#AS1n#b>tc=u7vTDcu3+aNcsp>J?HQxP%D)@$E7t=(|OGFlbq$)8PH>OQ!DQl z&-l)u9X@hyeS8_TsZd|lf3KtWvdypdH231+e&P4|9Z*MYMlTeorqwjH4P8kqs;X<r zTw_;QE3K<*nu1}f%rk;)b2l~B=7hM1u4t@J*9G%d9*c5|-2zvji~RFiqOS~MR>nlS z1Z;y>U>E2b-6C;gnm#y`abjD@GI)nxFpqvErm(AZ&A?67=$S{T$%`gLOwu)cqc)DF z^9;J~zEDpns##}pFkhhbY|+4%=NLWeKRnHbGC0kKnsf->wMqIU9@-?GB1!g$BPaYU z<PW>+Fw^P`UZx0&Ruov|il_-H8N9PZ>h02cfL3~fxwgw^#eP+E?y<IP$r(D9>UHhi z4<fn<b!7d=u2?*d`XO=c{8lX73+2z~uN;2+VP0{ZBiW0Rb6YQ`(WAA!<ILH-h?Zcd zOK&~pm|bj^VE3S><M2V~Xh57Z{!tNIzQbUJ*&Of5xutv2x%48U**33<X7lObrfyh; znl|pHZO4Ykf@`7Q+Up-MwdDWd<UX?Yw!^L6oZ;<r192HGtg`)(=|tOkoCZ(wh8kL$ zd*7cdi#u*Z<|mb>PBrG}1|Hz}mxj-#&2`HzMU3Hh>LG7WGNR#+rj>o_J%Z>MuBEm( z1H}224JDfPO6N$~zFAS=h`G%cgBIKjon2V;8FU!5K7CnayQ09%{qqBN*6|JSKe=8S z?DtPL9;d;yH4WI-$HJ$<vfC$Yk~i8ixWmBghkEr)UszwT(gHSiO<%m*?+rd3tcyPo z=?9ub(9w985aVq-@vcv@`mF8vG_y|2+2d|J(!z;mU3KZZ%|rWCZ~1ws3rOOVvfU+~ zikpn6KF-i0S7%3+7INbypEPr1$v5Jhdk(yPa#qh`-8>l+#|OgAF;mXs^LD$Do0@3Y zn79piJ)BQz!mq2Z-3MX>4A!zLRs7X{=nv3x2CaKkF!&XPMzugF3Zsyg>qmRlHgMXH zo(cp^%c!6S{<?0%xxAxw;=`#dc$aBoR)14YXNcwiBEsD94aD-Stlyh<cYXQ9<z8Hs zjOtxfrwVrm`nezc93XB1IsR&#!M`!TCNWaW#}-+jXlVQ?qn&pSGq%w;{fY?{%SYi( z%TSjRDf&(#u(@FoRyNVFe<KAAPX@UWx?Sa91N6h2COsk#`}+_$Ny4}eeAZsa=vNSu zT+J#vr(l>jP|r!5T`(7W;qhcSr#VgbW^wlD>D+<HhCn+H)}~uGAm4v44}k*!tw06q z%BKdzl#Z1t@u!y~)=;?4u&2HA{&=*<yN$oYv1!hayxv0~PDZ$r*^v#xvkh}}qjnAO zHNK_wXhh2aX?Ro}fTi|Uv$pMMYy&qRpJk8(*=3W?r7gGAp4-tZ{d4CZwG=?60WZ%5 z2LtCp<FNzRTn8JEdA5Kff?2jR_c~`kb(@Z^n!f=pJxz^`?a-!p!zBnnL|aK^X4GrH z+1+RdELDK_7_cvHX!%4h2b{!aKeo@@2Q{Rxr)S4?>t(R@8tlMl>$!7`J??g=;l`(X z|LTU01u&!yJqr?t9wBYkUGA_Ol>RI%?U~eT<aI%Qx%#1ysZb}_T9OmIB}qxiJXN#h z4_Yeah{7E8KiV@>q1b6SfjwVlb%jL!P*v93HYmls7X~!pafOL9%0J-#i$zOk=MTtF zTP2o%L|2&9VYJauT0?IZT3>ur`4v}T=zbjI5E2&8Kx$+2OG**-0{74yhmnlxU(*~H zq;w@u(95MFzUXJ?BEIlv=%OFARr;upEsZ{si@l*v%8T>{Khfnnqi?Jg;y|@8Uq^7) zS^j=6KzCr-iN?bsQ`|SVwpiDpM!2rn*6!pcnk{=RG<~V&A^wp=Ml|bSEh$ye%3-yD zIWr2)b)66YqcsI`I#`h!8Kjn<kF6rKcIGgY+#<EG3y~&(=lVR+2w;tVuec&j#0KF0 z!xpK)@{F(4hzg7G;ebAXk^w>ja3y9@SBz8zbOU37t}D&TbcZ*wXB_tV&-5s=FCORs zOMtfi9yaVeS&;$H<iT-|wJ|*h7cADhN>a2hbp?TL4^cN8%7_vT#Y}1vEu{s`49QMY zMSYEl1_pV!0wqlWF0$kG=>|2#aEc;v>zEdpPDLRBHLu6m;uBD`sg=q0K{3@D-by*A zs5q@Nc0h8sLrpLJsx823hibBfOxykrf;`e=FX36rBJ~1JA8NYix#6QE(YR+Bwy~O@ zEdW2k^?kz~01hcneH#{=E_)&C{Sys)MQ*xIL9Mx{SRi#lm~wO_6zo>Vr+~F~+0%({ z*p`C*x<V9yMu0(;YSE*oZF`|qI@??}FW{&n)=0Ixwy!T`u#|&0H+c|m{(lSHn8nt5 zkkspP8#JJI=^_+_Nyj6&y2hFzq%9;2^c^jCxC2`u21(`a!sGT6gt1gNNF16;9q5xf zP}cc=^LE}P9T~=ghe|qv2RyWVgEpll{<CI7roj}$tL_XLqSuYR1_xk^$$feSa8IUR zsE~k0Bwa+U&sxC>vKBwt9~9Pi(LOT#VzSWFfV3Cqm_BL2eGfy84tr@Rl4nS!E8lc4 z{9Rmy%cBzBvJU%Bp;TWhnRxO73FkV*3<oC*ZrJqzTku&5ZWplniPQVB*R0uM*$T^_ zaEK`^N;Wk&;}PuD!<dy}S6X!np{%RD{pk2)Dk=niR|P}RX+|&Utle@(U>4SuJW>m* zXt_S;vPdc|$RiPB;MQji#A=icV=~P7Ic>{kxfteX4ksyt*d1q;lhAWBB*Xz^s!w(# z;{r;%op8>NEoY-QUxH)+O@QBiVDp6=eJCi)`fr+}U#d%j9AJSVZ?3`oMQ!^WE;N)0 z`jO*cUrfB#J%rTz(6@Azd=s!`f)@fBxy5efkb)SvqX$CgKfD-nA}sj6_5addJWfNr z$d;*)A$6xkZgWLmK8<AGOj*8c+Y?_8T6aFoonOgd?uq6ZwXj5=9p~?a)7zmIAUCjR znl*Q*Iq)?#e38o{joQ|q!%nt8guC65pkW3v-vYpdFJ*diWLV}~KR0v*4x?_ZU0pZ} z)T@XV?_@8YVWF`j&NM#&HC)uyTGv;^{Z1M*vlA_mrVsgX28j8>_wY2NQKSVLntyc# z)-`RR6b^H^BwY|KjW8#r%+T)Is>PNT@4$^jYARk8V^~H%6#8$#MV*}2%lGAi&|+jv z^j8t#y%;Wc#G>shkRtD^#a`lkTY4Q`t}d{{qXGQ3wcX*q>Traj3bp{#;6F1%s0?Aq zLS>rNbH#N)sXZLIeh*RZ&|P)&_gNINPTp))aBd`6nPcXyoVn=|<irS{s&gzU5Pq4d zDr7$9sJOo519r;_V(7>)c&*kgOn+&Kd9iZhN?i~UwwEsH@8#}zHh@zN4iNEzLGcl( z`tnylUQIw>5ggBFcqit0{8!oGIiJ6qSNp_)j(&MW&qcA7MTNJJU2;mhj@Ul85mvbD z?QRTTDozg(2wHPp=uX!y-4?v#MP?_R<3L!4l_?U(6ftW}nzz5P-jF>taiN{KOqBK- z-n(N*2D0VAuAns*=Wo8D?N(WA_c(@;wx1fe-5_S2jgG`)tgU>n$kMMqXvJ96hLad1 zEhT26YbGb>i3UUOkXSziKX$7G@^nb(Vdod%+=F_KJ$9G)O5+y+Tdd-YEsic}I5!me zC?8!MeecJJw*3O5ka$Y@h|5BU;?}(Ly#OO<n+bwe$LgsL+3{BoG?=hHzQq4Q2!#js zESMZqn&$v^<l(EKW1hbRD+TYqm#qTNrIGRs7iISJZ;D%d#iG=fr6cJ0bbUkA9+8!V zny$g)1Wsj;;6XkSs@YdNw{gXcc^ZG!Kb!(aK@Hj!MU8CvJMet77(eyp^SD@80@S78 zu~sZ-cZL#|QD1f5pgRu${7Osb?ZLQunA#TW*>~|@bhLZ#$KQg3f3Wd$`(@}U7D5H} z{t+&fw(upszEAt5sd<r5c?8rgER$x4c_Cb*C^Pfq{7M*ZZ~y3raFXz43`ba)0KTg+ zHAZ|{dHfM49zy^X4z|EpAl)ZF;84o0rvXzwnU<4)d#b0>xTt|j)?|fEwmgV237kK# zjq=?uG1I)vkvSxU-z+~V+LLVQI|%t5`;J0O!@_G!0|<KwBkb#-dwBC`a#!oXQPs;K zW6Fw`V^GCO0IIxgk*^gdXFeu>GX<18KYvoh9G!||uRr=L(eqoc#!Dab_YgrGi|6R7 zpz1gdYdhHT=*#%jB-A+{8Us&;@?Q6fyB8yDdk5?b9oHZIRspI5Lf+(hKp3FC!2cdj zN?QA}Dw}$BF&@pjC6%?vydf@ASnvo>VJi?F(T|tgBAtP>r<g?F<j^rpq+gD~7Dxt0 zBcGdy3gynToSJMUNctE+8Q}+7N{$mgB)Zn+xQ2pxQk4`5pX6l8amDe+IHxvj1eqqU zk;H!408&^aYK)gAA>w`r#3E!U4~|cBj+ycP!TE_^CIeGTjg?AlmI21Ol7-n4C8j$O zdz^|8p|BMQq~kZgdQs!SaHwAfX%#v{ezRQej#h(YlL!xCagAUAh$JHNh<f+FtIHc< z;h#hfuk}~Z7=I_2`!ISb(E!#Uh)l3kLgo)g@pG_sKgB4NNy#GuU^Q()3%}nuiIP~J z3#|~ECp&$yQx(A+-64jkIl3y@+qFy*+Twv}(?U$dj4eBoi(2>n39+LE=O_LfV5-H$ zZn7yYdjN}<PRWbn5Nu5=yjW}l7oBwPZgKOIU|GsKn`ISW<W=#}WBppqDcccRJyn%3 z{yGgo4=MHfW0!3P(vhA{vjN=!@k2AM#vr{o1{U9g_8Fiu(^)FRfUspACq?l_VE6J_ zj0@og2~FHgAO^mUWENHEmvF3Y?myoxa6L(it*2)x#Uy&(AYa*Zwi2-4EA@lfX#sNH zFxEQ6FK8j6JHyU?jGUn}+=%xZ7g*113R8vU<ewrz9DE<d#bt{urf)L|X`|OQ`K?&8 zBo@FCUWD{)a0MAQA#V=*Me{9$9grWOFFNE8O9~8w{($ena4bCs5S@6q+4bVRvSF=9 zGP7C<ZmlwGvU^{U@q2WIZ6VuvZ>xnBLEIRzB^64o-_?Jm#hJ+p0|c-Ul-Y+vL+s1T zi``M}WlLjK_DFQwYpC0{eF@u>rB<sYw^GQ2Qg>mI1oYD)>S-Ty)cXk6$V~$spQxgG zF0lbg(5y}>Kg?nIAQv4ccpwI4xY(D}(NmVkoTGFY&WDT<bro-y%eM1xZ}<%?{-jSk zScNVgI&SKcv*;J3cjeOivI69&mQm>8K34si;LG`gd(3GjlcG@aI4lBtg%aB#m>;v5 z3bbd0i$~){%ORqLVxSilLR%TN3&j@&iqg^8rVA3dMXw~bqNRy0KsNXcDl)Unm0+QM ze#6HHA^p+6kZ36poRTSWBEc9S8?3)ae7tSFGwqB4bj5kmf6Nif7+XGc#po(*g7nHS zpD@C+eZQE`KL+T%Is}(HnIJToVodIH=U1Ig-h>IoGCJNGX}q5JLi>QM`IeI;$CPYH zzLu;_I-VU*+l9g50G{MNL-^)`)bz`uKFAnnIMyui+;nduFpArB<((*esy;9R;%RMZ zW<zxMJq9!SaCwYk-FsL`C%S_`<rQowsMl63oFv9{>(prdxN#35F%q32E*`T7NWDL! zjt_MjYYTy%8DkiUjZ<QHcBFgR^h-bwaZWD!(LyDCLyCeR7AS^c(Hb)20$ebLo1}fS z_zq^-J=Y6~AQ*>Fkd$lYB0hKKZNVRd_nhCxG!*7%6SVi&M#R{+A3NUiA}lSa=>(>= zig}6@U^YE;^>y{MD^A<c)Y)kPvb+MVAVi;uR3i}{^~>Ud`c>!&$ZG0rs%=&w^ZeQy zHMQS;n(W3$7e5xo+d$CSkx=6nZFBnQdxQL<_LPG01rk+<345zkRvMGO<S0;Esu$Lz zW&I{l^w~wF>$WSt{{A<otO`pqcJ`0>gn;_LbILCE#{bDFw`k0`ZLK2qq60|Y%P;p4 zYr7@3Ith)HZV$WauE|nQMIEh{>Pp8VbJ4*;=tva^1atz}LW=8E?6|C;pK<QIKz@K} z9)o(pvFW<}RejZUH3LwXkN54a5P_o)gx==f^I?7rgnsriJss%lb)02>u}}L{KKQow z0RLxnU|t2B%B*2XZ-Sc}g}S6*QOm4q3>@XcI%4xd$$+gR+6uxHCF8hE&&V(ccW}g{ zKT{c3%hWZ>#cCqgD4V@vx|Ct+8svg?+p9gK{TZLf8`Le`SAeyT43BcLz<RA;s22A# zRoz3%ONcA6&(c-rxv6>Aqv&Rs2k+%|3dOU_F1!Kxpg?HF`|y$vS$$FEh47_xS!#L? zJmMTmv<@pWy2y@Sd&;ACUEAAq>ZZjF6IRXwMufs_rm{yUbW0vfZ7Iu^&&ybigDAex zC2#(N3F-T6S8ey9rUUp0T1$M44W~Z58SD+ecC`8ZEDNm0fY;pTfy3Tte+j>aU(?23 z<Aahy1LeyQg!n)+(p_Bi8NdSoR1bUssfP=M=P=@kSO}`)s3T+nsD?8n2+$;F3;|KF zTfiuj0VGjII?B%#Pmu)&AZ-!AeOZe^P)!?MrhR<Qw&sxS$^d5!9)mfY6-y?bu{__l zFAN>B^~s&An(@3h*GW9qqTbnx974NxFXp}WVz<L$x2u7utxc^q=h{gPamp7n47FXr zx*bmr13ZX=HA<@^Tlidzbyby`>yhv4xSo!*vZiAwMG)5SFvMnxX*M7Z%4ZQDSz&k# zg(mki;-N}PbyVrHtmL#%X(r7F-sB&M>!5==2p-I59{pBW&pp?j&rGYbAs0GPhjGfY zvE#9u+otmxJGQY_0j#cOtIh5z-#sY`){)!!M_cnr>$+5IcO;bdJU*=91Tg(5axd!J zmC|=ZW&FIIBq=-Rsn=?=H8JlKl}nw_UDYpe?Hwf^D?-$6b|c~o29YzrV`QH8?jk`C zd#)Q4K!i|$PgG!jqPtE0CK{o8#xskql$%YX>{P(W{dM4cU_O**WkIxu{2TC4abc;C zhs=tnhjh?pNz8rE;mU)_AEH;imuV-F15BA$d#ImPE~v%jFmH@(Pn>|Pyub2`r;ZxY zYuRg!)R+O<Qj?4UzcB<$#2nyGJG3V(Jqxg^9vC(H*g6*1LS|P08e|h-_L-Fi2cidP zM9UQW&CY58j7Vmi6Z*({*J3_YX#dqh&h0Q2*$y9=0|PdkZWQQsH_DS*>!T-}HM6o7 zIQ6B35|``Fhtp%h4((6~Kt05fHC#xipnO!cx?gCtM7{K>0Er!1(koARNq{-j?8Ieq z((|7QtrBa1ch1}+F&(Aga$0g6cT36H*M55aa(sQGSVRXz16{e&spx{-T=CicR#Mf7 z;ssA?(%o6L@GEsmqi7i<nD|xR!w+!!k!Qh-P&S!l#*_CXHLZ8zuP%ePFPa%9R1T+! zM7=jXTY{l?A17D1#qn$%PVpYmoqa<ckqtLgGP``v#(K|0-ZfplIi*?r9x^jQ!upaj zT`w{t?W)cht>n&<+pr%&Isz}Pp#6C+!far}XsVp<A(zP|C*DkcVoltRomvB{ArCBZ zEru8omw^s*%ueEYsku~`;b)qm#Fe-c(hN-&JX5dInZ^BfSe#qv@fYO{RGZF`Xi4d6 z^QK6RPSq;eEE=5r#;+hpz)8}0#+eh5J&+aqItLDhx#GfF<BM(TqHU^1E#)sErJ<xU zAHfC29~#GkeLu$nGhkY5l=`%Tf^oPg7K(;oAXu{UyMcn7a`+NjMQ|4C2BT*q+p{T# zRTyb4N8zZQL<k{6Y>|rg6W5Z1R~T}XU;rs42q}gGxe<V8Lk%(xEO}v2=OEkmNhaMk z=t=robCr4>W{51(BK0z!Rk{bPup1`4>iyVO-!(KPy%NnM?tB<lCX)z?8AXn%uVa4} z?>}_%RrsX&ONbc>jr4%%&S+Bnapl+~;qyt$Cx&5G9Dx(xSsyNaIkV8z6Mv{K7a)sA z7r9sNsTHU>T_aK%&uP%{`)_anSQ2;slzV5⪼zJ(Qnb)U1Aqf4&BG7RiVm9^%T}K zh$+GBe7iX-=?zDq*eu}MB9=N~I_8Mo2QKhJP5l8J9LGpvW3R3ixtO4~K!LIX2yY98 zER3k4=v(X6v29z!A8lz7e~nx2Fv~8)R0lrTIPYOXEP!#BiyQ{v^@vT7S3)pL6-6~> zowDZ1njDEH!%MC_8uiOIm8zd}PE<smXN_5?pg?1k$-xU-E^kQ_63F^qX}uc_a){yM zfiM+`tAzY`^^x~k2m3%Oa8`o(N<ZW%h1_39p@eY)g?)IVE%Ho53P)pY{QDEbhX$D| z+E3b<Vt#*qJ~k{*ICSQn7m0r+0j{#_rb32(?#X~S&4${+FW4rTjWn-RBKL%!R#a}d zFd(H-;0bWjCZ(p%^Z|Tn`>|P94`SI&>Q+uVuCCdahI^Q~{=rA9kboeTd&3lI%Gxmn zG+iu>jncex>%oz#+WqHAc4->3amhpb=9}5sFiPhwj{MZ&w?JzC)f39U(Skpb#+d|A z68B*_HPV>;<IxyQwrm&B2LDRn>nBZDah8)mwrmc!a)b2knijivTFC`X$z?HjWsI6F zjzc?=&JU6a0)>!wrv0;%vg8p7%P+}EWoQd&2*1MphR;K|m>Sal_LI=j`}%xS)pujH z!Y{cpi0OCg(tB#n-WN9(|15Ft5BI?q#0f{9++X&rz;H?p24q|gQY$iQp22(wrUfjW zm8DrhPZ2AV4ZFO{lxo|h#}H^GZfX_{r$Zu%ghWs&x8p+g#z=EMt~}us^?U_L!jH17 zk$Z!ww?EX1;}h}s`#Fhp@)JqCb%{|0d`%+OTzUj18Bu@b7y}!M573Sl=eON`mu^(X zoq?&hCvJi{f6}Y53|}i8W9O(~e;8GoKuz&dTw>=2j-XZ9OA2QP-$g53pbbv<3mw!n z4;PI1y5d)k9F3~phuPv?D;+a|M+G17%+C4jG!GQ}4y(maV?wM%^r~SPD7mw(CD`-G z2rfYG`(beRmS$@Cg<!D+<^X#v5mOTgE#G74czJO>ap_2uXtx?eS!~thz|eS8`2`;- z!O9X@GoHZnLl`t%Nv*n6c7}ivY5_Xmn_<3iruo<37<~dA?C;LNJ)7qWB)c@z@DE}A zB2L6D{BkT|BjryaH)_qTb1DQCRbezfG(@qQ;eJOp#b+=(wRNQYS(4i-66fhTX{E!2 zndaXKAd}E+Fit48UrdW)3McvtU=BYBc^^r&dom8l)E9ihN;62+lhCbNYnooL<+mk= z-%isVmNM|hce0pD`pXs-qO1~^u&=IaegXe4+vZ4FQNG~ceG!Kl0N~#MFgCNXG@>_l zGW7ENH#4RG|LZID^)2lzUG(+;dvVl~w!snis?Ez|H<yS)dG>3zRYWq4Y(%a*^7u<m zy5-c|Y_v#i4O7;(q04O3Smv#=V;qG%2`%!X1&2TYPauHCNs?~h43Ti0rtLIN*hVl0 z7Q}muln;EoKXvl^TX|sz7rwg!gg9cP>dO23fxq{wj%(ePz18OL$KO7%?%y!j$Mn?; z*>`Uo%oyJQ_Xq4ziiSaBZ2leTGR0-r1ULDC40^I!-!K=7xn9RiF!kBGS~>YIRO)55 za{6DYRP5@d1XGNv2`=U7D#p6mAhgRi%`(`%f^CBVmdm;N*%%sjO@^rtagEam8u<o; zxaU(%bG<Ze8ji^i=;|hdDO)rg<L{$tXPvY%O^2Xo`NmmE%{;>a%2oaut};{4G*EMm zUz*FDRBP_RAm?iTJl9!a&p20_lbI&Ggk#K6X`4&U(R^cphFQ>;TK5!B=qu>3b7O*K zA{E@B6Ae~*RdmcchFgwDIfZ+qW{!z&<>f<^Bi9#<2ro>^##Wb2PI&SKoxS7LC<n2w zo&Hlb{)aHYwy$-p(e0+B@k6;Q@UArMP(t_QOGfyf%b>39-x%$@WR98Ih>x`7_=atp zU8il?DsGsa;dr4b_!^Tvl59B`-0l8I<8Q^8Y#Xk~zg&ea1D1fY8UaV0I9QA1yrsx* z6E}^a*73P~G$CVt^uwk@28BAGZ_P8c^dH=D`>V61@Ryg|TRdsW+`)nPFV*P!zKGt> z#Te*_j~*TGu#GntNr`O28Dr96!2!Y*KIBeq2llSM$_`_}I;K0f&iAkiDS{OZNY9^g zXO4iOn^GvFh|g8KUKub&7*4bpfNqRV4%`ZCw<5eYcfh;x!*p;SYlw3AOw8`U<mX~V zeWN4hz0pI<YsBuL7Ba%M9D@BL78kbsj)ryHUYE8R`nQ|3lLdvQ4wy)@5;qx194V{@ znM_gG5LghJWl=?-LSR5Gtt!&g){)6~iJ|`0<<ftYZ34%55E7?)3ipA^5LG35DGiN~ zATKR<S`#B$bJ=XQ@i>mPTfYs?KrW<bT6@MvF0$L!)c7=Xds-U(F3q@Hy`Nt`uG?<5 zZv+Yx*W~MVw0_TOzu|oJyl+=$`b-aLW@9JX>TF=X`@4D%-W?lp-VW{#TEgqPZTh|z zU3V{a-2*wW*K}n|FI%s}{fxGzf^`|ecl3psSP3mLRiA~QKhHE5p1y8}&MJPgCFba5 zi0nbnA%P-A$U;NjsjP?;_%g_AfTO@3U6&aOR2cRIY=NLa9%Ywt3g{X5Ll@yE0Uv2q z;0jO~_SCWf9+zm8K?=^hm!`Re-!)HiO?NpbhXPJB%@zIPTm?;ehPur&UvVDk<_}Lx z4mD834Z4cozq5jeJy&SamwA)SK_{9Zd=eO5G8%YCZHg1<Q6J0*_34hOLw#Bj>QEn^ zg?a~)$hNYIe4?*0Q!JZIu;NYQ;Y{X2MoFvl4JT;WJZQ3U2V5>8wz7tVgQbL1PaR!| zIkhah`jd=94;|BTC{W}Zk5vjivPjLLMw)0i)hY7KBULH*hLX&oM@|#G8Jq*v)Qz>H zQ#vwe8LB!(RC`H=P19&Bi*y7>ho&EwXZzv$!}|mE>uoTE;hkBlm?{i?s|_Qqu#H<( zD{bRe(kk4ns#}FxYJ_O3?QJV~Kgvo=erf`&WH~A_EsXzpLTnOiB-sS#sDlByR*|~F ziDp61t_ap0wr%IPHVB9sb(d3CTdY@g$u~rj!>B&BP>NKG<<pNu0)F%-xvy~+EydsJ zi-f&OTzN5%mmw}GwOwO_K15C1!<ZPSB*<DJKK3<>EmGCQSEDvZTGs488W!seW-TuB zX-4zuQWvcdp1uC%v-z*Y{!xtw=UDSOz$LZ%5IMeK=RCiqb70Hxb;oU8N^k5yEW!`h z(p?|Rw6D*7TBtXa0=1k94>fgWolTHOLT!9Eh(?G=<exsald?MgJb};f@Ut<GGY4Q~ z`P}y(TZ99#>{&t9X+_`nnx<G_TBbrT#Cs>FJ%)2o))rXtJO|Oq6^X6g2j@_PS4-&d zgmC$*Xv`|-PKQPg4=BGPx;xxb#+}9c?}+N;wMS$C$2E4=r+FY#Jfc9qH~A1suYt^F zwRQ)k{9)!KXh=j{)U5y7Vv9#MCoVW&EDj|L;>Q?dFSk85#-U_M2v47dF@Wc3K)rij zq*MiT;E;@8#ECEhNZlL)>^HhW)IuP4j7-G{RMr|bGXk^Das#3ezlbt^xt@>xD3H2Y z%(xAd0~SbM^;OMf3ou~E1qdUAB}Gyk5;T~AGJyi2s(>t_!Ak0ZG>f8C-9dJpUeSRR z5zSU(6$qfzS}vXYG|E~Y6)2o(mg@qVNovKJYie<lom;QBa^DIQYc(R*Rvg-qIEB*B zW!OC+k~3F@%OWi(8`8)~f;f}uXB;S~iTQFvDzokKD3|`*jPqDPttS$dH#W>Qjt@a! zBIgaCc^p1o9IF=TC-a={hb1;;k!lvBSqyvLo3AvK!+s(SYh%h5)5>UX0M%FW<<8=+ z5PP$P@+MsmK0)($pcE!z_)MmBZvYlhy`+7?)PZG~wgP2$#J7i05N0><c&-Jbe(}u1 zkac7L4uXpIJd{xoR2r_al9snHhISCrVEP^ykk9$)5UX*A<1pQ+y8*hjf!d=xk`IMV z^VfhBk9H6ElBV%RX-}smWf&L3%(WuT8ldA|{a&SPd7XmcoQFX=UPK%c(;?>#wt{Il zw;yTD774wJV4h_|J`qK=NPoxztJoZhC1=|hpS1~Ck5UPlQAUZ##^i)S%`mr8$PVjg zc|$E2p@irT`gp`Mi98{UBu7H>A&s3w#XTHQ0IlV5;k-*TS|)jsog;Lm#7u6wISv=e zL0*|T#w}uC`0=eUhKbhF7dUAa)0HEt(`~t>Fi=)H5}xor=!?gV!asDm0y%JN6enW& z%qMU-*-OT3jrs^gZGXuGNmJ?q4dZ!}1NZYx{&WA#o-5x`QhX1%<l5br;IIP!Y!2B% zgO-70QG9#!7+9t^_|(icgNg3y%Dg?Xv1sH>B@oUSmi%!&R9^@vXx8a*>L?rB@|_Ni z%TwGpzy4jy@bL`V-AW2!WJmawZa4h+_Qm$q#;^<A^cA4L2>17q4>z@fQn`w9{n`z9 zj$lbkD&Y?@Wi~m9%N8k_&Na&l<q|=^+M>&_o2(7Gzv>yMDDQ8cm6oTx?9WT!K>bql zgGI}%N?D-~8V78BSsFP2f5cS;NFPctvT-16{P5Ximm*QNBB!$j1d*XdQ~*e-TDsX; z$l_)ku@DDSU}dh1iIyYahXbU5oS_qH@`_AD-smw5Svo_<G>XE4nK=-eY?&?O9|v6r zr{4&0S0T%JwspDYB<E4aH&Dm$zGCE&WO}z;8|rwb#SCqi8}Fp0)CnCrq(%vmhe@zR z1r}uh8`M@uU3(4NiX|L}gP?WpeKuT#b>F+0oj3F}?KS12uJLTy-LWamM=3LmrfN|2 zj?q7a6jx7m&U<YH6T12V11Sj5GE_IZo`WM9RW}`RyN-l@myQ8C0K^@C-D`3gvtwWn z%jb|yyK+G~&4eYF!SvIbDpyLvj;Rj`jXFxcr(Izuc!>q-{6?AQDRw94h-i)1J#<_R zg8fZ5Y1Xv*MfT<X4*$YUXX1jm<*tC=`yLSplWN%)8M3K3SiT}kS854jXjNlYhK@Bd zh9(J+59=3*ZCX_v;04xNB(JA8I_D}jT}$eq=9SboVF(RQ>#Qn_Cf|hmPfkuKw(gi5 znhtq@aM_Wl3^QmL#80veF-HCNYfai*a=ZxZa;UA)HW<fKSrr~e5Hf3%|FNUFA=WNp z$$7moc3CuGcs(Wi<X~AJ!|QBHU0B<w@Mll}1Lch~JnM>kYF4~p5Q2XOhUw=(B6<lB z7QQTow^#NMD-tQ63!^sZo6>7W21`6Dtm%~N2Y5%VSyY;JErza2MEkH~2@w?Je8~m) zMlmqTI9I)V#aG<+MD5pMf$6?OvH-<mSI0Q>X3yUD&qq;bDxGOLhRzBX3^a0SS9TL+ zI-7n9n38z;OJRh&Rb#r@8dc?hWJ&MOuG~feekeP$dFWnmd9*5=4)1VeNsJgbHBnfZ zU?!98gp<whG7?Tfx3Uc>VeN}IR?xkO<WF%^93kt>o0c2U#a_FDg_wg$`?;4n_+8Be zT`NDtaPSIJeoe*6J~jyuD7`eA6Ir`J<Fg_+XTg`=XVdIUKni^qw=R-UMDzUWL`&f* z`{S>JXT7HQZ#$dVEl5wVHS948=LzOB?ZdEmhTok%l!xXkju<+oVw6B6mYBb5ORTcJ z|LJcE9*0Nff@ny}oRpct1^US{@r+dXol?;Oah#8FRN9arxLnAo_H<rTabeX2{Kdm> ziju0a(0`zv6Fyj?02Eo+slTHFvmweFNOzDGpZ6ZilEJ3WltMJN)dIq|lEM6im|GjK z*+2Ig0SEhZMf1B6W`cicf4U&2`7UQ7PFADGkzs?w3+kuNk}`ZgeOQslvfl%%^a5Us z!s$_`A{gcERNP%^<BE?>g3(nMr}rCA^iHWzQ%~d8>BJ)x=+a9eDZo_K0hzUS5pok; z1-Wli2>^LgfqLLg07UHP7_ieqU3T(CeaZiHQy#8$67sDs8F155CXQu3>&6xPC#{Pz zxDdHvi-oP5OMfDK4zzyS*oswaViZn|6EL~<++{$t>6#s$N-!2^uNg#2dOB&v1rK<> zF^g<noD@o>%^0xre<L&bkeo?aGPzhhI5=EHV|M0lu+5(*(DG=?!}iiNBuDJ;<v$%D z>QY>*K1rDLv{A2X$y!+*LHHXe!|$5EHilWL)4Cc0rIM#o=c{&u*#v?;*}n{MP8>r` z4r)5rlXhXPp7#??FbL)1)R+cearhNsjx6YeFbSg*jW12DUeoP&R6U?=y9%X)lbE=; zZ3tjMBXqcux^ifBBa3bw`9Qpk?+jC-8DBPGEG|^IkN<@EfKOYm4=KdiG-K4!u_`m~ z6P`~scTV8OM>h+(pBxe^aRlO%TY6^SjxKsuc=#BvOIJBnY#u&KAXXjNV(GoGgIS8A zjfwo&N|+_Y&LP;V#eyodoA)Q>20UT>X%a)mNhTgWn--C&AbH5$mH!3${oca1E9pN) zEx|eLVi-wITD0;wmZ#VarU5*;gav-rW|EA|IHphh*18jK-72ai2g7QobDX@d%LK~r zcb3m^A-x>0(r0{09q0vWAfyGxIw60;WYh~CwKfRH_CD@A)EXS)$mX!`Z`WUHiLz<Y z6}3}sQkk$Y+mRP~gnV4_D|tV8Uc9{EuGPDCfoiKLvnm|Zp<o7?F*#VkVG;YyY&gWK zloy8<ZKNzRv}bnD8z6FC0Nqx(a|hdcNRxX3a0d$;=aa&%j6>h5i6-O}+Q7+l&)YKz zX0Y6W1~xOseQO(VY#bIE=(Q3(o4I`h5bBgec=QQGvWwBvQ1;T}cB)tAjD^b%im~h< z?iz;rP53@xElOYk3F1>^rv(Fx^QA>H0B38#Kvj@(i+pHojSUc``+KNRPXcZaDz1Lx zs32fSlxxT2+zyOcnG&5=XAko0ul=T-SqOB+)mc<+>lW_3vWY=vVBQ3pSS5gN$9zb3 z5ubI$hw%|4-Q5;yWkz<q9c^1UQ@=hcZ(=|!qwqosATp=t!Z@(T3<A28wGZfSq_?ay zI25vEzTCXPaLyv2zxl@ve&dXj_YHKLI0%0=p}qmMvkI!b8|>UNAj!5^s}d>0#yEDP zR63HZIg3>c8adwiyj-LIKHe~BT*ly7Y@ZiWmps9l2sj&KyO<%*#bJDf@b~X4LqjG| zcu2$XKu>Ps->aXH))0D8hJ74jQSJJt&=s`~RofM9)VIvQFO^H8uYb>wLgq4B(%wud z9R6b?msBC1kc|&H7&ezBz+c9Bf7KE(XVH_XT^zq@IPZMpMd$R!#fA&bI6w5jIj4&! zeZE;rS&y8iRu)=6WYDkD?)D*a+lO7cp}<9GINtY7m|}bi(M5Gc0{YB%^!wuiB%vOf za*>-<IQr+OCCqj7NM+5G=MA97TO@&1$DTPd90azn@p(t|^Vi&bAL7hCH(8PC&$=`c z3pVEYYR4vV6MvmT0I;Axx3Qdz5d0*OXS4<&ar8h4V^M<YAG&*_au~V+b`nR``470& z@@PHs&!*g#yY_wqci)+r(5_tZdNIS~eVy8YK6?{|58aHNJ`lNZuZfe@2&cXLnFjEC z3U+rh^7@12Fc{CYgEJ5ob4m>{wyKKW(?|%|@UxBHQ~=*m4~=<w?dTP!^rZG~qDZDJ z!WSjaSGDa_xODrI-_6&}uM6f$;O5vHsEa)1t<Ixo@51A}6BWqZ^9wapjYoS~WZYtH z%xf%()s)7Ts8Cm`QHUG<<I`^-Y`DZ*t`mx$*|_{0+vsmtB92$~Zx{ll?U=BV7trBL zUa%{m3s}^jLj?DL0_MgxA8&9_z4Jrryy}cX)<}^{mCP6ci;|~TL2{{7s@YXv<5pG= z&Hsu}npIWmkHnu4lI+M}TR7{-_6T8(8`D4&>z$=3lisu?@P6d|*a{X~FD>3p*VRPR z@G?B1VJH-9hPx_<Y}48bwF}5)!lUpouMX5BT)V=Y_WTD`RL;pd^7uZyyTlVH`w>-e zZ$s-EofZoyuKgK?1pM(&pt30PCQyKM;>`dvq7ON1jGJE>v!aAs77A>Dxqcb7kTphv z@teH+Z5kr2d&DQZ8l>#a_9h~V=||=}hi|27zn@sIV&zz_J)-mQ0ZDg7Yz?U7KO^Im z0ahO1`9&80ngyBMJIml1J{UJ5TUx$@S~9^v$~6N2wmKG%2?JCgKF_sulrtd%OrC8T zI&s243n;y&S-g3nL5{4g18R(%DYym`YA2n#_B)ykQQT;iQeR8qIPjgxP(xQD#K-j3 zn(_2TLk0mv<w}*TOt37Hw;NUzEkXr~ZCv)229$z@D#)y_^(&+=!6a<pXvi*UP_)1- z<$&9~<X8rkZP2w*jB<f%)IhcrD~BgT+N;8eTJSGoC7Q_jbnLPGMT)d}AgqPnyZ<M? zMW`~zW`g-@Yb6Em5_*oIhd{Xh0!S;{p@1+E;X|8rH7Cvwx!D9ZQVN0^9mpjc9Zg|i zp}&oX4VFF;Nc!L-t85&$F%FbT<f<unoXXv%oaut|$`(bNdIgZ&uHE;@n2YfXME!Mk z_exu?AWxK@D>?gCF&CsW%6Jp(&f)z`fgj9jy@pAay}LN)<m@%5UlNNacRySBL&D++ z5c-2y7{x2wFPS2H$$o6TwAO&WbEkR_izw*)L224?2#@1c%wjydcIrQnmB9WB|9=JF zyg-Jeu7Aa}L@@tb@cm~JFg7%{_%GbwS8c{_TLp!0?d8p!Dftg9h|(V?L@C39nLBN& z5UK(dh!7wpB32lJsfJq_p8NHsOKzD_DGdcS8ict4<o+N~XuSYXY<rFR3+npA9Bc0+ zqGcH$-<yu#z4sgU?v3l#c>a&eNBT9upD<{DGQQix<lhKU5QhFFK@)*NgMO^7fWU=y zG8h@#>;w&l1_J}YXqpJEgk}Syq5j$nHWD})9gKDjcY}Sw<3Wfr+h7KRZlEGy`1;LI zc;cNGT!nW4bnTMV7q9C>z0V#76wld}#Qo3w-2+2}BGze=bfSnum*xB^jRWs+|34ml z*>cPkPJS5`#C%hsHtN7ZEQg9YRaReepM<%-ZDUf_DJJ3Yn5*@R-z3=A<_9|>G9s1p z4KJDm!4n--8lL=Wg)mS9d)|F64F_;D=z1c{RtUWPLIGlkR$maD!oS6a1MXmf;r)ba z9&dnHa<Cvl5(UjIv9qWVT$^sx7M+Wu=h5{u_jLml+~F4Cx8^!CCX-EtV0B=2X<<~e ziv*D?Lh-SUPoYrlCV>pJ2xOE(sS_H<+?``~7J3BI(D~dh-8j*R{geUmq`>b)8><)s zjFm@@`Ga@8rV34fP96;#9)C0mab+;HkHz)*mh;qfP2Y-CZ3Z3d%&*YoeoJy4^Zwb3 zuiickei-CL=wP>%EloTvWr1B)HV;9J^U`lfIM6(5yPteG>%^X>7biuTaN3!wcq~?I z`2%%EGJiT;Iii!x{UxS1BoAHOoQ{rHWq(hweHpQyhYXSMUm{_ln?>|Z4MD$M6gzwI z%NicO*B~ohf#N-<&9px{raQ$PD-7r4me^UWa&&#@SUG;7KBV$2cL{2<%|AYJH65H{ z9Rx-A-!3pYgxj?k#B5}NWSuIF%06*!a<vHj14pbus5jSr%z`Ts+9IP_WTC%d)CK3( z!@%1Qyw7dxQ-H^86ZnC-odZzS1v?mCB6>KIt%fRuA9)!XK2H<lxL!U-1A|ir1}GI< zRJV^modln7AV+}xP^j_BPOH1)+%=V5*`-0pvZ;@GW<mF8yRX&laL*Lr)f$Hw9~Sv1 z8;=e*btx5rPQ)=>`Cv`rfaV!;bo6ab^?Q19U)BBy$2f>${e8s1G&EICOhcQ|(2_(G z!Kjc3(Ihe1fJ&x8FL8e*K~e4`Dakb{Mr`GH{CDJtSe{6|=xmfo&M1ThOX+=4C<vYt zoTemLS{?#QQ^S%0o&I@QL?Ks}t*F!}zON}%I9RZSVk|4bX0vAA(lEEKj%}Ub`e=)? zxnF-2Yv??V#%u3Rc@b^=f>dx8`hkn)3@xrCatsSQiCaVwq$`}yJEw??4TFhgC?sJ` zVR(XV#*!nz9i=-*U6}4i>s-QH5&K~BcDVh)AJ1wvo3S6yQX9bvN5TIK>s<-w_?W{= zXNmXnSqciy@kVgXw!`cD+mPxsfZB`h6RR|<%vcv3o3eOM$F=3@KarX=Bh4*GjB*vO zg_t7&6RcSj1)D|4g)hTH*?MczL~>{u#v}pF!_`uXv^VP>o&H<5=UVM7B{)FnX4mW- z__19mp}(3~>PE=kj5|Z7tU{vyC(G3-xsz8`RxQU!k9cshtbD!b5XzKHn^}%8c%)w> zlTvpR3sHto8rEl`+S!W`AmeA5ui-H2Bt1N5Q^1XPrgOa6wY4JCb%tU!ZMt%l#x-KM z3bv)U+65vq#09HKD|R%C$;9F?L2)4*(KmuTrd&8sd?;`|kXHrauOe=6bVCWt9c^%) zx`Us3aS-FEvXdgIZeE0e2QexCMH@buVBV+SMigbgsWnN{hKk<GewY;_Y6-8d%B{fZ zh*9)d2i(?}cm9nNk73MtT|vO}=0hhM#2z_|ul_CpfO~lXrfGhZdbvmHhvz3p-D=)q zk`a}+SPdwJ+%F_Rsc`O(^)owHgzMvFWAueSvteYXCO_6Qep)&H7C|34sH@#h(I;>U znw%?5>)peL40ZPpTd|u{X6%$!XZ7fcR;O0%lwPOH8H1gdQMiux+4^M%Mk)NT@z5VZ zU!D}+w&vkAL8a%;hxJ-B(O>pw(!!M==;ve&8OR!Pt8#XP!`P2C(^X=JHK)DDV`~<} ztygkQ7HNjJH^zg#e9(W56^r-Z6wrytC<5;|sPycCE7E%FqwjhWapy9eJHK(J*y-wA z*}2lWsk>P|*<2Qw4irrWVu>jiRdZ;_x{He}d5h|0HY;1uW)~F6D`7z-f<r?*ACYph zA23>cPlLa0#f!dWT>IBmup(}`+N+FP)yB2=F|3dODY+Fjapd2}1_0O)`rn2*8+-Hr z{(ExE+Tg5t+MB)POVf!;rBF;PN}$o&(<r)KjmH^LmzJkiYiU&wAx~tlFa4dR;XHOS zdp27|B0nZfTxy2RVw2n=;A1(PD*=UiT9k$tU64*J5(oqWjp}%s7bbjCC@33DfBNiw z-JQO2I>!(sii)@2?cTfn+<oPDPEJm((f+;1^X^~wZ=CMK`Rax38{oz=W;3RxU^Tm} zE^A0Dz2LGwue7UA8?brHH}1jNnr%|cvwX`bI|Z^v-N*bu)2JJ7m9ADrniKV+Yf{tX zN!O?wY$eyQ2Ffe!n7o2&B46jKW{a$9DRszIi``IN%_>b3US<-0)~v)YZ4=MnozQZg z&NHeho~~_JWi*p-TIFeiZ&-CSo2y@iG@EN&l{`7KdE`9FF_Je-TDmHQRmL&IXQas= z+$3WekP)vqr*NLFFRP!`wBQZf8d`<Cc;jK2IVx?a5RyGb5TSlPy3R+ztYYbY(VByt z&g<*F@wzPCW97GTR%dbR=(7#Oj_a7-T99iy<%&+742B(J-m*+S2QwRc<tanvYCR7- z1#Y?p4}@mUD74@FF|Ippv&CqPYTCV~`_w!0Af#Kld8Xp<?=)#&fSZxqVqU}9Og5&^ z(uZ^~KLDd?w*P3gt?E%XK-YEm?cXZA^bUOY7&?f<<lt>+a*1VQ9fC99sof1!?nkEC zt_ATeJ95)K+jDQf+;Z4g4Y%*ggRi>MsmM67_20qKn&`Hmi*4p{8-nGi<4v_VBW= z?>V_61Q@b8`ay(oNcO#%=hKaU>F{#*L=3AA;S2w62{!2$bw<?#w>zHKI*{8NaBWN& zxoKTGZ*eToxD8lQ9(L31{l)+j7{iuZ-x#OkbdznkcbPF5!hf<6F-0F+Dn*Caa6?_N z{tUpIgP)0g2@lz24VOb~ZaW7#I7<ST5i>!e-~fbEA9RCICZ2#ThGOiT&Sg`AAg~*P z7vjkJb8q;ED0eDPgf%Dz*lN##OFNF&jXjY5VDU0@sM!x7YDQZ(WMF+lXgfoPw~4i# z0fIFkZTsNxt|84HVH7V0KQ_QU$F`H07yXujZD3|F`2##jY7%9-L_ue6eg_R=%dOS7 zH~12S(7sFW?Xf@vLi7r#2rO_S*P)-+5w0H>pKmOwjkv9C^^sc}sJFHtN8lxmM}&_q z%e`mz&A1#;*ayyzp#YizSi0E|wEfGCTZMh|8i2`tG{1Q1zC-p)iXmMwEXZa886;}} zb^F}Ue-AUcDTYWpCnk($kvHWIZc96k-A&(`+Zf^2o45=NgYC8!XwMzzb1*RCwP!c( z+@-5u-4R64ALq#+7)0oJ=IBIGfD}U7;Q&-5KnJ|F2mgHN42^_fz%UvxI%-_EGo$r3 zmS30ysQDhi2^bI>vLfFdR_#?*AYhz<`9??O)ruzz#~I<D%pWe@q~RI%A^(VZ##>!G zGFrJ8$dCFa{I!1Y*6ic|yvrL<fIO%indcMtJjkR_F;pCBZMPmM%XPBYvJP;MDlY_> z%;M#6-gB1;x5Up}FQ9s<i5JD;e)(}NR^`>yU<D}OXvb>59cz72;n?L^wxHwd2Ib|} zSgEC0VP#8!BX)tA9EDkFQs8$iK{{D%2X>K>TpSfwiD99S|5uR}xCJ_ec3wkEw8Gx7 zCqxUSTtS1r7_CLAZUosOsZJ^kYleo@D#oZ0M{w*ufH686*g(Wy!?28?E!zKnhso|; zn8J;<bt+>-qr5>j_xhqdz%Y7X5NB)VfEdSA+Wbq_W{>5}HqVpUN<t2HqG^Xm70O24 zh5AstI>o`PIt7u3+O<dWvs(Qy2Rtb*-LbFfQqH2IHB>5N1&|HuG)kI8qQ(sYn|CaF zN@(=J8SxCtL=xdtfv&YQnLQ0-v$CSFu~09<xd6xY-7qYnv`t#D3Zg)J1XIc=tR!Gg zIK0o`i{$J5c%>z9tBJm5gKm2%?-Djo$LC?x^zy+vJ?HsZ8n+$XI-To6Ob5t?=EeOm z$+RO6TPrO-AWv}q($p5r&*~#atu+740W3AzN<cihe6g`SOH2ju2{o@(p>U-r_E>6% z{N6Ck2Y|;`1W_tAN##V3q3c>tz}NG$!31W)#>!$*f&I<#PnB>)8PaaV%Igj51r~o` z4SDh*r;q+WuhSEET9zrge1N#&`<ckgH1T&>oLzbG9Etc?Qu+M_YeB&otLMpB6gD}y z8*?SX#D)syktzvy?%aW0JYqVgci53cG>4@3PJ;oI^!(zc+!>E-T(LO4Nxbu2LSgdX zl?ghA#>++zRCbsf<qwIqD(iaAZq|k9OwhUv5BFUy2)c+PrC793Enaz(ybjF=vB=B6 zn=W2KLx2PnS|0W^m)z~@Mg&=fxC=!ahK(hBvh5QBkL~zVQPgQI*IU7Ot5s>w7V|d~ z><neF7;SHsM1QzrxkV&!-l^CdID$tWhqfeNM4nD7p%qu4ya4?Uj8v;etm1az9L<Ft zPyKl!xPh(3Ub2$6F*6>-u^2Cjm`r_C1y*UUB#&p2$5Tk%^F&H%I-Fr;wX4-Lm<Mu@ zoTE&9)XovHrk*$=Tj?=+*PWqk^%-0m^n``cX>_XPi$kH^XjcoFHJZl$A64fNCP=ho z;j(Spwr$(CZQHhO+qT(NUAAp=dS)>*Z<m|9$}dmcjEHmoO1|K1oyz=(>3~4fq^`v& zUva8srNQ%{BQjwp5xQikeVENYm)_Ux9$aGJz9YOJNEAY2`Exuit+G1v3$e1i<Ym|( zK{Y4{CqfJ%BuIcCWF@bZ)QE~b#zv+>Dpl1?lS`uuO4UkANH*G-uYagDv^z!g<qrvp z69B9};Xh^XH9*I)AB1sA+<9WEGY4|xj{G2<i<;5WaHo9ZTB1}%%TgcED^Pbk4__MY z*BZAj#=s@kItW^JI;j4EvD%x0It>;mI#8U-IpoU3bmS`tHUsBv;Jph<PEmF=4O(5X zF5dds&fs@-KKP7IQ637a$o!_bp;I*|bV?&LBq>P{87Bx{&QQJSiL*f|{M7G=4jT&O zdlwQN0VK28X<v{#gU~iWJwV!4zoY@~lVsVuo;eSO$F>tlL>XmL6$J7CtnTZ(H^pSs zdE&JmluccHyKJkS{Act=?Iv)bTp8w}YuFSy#ppoe($>B?Dmdk7WkAC|i@G4Fs%MG= zdftB6KU*EIQ^(L`E>-2@gv4yy2(=MO77Mq-rARBG<g$FEITgs2GfMDsX2qt-xzoxO zwx*=IE7}RqKrtOWNt?R*HY?6wuswjGY-`GSvOdZFjwvrEV-q1%3a&);zdVRAsX=Z` z=(D9GY1b>0(q6;;qN4WCA~oieuv8U>SS6|_%_J|gAtOq@px;Jydv<&eE#EDzBda<L z<As+T2Opyq5-XDl(y>*JDl7-EA1YQ=<j5pmSLS7w8&YcLnAZQA*KPKHBrg{K43_3G zjmvmZP3^0vFr3g6tsjX`hPgz)GlHlHP9Y$CVv_{pB+fGy!k9;hyPTgTxjfa7bd98J z11&e3QskAgkeSGGEg?;Z!NAo*wtRzbjS<-qhyTDR06T6v=4m|l<!S*^$Ua@*E5TNP z;jneDwk##Yl~?wnAv2ZpTC{`%qtr#U){zPOik@W*SCiuUO(qE5%+nj)qY-~+04S$4 zS>vM@C{L&VvH<0DBJNGt<s<T>!-L8H)sip&Oos_L5d&c9A_^)mQ2XjCTh8E3G8!s^ zkeskABviejV<b_~$@`*jMOk}({f)j(4D8VySuC)%NyYf3Rxx3lu9(=XhC1g{$Q*bB z5%OZ5XRD^kG09dg8Lg00DvNuWs9rpHE~c+|hkhy&>&`UG4qrQg+003em2aIH>71#t zw05fvK1rbFOOQreKiOXfDa0HZAcnwEh;QEWs<Omj(5h4~N>`isZf2B&#WfZ3K}v8U z9>N&zdLlG?`vj7hP0y$4`Pvwk@PEYm+KHMAL>P#J4vgUJc+rM-JHYja_V)iVWFhz7 z2Md9oZJo8h8daW4<^vTMxV?OJ%X;RNo6Cn%x(Hip!^M-Q>u+9eQNyaPZqH&@KR7?; zUadX;j4k~e=6e0IeeC`|JtCOE2xVrGL{qv38~@nW%%*{EHq&F2>Ihg<B1j(N{Ox8g zeK)DzupOY-2q@-Y4Mn+%_(Rz+cK~F?bIp(^;9v9?{f3S(&$zcA6`Np0%w9t9P5l@4 z{0oOMyos%Lc7eVsOoJQR7PO<%`A&KDq}76}m)FR{$=)T6QSFz7x_*&Z#q2A-QdHf2 zUwX<XR2uUnVZ}z6A`X`<-}!-U(UjWE&Ja?PpC%d|bsc&dvc>nFPVMhQvWPEenv3#s zc$5$$(vGvJpNI;8)IL6`c7Z3c*M8V^umZ;|sVB(Pt4|=2%`#T6TdZE2Hvon=_{d!s zb_m?K+_H9(MiT@gaUx59T#SvB0q3f7FD;?3T0=+ZXuV-zi3rLBw#L@LPI$tenp*lz zy;l3}P7kEWg#Kvyt$`!G>HOE~IKw2*^<_Vzv2(~U=76hcHdu{1OG%jV9nN2+9Od78 zir+zu6o2_b9paS!ARdF{ugs9M*YivS`VT}tXiO3GM2LXFh3KX$(sf%=T6RGSvLFdA z5(+wzaz>9kON_WVWe>nz1S0wj>tKXd=fEqJ_{C1t{W|o%&nuTGTNvXODU9Q4$OpT` z0-voDJQx%S+`-e9fzxeoNG^V4GUtwBd5r@;5fQn|W-U#<QwyqSk$!%>aDJTN;oVOc z96yGrVNRQ$QsVm>2oIBmHhB(~V$k*TQ-ga`08!xb4kId`sIv+BD8(Ow&Z5Hx&tAvw z#E9VeklCO$dBg-1oVmT`8rc$z*#@IUUdF$Rj)@s^{Dwy$o6HEo-kdK-!jKP_xAu*_ zJrB4irPPk~0?#;`)PJgdPEaTAfQp>kMZAbTzucj(&e~nsep4t+{OW12^}|curcH8C z*R$hK)_`?VRY0G%5LyfV2>W3WU-*s+SDI3RO9w$UsR7{!*G1|Ax4OXxHv-2XRYw>Z zxyLw@P*_dAxnH0XCQP1k%2pL%b4Cs)(;$QR@x<SPweVYyP=C-FO7|SnGnOK%L$uZ+ z;S3D{kC>w14e+#o)*^+kH#DjerYBvl&msHi>lm#CM6j!j<}lSHmN(x#=1lWes>Ts? z7SN8y07=*il7ZGj^_K_a%Udq`NHG!ro4n$<0`vupLTluh|M3P%$};2ukD@oeXG2?U z5cr6a_Pu$<#k;wyUTaI4sQs52h=-;>Y-F1;rwos}@zOtC5?)n>{&Zn;t>D^}Rgd+i zy=3L(TBjA9MtQ+~)GTTjjt%t_gL~A>D_*w&3YFa}K)3#Q7TKy#a%zR^TlI3fkZsjJ zvW4X3p6hcVJ_=I|)S6@PBKcRTB<(cASE@Co;+Umb_Ae0EJ*HW{>C590Y2DtT)Hl$g zwu{dsbLmf+1TwNYLx13qqYqk?yg=+RDi9MFpkAj<=)x0RzC@PZHxKJ}nSiJcLLQKX z25}lH`jR5{JXDn^oKt>k#MwgrU5rnT=L5q)^-Y3@1k6~s0*@y!EYToK$P1Wx@6QjW z$xBiy0JeY{06GqEpz~To5DdYLWH?<^guNvNliEe+nJH$bByQjlbn~pM0Z7ugeo7*e z)6Bwitlkhs&U<U<p6`_P*#~g^mWFWSrf3c|$5PFyVr|f-NII{4t)t!aI^@Bh?m0PN z-p+x9^DgWK9;ssS0uRu7^~kza$?FQWKSj*L*0GQhaO;i8P;nmVZf1ya*(N&39cp+U z=9+La)3s2C^~?yqg?upeuRO85DFVv-HQx)90k$Yb!vW3w$a^qAnB!;k{zDXVdG59* z#l!?$(4**xBB(%#fM_Em4tb6OSdp~fQvpv_U=k^4$3}R-WL&;bF;x99821)1#h+X# zt78IZ%YG21q>J@1JnBq)o$bhW0Vya-gD7wBEEMPcOccHFqus>{Of6?$eiX5(ld~i1 zsm7TRqq~d`7We(6yvYv+ini;;4k@}M-(fvWZ4R3j6~zL?ZbH}WliCGx>v#mZaX~ig ztBm5*m?IFiJxaM1zdct(C{+&<)}p+@>mO|}wuNabadl+?2>((6^jYeq{pk)YXP*~* zx9x8g<SL)0qy(EKT4<dpi>7K*yU}+&4x#mX-k=B{*INW2`+Q!Q-_+~JOnYc-=Qg<= z>!7`$E=qBC-41w0)k4gJ95mE$2<F@oc0)$h3j2fM9RXcf$RRE`3-9}cZv)f~H$w5Q z4@oM(YpkYH7!{H$t)R7Z^OsLsICFVCFr^d<sTPP-!Jyk6@p#Y_a)Y1g&`=i};+|n? zs)_)OM|_x>O`tD(XAs~o{mdqc6Y&xga(QGvWMWh+5<U*8%<emLZNYDHWSc?_#9@L6 z$e-#Qr;va?Kto{J3eDKRl>eGbF`Is2{z-C(w?CwPqh*tmb_(ehEtdkcM58uoGb|-x zP7E<#oK2=vR<V@8GV?FDl=v%yg(TW@odu;YUpz!Qyee97iW&EZg^LV{@wNN6$XIrF z>%}uEa^<Jt`h_C(e4(koH`cBv<W^*9ffK`p4QZIR3esQZ?9;4%b~X3xt|55L69`Li z0p}KHH&{q4R&raiXtg^Ec8$u8b~tAem7F^~X4^zV^CSO`%9=`Q)+A*^P0<STrVdiQ zd+}=D?&tJkb%%+>RBjwqW$ip9FhW{>F}Sp7Ziwd}Vvsu|F|lu6aHq|iSBB_F2s9-w z)MM%)XZ(*Qgs?Vph92|TW`@gTdBzibs9g1itvzRo&(ePGTf%5A9flG1WRIh0kBvK9 zj>j01gotVda0Xzuc2-xdQ_?%j%@lZ+ldz>}uhjjyXKz%ZWzD4`YMpP^TS-FNJkxvs z3e!*Y9w#P2i|G@l$62!MgT#@5aqEQO{KTYgLZyv2iYyEemPU%5*GP%%49>eNCjGFP zC>(+iYI#nA*|k|J7!TJx-hio~_ow!gA5xl+4D^u(hiIQC@b)1CaOM=4*IJ;~+jyod z=9#m96=nMQxRt)>v(?wiGDBmxIDYUoZ1h|cZGt~P(fE&H&!l$ejBzC3Qm}Y8O*yi| zNLK)5=Y1`wW;k@bkUiY_Gej${Y4*5E0e=4J`ibN76|UhqoBYB!`Vf#nqnhonK2j}i za^wMg_YFryN4#%eYUGZRSoJkIz95WgzBFQozY(f<xd=4LJIfHH4`?jtxU+{qAHj_B z8oO|U44_PeQiiCLEg5~B8QLe-v-p*~Yx?;vQ9CPy>W%J7Eh2|pk{rxc12P=Lq80<w zRCKx9=IdNIc*ziXb1CJ0hD3u!U5DOyVLUR!DDH}AY7lok7#(LrGk%MW0aZ}`Y^X%P zec_eu5i}%QNJ_WCM+5rL+9=JCf<PVgmJefB6OCJtpG%`EV)Z?E2X_uxE-t@?B)d}? z=3jIXHExRBlrjlwC_o0E0cQ3h&eSk7KVy1ki3;K90iC*xe9ty>eqmfui$Qhu@$tGK zm4^%gVeAxL2xn-B*G-AZ2^@Jdov0)HIb|cnQVj?>KPK#J%}u~IDklSqU^xzaeRHMi z6N?h)^jY>s2^}4wZi4!>$rS6$wcOJ1GmEx5`dT{8*R-@<+ZrwEb}d*$kvBSJySey= z0*;^d%qOQ&Wobf-9qZr)#FyrX%l0S$Xpm3^_{GLif8%~KVxvzWlU=d7Up7iARa>R` z<3-od3m7oMI1KT}3ZOYm)oYLz%w;bml3~iX=uVmN{cD;D2w{&-^rcAT__GAcfbPU~ zV@avzvZJQBpR012D4+xs!p4IJ3KFkKSIOJ<knAp@nEWr91J#2jwjybw7Lw4?10X_0 z0teC~i)+0wNS4&_cXtG_{@R9oN6O;2lm1B!wkPNQ#y=Xkai|EKiP4%ATeZYe2F6|f zM6KG#A{OzkLh==g3)i=Z!WBpi#WbW3Gy-`-!qJ(2ks5eXU?SsZ$<C3Rp8uAcB%O-l zBSy}rilHWCFgI60M+vVhS%{%ZPR_Y*HmgEUA{U~6I31S&G?y1-g|la#B-kRsrM`}K zSt2kD!o9t)F7kJomw}J*lV&rLC&fFS^DnwN7a8M=w#QyUQ$OW6CA~>%hjCo}<u^%t zfrzQwTepK`(&77}`J4r<)~=DCvVu$C?JSvk@`~3*dXOiZL-afd_+T<81~gNdE}|=} z4NzJ_RAR9aH^d@~3YNt~)uPrmshY%ZCpCDl0D0d!jtEsC-6$~{w9zbqKri@&rDu}< zD4_l6i@*XD`;A^ke>sq?lB6n%4wOEe{Nd$g`6a})gL?+_<j4T@nux_U)eDZ@)NnO1 z7Ui_<>NRG<97Nk3JU+FY%*vzFUpjtBUO%?xsuF17f#a6b<(CKtO?Qo~LVifiF{R?3 z20y21BC6OcA;JpNZvf-}OX@{gER+m3PKlPMmIh4GST<th5f*B`e)1>-Gp3|d1^R-b zBHJM{5T{oV!1d?UQ_E@|LwxyN5ein{B-@o`QOSsZ#6-s&enHr6`ist!=;RvH?HOyu zywDHh!dsQ~M!`vvOjGK76O8EC*#;de)bC1`+5}J0fVlo2uI;1gNM7m@2()~b6ErlW zmdKe?Li}Fj02pHHNjc5zX^T5U8EA!|3%3h+IdQ~Xlz6}A?-@%Z-M`mBXPXE?^hZQb z2jYUgsM$chDu9rZKya_l`$Cy|m&f@;=IPJR^K!f8C(zGg=00iia)8U?{bMBk-pjnZ zm%sUYWBQeX`Z*H@FEo9E-IW(GIcV_*1m{$*=k*5bgZ>>~@*M0B?6T8QU9X{mO+Z~t zWNC-ocd1$<Fl^ouvJ*ro$}cdD9aZbt<DpRT{oTq`RRmgTCv0WPClp#e93&G117jwZ zuYBNwJA->{(xU|G{+pvn4zX1M019b2??_RoJyh(;wwQCOKR;p>iLQdcy-pE9=|O4; zeWW3b(WvUwJs@VZ7Sia~8@PsnL^U6&iH+cb8Fe^8MC@D}E_x|;9Eo~0)t}K(@EjcC zYZ6yuV{Q%fvi6D9<60>s8kmk!7Ah$Mtj4T+?Pz~d$8hb@r(DT};Hm<ARe`%gGZ&!Z z(UcWu5G}ISD!xj?dZu&bWFll8>Y~F51be8A4`rFnK_qrLfm<NSZ>n0wGMWdV*t&#J zKFH?$mH8w&hH7QJ_k#xKLO$LV+?Q|=u7SDSv0OF8#;1nH8UL8t_p#IZ?XJmRi0<zQ z%KWuk<NM%{hCb$+_L2fY&;dm_&@~%D($3YG4Vh=@zgDdZ`Vy}Q=*PWCYqoHT;+G7* z?X7G3hWStfuxA9GqRh3#2j2uP-h)L-^(FpgMw-`v8q7LA^FZ{p)v826LWjXO6XP6` zu&tdltHHHZRs-?S=TNN_xd!Juy<(4DGUOJd>|qtT5IBFcRzyygMD&JFZui}$45YTo zwwMFqy8@na)dux9L8zmJY7Y2P-~jA&y#8fgI-}k)h!TM?sytiD{+vlD9VN3I)qg0~ zip^&5vcDd#)Bp1S-`-5DnT#|*eHZ=?FaSUUH~;|F|1(OuIM6$rI$0Xpm^fLwnL5!q zc*d$&+i$X=eAnqaro$xkuBGJ~4P+Tmn9SS3mc*Tc2hq&3XmvG3Oq2*J$*CNT-zGIt z&&viPE(E_idfY^x@`Hw|4Ms%+jKZ~*PL|xw6@E)&8)Z5)_5}@<T<_M5aFfUC*4N+J zing4|>R0zzbh|2^10@MHBeD`k{B#p+e5%^jFZiCr@3p=ZwSRAv`wj9B3IglP#S=TC zaFl+E**O!nM$my_3!;jS#-!*Iy^74ioz<%jUX`le0e8}(>YIaM1(WHxdH1sQ?g-{* zYc$qF82Z~wbTiFz4uwEM`lHcA9<LMx0YZjW)}UdoHmEw)u7RDgt40)<TIFR9SyPw- zG9ni+>~B!?QNaMQ4~QU1m;$n?6t}cA36X%<F@bQI6bqKwJvugp#8W6V;*^b2oic9S zVT6iZ&YihXFJqE5Q00zKIAz>&4oDy|FzZBF3&?qaa;s#$`~x|>j9)Qo6QHtWG|r$Z z^q8!Ybdes-EZ60>7uN^N1VD#pPtt;>AQFYX%{=0$L4=OAOlYG8#q8Vlyt#Di2yk?U zcRR2_lShAAGnJ{4(cUx!9c0s*@&Q6gGa5=2*&*`5n+MAuA-#;VACC6^BUJ0jggtV` z*qI{?vE<N>1s}_D1fM&x_2$BJ130&|=)n2s7)n6e5K~4&VvRX(H@>{8sK_oqfH1WQ zQ`yD%h>u{%Znb^ohfbGjbYo0*%pI`ap@gu|dZ^`ijZWN3TWw!fwHeSH$U*yEC!!+D zbCUYmP2@3%@sNHg(v?~X>RSn)(3uhnyf&>~wt3%n^`g<78jf>wb3Y0JPN?VwiH%0G z2l5IQQE>gOtitW?Xsx8qROl~hV{h3~7<+@>=9DG6sT2|rD_&XACaE5@VdMpgdG^rM z2_gMEAq!=w#eb1LJx^^%rKRFo2}8Q^s6@)X5ShBJ)?!fKeCE$FxdWna<Z@jNPv#z_ z)TiR3Xa`9Vr6CAgcBb@!`&E4ZT1z#b`!$%~Euu2<Q+(>_IM)(p>{!g#?Ro6^A}7UA znjHmgS5#5RC@<;QVNb4PV2dhE$iOyN0UCNho9@zO=VUhph^X24R*3|cnsh<HCBzfX zG5j{!7AJe{#MU-E0Vi7W&AwFCO_7W%8yeRf_UmryiVD)l{R^>5H_9<P=y-wk6M_)8 z_+92cV(PFb1bl08MUiqu%jB{FLpg2VWXaR;q7Jd?FWCP5b6<q%W5J{1kMFm`%o{tk z-z)0xaTXfJk5=vicV)}EVnH;>=Ap$LTBZQ>H8ow2%koU~H*<sEl<}r|B1xohW%rYx z$Ls$`?)<kZBxQXVaQ#ySp?@2782_mXrXI$o4lb7VcFzB!3A+ES3BIfK9MX6;^-U(_ z6bvM5!8Rkcfy<J%n1T&(Sfq+<?3pMOQ<Y&~Z@Nl#*Djb0Kt&_o^SrOgU0;+oR=8zC zVLCU8t!C9F?veZR!X{McPR_AoD8u?SBi$siy7crMbs=ciPi<4~!tFb*T?r)^PsxBo zN6$h|4VN=|3?FQn2gfF&-M*WrE&K6z-C+9uF5(9yE>f>@Tl?UZrY@XoFkLiV6B6&N zj`9Z%1@!&JoD$tf<yBU#Yc{YSOMrD^hxZ9>uNe@@mM`q$ESv!6%V?$lz$}$_rG}nm zRKu)gBq?RWquPqaf2@kv;hr=t<`k=kc$jDH7plN8lNWf<TNjCJVZs><nBY^}K)5dy z7qv8ror&1B;hdVP3!&WKIy4T6({-AW;AOR<VBCogn@(1865Xk5+Ihq`xS}&-4P7Gu znMFrtAV}>8K+joUbXHx)QcXEJI2}F|uzbyIj<8bb_rXx?qLVU{E$`f3%1N9d&OO?z zibC2(Bq;f!n?$A-mwPOvc9jq?;ve6ZzPZF&Jcf*0bi|_H&cg;+rb>>zcN8OaMN{Vm zEiK7pr3<yg=G&*w$(bU_9=koiOpr5X4@a-9Lf5~M5b=skdGhOSi%9WSro%t~+5*&c zz)t_Y>!*$hnsAG%%5WYQ(F8~P6_Kr_Y+)KtyXItNKQxjLWbATO{p811r|NX%M0!&h z#f|_{!o;7~TByNzzD?75R95$$F-3cOV<1CG_D@xLOC{uSoDmWHYF47WHZHOfc2IAE zz|f5yFW!Iqwzx9xjRLwoI2h{wPIFv!-XyAedQtdzcC!1F4(v?QP+YN)T?ObY`<K>^ z&J$qPsjzD30rFP|TB?7T03s-mon1ncmPsv*)-7kU3md+RbV~LVFsBpfRQJcfY8mS! zYE@%v{M5~S-!^5+_ER~n+op%a5EeGE41d1<ELZnFPc^kP`FF*8c{#cj%~AV4FMdbm z+AX#O!Im_R^!)qAQ%|j_Yphf77Xm}a`^8@*j~f7{@|tDst}99*LFf-JmBtwD0;Y<H zXNlkDYqp%8;59%g>8>m9v|QD#^4Q#uMLo|i@PAfez@ewyaa;fZzH9&h%>Vq}OiYbj z&HuLuU-MeJZ*nB<ep4^x&PqvHWG){UANG*vU$@I0yk+F!wW~`<CX7OgT1il~m2?04 zRs-At2}ZUYJzWi^Par{}R4Ig32?2ukeHdEfy=e<?ZWrCCGkHUi=XKvl+4QZG5YIPl zfATWHk7sjxm>;6@3|_|bOZdR<1<Aif!|&QPUDEoufx1f;^I0U+3ce5lE5@sT2A{=) zhabh4p!po=f93lm{BA_$CF~xZ?7bL7^P2dBUxmA%6Ea~X0Lg)l!{Gg}8T^9R-~`%Z zffL_29l-alC)@AJ3n}s2B&6A4WZx~4fxB@$%=#<+;YR@7UtL;jq<pvN!h7douT5l! zu9Sz{FT;LNT1Dn2VBYP1ouv${H_lf=@;JO3d^(pun#@j4JV(mcazprdallhD3LkN) zrJWZCP~Ka7gS?&9g$@WumMTcJ6zF06bo{sv%TY@IC=;eT5gx}&boLh64lr^>)*8<q z4AC-q8?nkEfKvwocRBzxU~b`kB^R>wxJj;GhTmhiBm`NE38+MzCwFBQnehdB66ypi z_!PlmmZ@U<yG$;kHR6W370C`9L<WE;;nRQ{4nvs<?!x2F0s<I1NpHT&@88u)_8s4! zr2mng{vE&C{{s>#n6gj#EyYRU%@v&24v}!2ZTALJK^y`<o*vFGocc4k{=WWPFEKE= z{yctIP3`n>p7b;+`up&4b$8O^FG*)dN6)8=%MRID6oGa*e1J!048ZnWfKH2*)rQQ{ z_*Fl!44~jl!^GIHWN;I)q5tnLBer!_NpgrY-)qhyv|obmPxO+}p;wUzz6+)a*~=r{ z=ryDoo6}ibCe{U(!n92f=klcraSS*X$qV*I9(VeV#d#Nm5Y<d~iCokUBfQJ9(N&n3 zUG3+5IF9eX#lhIG0EEzoFb$sMbCeP)q2a>OZ(gyLGn$hLUZA%&>(Ri%&Q`b2&aiF1 zc0VVuxOeBk5C9Ov!~VoOj_CBT2dJD6M2obrzXX=za86+YEAaT@A>)hTdUW#d?;0(* z27FocTda%)V#XUwB-b^h1MmLDEDzs~pzRge$-~oEkjH%_OMGt`$VDC?<MLg3PieXA z6f7p)ZjY0Kl#i7b#eNBr2Pvd1{$bW63zFra(Q%$57QV=9L74fhq`qxZ>jW2u2?hi4 z;<FC@+o9*vyMXuuQl_QH@+(?w*TI6cbZ^xMWvo9h=*-$e{(NlhwG8Aa_<)`$Po)1{ zSq|+b-@|9t&gQOsHW7agWPZe%B<R(u3gT((OuB32pKWD-2x$W8Cx<WYEatVH;w~C~ z_+YHPKHm&z9x>u?17{Q{j2AVP&&{^Jcd>D}oFYE8^t?=2md88vS7H^QFf3OcrOU>E z+c=)5_=Rn4V|!qlsLCf#xpP$33;vsFFc;t~&uKe57_c*3(n)aYCV6WLZ{<GmxZ$h4 zHRXBDwyh1pV`2O&F{Q=M(p}DWH9S}yXKApYG4L3Taw{P0DRaumRm0OPI0i^Td7hDG zQ2qgRz>lu~axCwIx2;uoD{ql?2^%Z^zIOHI=xrY8t|07kUyz0H_+h>M2H2zyKyhi% z;^jqGo`B&lG6yYcP8$^5ateScVXJBa7i5X-jtfjpKtmjq3_G+~dP9_8t4T>0l|?T~ ziyfGjJ7Xj-YRh$1%x7C;Bcsy{0YSwqKSSr<gV*=v=>1-eD+Ey?IeU!$UVG!9orVhx zUfT7>zJUUK1@j8T&|e9IUt~VnX&_-BuaT|avrZKl<eml_<Y*w8uVmkV)_uUANj`yq zJAhvkd;@F_ohR-GGHrM;TE4C6CzK6KY*|Q(d2cQE3hi;B*s;9jLdv`L7u*(tKGLIL zG<b?)T{8M;WfAqQ&B{Psd6!ZEpssxM2@ExnY*<4!1^c-+u^ksK_iM!VTup9kCV|FM zQR||U%$Qe<k-Z#h;JQQLk^?$zi-1zF0yY(RU8!1wy`_nRn_!DTv>51KAbDUI!ZWg# ze&Z7nh->HX^8{~BeOYrjHmn%zOJ~xkf^5`Ua`@~M8!(DxfAPR}T1FD3;l$sr*WPy+ zzm===9y0jKuTWKmC8O9+@?C766$gjXzk^N~RIY*jeXLW+#yud6@|Q$q+L381(hCps ztc!oD#?oK1EE&a%b7EABNJdkrTwL@5;52*kB*jVnT=f4vw&aP6S0mx}!r*QmC&ZnD zjC)yd8w7r3r4fRYtC@NUD0F9cpmtMARUtHeGlk3ygy+@BL@w5_NVw^RrI9}xy5^}A zo2VC&M4#JeIi~pFW*IU`Y|K6gmn_+gvYg2lCrPI8m_$ZYqI>y?a+Qe*h4REw3NAj< zbT|4jY54<T);=dM{vc0S)aS>{<qL?d<h8GqRt-h+!w)@dSP9Y;VDWCJs@yI-@kSys zR~SHa=Prx%F3DQfNNKHV%vM!bcGMX0MnN!U{atI!QqA`qbVS%tMg~*fr6iT3%%ZH9 zs_pmn2dg^)q`<)Vb6&%PS*s@_>V3LClN{@BdV(7!=h_wu5FD23u_AR}^R2^PNZJkg zccM2R6lof#ISA;=%{y$7Nl6a7zqwai^j*D3{e@huY}I*s$-2eOom+QUB2;oc*Y<Gq zEEP9i^*q<7gUdfI6j|{io#~u*omn$eu5V1)@M4fMMR-p&vQEOyeAZ-Ff0m*(Z+ed^ zMU9C0a<4`G)Xty93ocQ0`;U}}**CtiDbe@~aUB?6^xT68P~;`7xp;IeDB$(keN#f) zPsJ@wxzLLsjx*7?lGGEvz@RSp$-*Gj>Q4?6hJZyQ2FjA*gv%54QXq8`5-xG~Ov9Yg z5E}KLl9r8JtCkiMEvX8MNHqVj40F$e`Z?5Adu<uXPg4p?^c^h;DM6R&jFh?P1f%-7 z6gO3=E_&fftc*XEQd0J=N&!iMm|<=l?Nb)tS1=)?G2r?d`V%Ipz@w12YNS4&q8=8t zf#JPXC08|aQSU?>cHLB@-T!mGNjVjT_!PY+G>x^QdwZ(nNGJF?p$V)F19Y$mbfjjG zT>-(kc96Z|3J1gb4o;<|CYUjG8<_YMU&Xy-9L^3EKh!Ui!)XP9cW5N2&MGuTumP0h z6esdlis{B5b?Y}z<Wwi_LS%F4ouI&O?_JQe%Kyh<ZF}7^U)tnRa$NdP?juJZ{Wg9b z!^Hb`<s2vZ-||%B&HMwgj|(8V{*4Y*4gE~3@5Q3wsFc&3%<WtG_lvI;e0O(hxxQ5d zL{GMT8vgOJCM9o2PWxk@lGE6m1h9SPv6oR<`P(|W6V=GMcctCrGk)pBb|<}6chl#O zWskhGMq@DK8G*MnU$#9-I^ZQ(ybAt?3S&M&Mi<m3P)$2f9z*|Z8suU+*BgT|B{?u; zfb#~GC_s6kcTD?{?7U0J9;OgVI?AVBsuT$VwZP=74ZST&*|b&_dlK%k;KWEwdcx=N zlZdF^pAPtZFhMKePWj=^+oa7+tj+Si_SRB+#@0JUxy-8VV@SzWBO*7W4Y-rq2&?If z23k4un~Cf>9IPe^p6CJXo#0E4vep{E>{WP+95vC53eb_^92psMn6$yO3bAFT0vlZc z9+41udiZp<Wm#8hGf}mgo#d*ea~dC_jO)M-pAS&x5C93PrG303;3J|OaHoxcJ+JGf zbgecHs@S3-m{b+dL1RKK=iL<zv;EV~^R@k@!gCJc1Vz8cwO3yLF3<+!JsxbN4GXa4 zC-G#jYkuM+YnY0Z{rzk=0cK4T*Rzy_3?kKwlZP5IYAVl~BZQ$Vn)e+i1f)Ws2p9I= zvylg3Hr_;p@J_<>8Oa%T8Pt<?gAB0AX5l25NfU`ClgZJDjhhj?4a5BNeS-A0!Wv`G z$pjJAxAO*_-on#R4y(*KI>o*L36%;=uj0W8d{URv<ElEOs*`Nm!}fm2#Uztz9dI+7 zwIVZ^UM1no9qLVqY9(Z;u{7H%-O5TPxPhQCE^GUmD4NvKrcWB0<FG%phDO;oZ<9ZK zi_LfXiG8M!&<;L6j_>EeMei6wM~P(TL9Q;MudaD7?ej^Li>zy_*s!A9J)nIwa9ohi zZNW^}$1|FcAZT3DG>rFc&Bchor!l>FU%M*~gjjaxll{kV>3Nj!cwFIwKV^I|x!k7l z7}@Y`^2Iq@GUE)retteJlS!Sci_&7t(io8^y-yL;TiZJ?b9FoX96Vfnl#8|>#JE-* z?+eg;u=kopuXx<KDx*w4ZZQ8~VcxVa>tpkC5x%!g^Kz65x_Y_6RI6N5kY*g@DNZ<D z+kZJ`bQ%jS3!z_sx8$n6qMf?SPuNyVF!TKB&G6EV%IcUanUhg00M-SJrq(L;5_1p2 zky#wE<$BvP`*!d@%?99i0h}DhfN#uLs;AuuxrIRylf5YOvv_SEj;vKl_7n1}22URh zuo!=Nq;ckur#dVg*jJqlw?{6OG96Hj$RB!D_6ik&MBJ+I5Y@fX03U%!#H8lqv#9}# z>dJ>e4s5U$X}ORF@`4=Y0>NR{1&KZ7Nn+;kB=n8OGM=FEycEsxyxPLw-U*1_oMVC; z5HOO%JMxeXpX@+G7CyDm`4$ri=S6~F->oJ{3h@_YHN)omCd|PmoQ8hIS_^!v@@_re zfsvWA4iTgpIH{^|_;O{>A(r6}MffFPPvPkk<op8e4`!7Z1$mZ5IUA;8b|Exe%7VF) zCVolCxg#3mLu5oGhb94Rk$F0cBX2u*cpUPg;B6P~dI|vH<(p{BfzO0;pd<9J2(p*$ zPd>;=AfK8~1xz%dekKzkH#Sm1xRK3c6DO?q-h9GX+(sR5Dhy&eNDR&&$qsInFgI~4 zfCtu{OoK2?gVCgeQI3O=q=OM^GN?9E6!9D@eFP|#<JiG%%G7cz{Yjyn%L61Ng3*O) z2N&+e^ix1}ZUbK*3)#od7*ozkh;mhtL#Id&tex4?QzH4@O;sNl8gZpM7R<))U_J$c zD%7?bA!nnc7VjCLi2lB^M<xansNgHRd7>lG<0YB|T%93s@EF1Oa?)}t$Ka2MDY9K< zVIfq_uA)_WJ`D~;Di^I!sK$K~%Ts1Jh_;XDCL^n(>E|{$j|7EK#ERx#E5y1FJ{NPS z&DVzVOSRFN3lLM8>1SOb(2acFADJLt43)to5zd*&(@p1uvuvF$G@UHo56+%19<S@i z(NDJwlL+9*sW+Am%j5Gs@#CSkF#{i}0B*gPFD*64mzyS_MZ%%p_nzs$@Y4Xz7cy@u zAU=g3h6WJ#40^%LEJAp71N2D++#wA=4?gLZbSvns7sSqX$BvQMo*I4(EA;!?ZqsT6 zqoS0t<OKnQ?%)VgE(j^$_IEBz=E>0h1mv2Ol2?*3KSGxBJTI(uPtQ<sC_Jq@7I}w_ z?@lgY769T2wdQl})bC873;Y@doSPlIRY!O-)X$w8g+1~yYILWgu(%^2x%1%$0X>Y} z=P<2C_YgY5spFc>S9w?{TGNIC8TJl;Qf|90rrsOLd-{Mk68HO8vyOMHpsm<eC!)7o z+GH5@*x6F=3WO2(l^7$FRt?zoaC2~Qe8O1ul>**i$z;5r+bogs=i5%fsVL7dfm`P1 zvu-Fz35_5kV5gEa`~=<1Y@wKUKwh2F4fnf&X^io9uXb8bd_&iC!;@G3+?wP+rcS<9 zaFI$2^t^Di_4{M<g?8Lv1!2DV-q!CzaKkB$oGM*SJ!b49=GvwonqkV-aS6bvT81hB z{LaH!<vio)?ns9I-IaQVw>pv)agZGTGMjP*Z)+dd_*N6>&=#E2l9}@}6yNG=DTs`V z8MV2!ixhBdc|bz-B0Y}G=he_GaZ+qfBF8G@0GXN0x599yz*MwG-CfZdb#KHer8S$1 zSJs?~(Pg>$W2AvjCg{&Hur7;D=mu89IRdv|?rScoy(WE*C#0`(h-cY`@D`;0#UdkY z@5(eE_IUpmgliH5-~1=wvm(hnDqJ0d)dbwr%u(raf6u(b3P&*3H5je9j5H!e0SVGf z3ktE*JgPNu5a`yo*ZxWS+pT};mJT&s%<k);v(pCve}t(~yl%uYHKv@0BkH|G()GrL ztZ8At$${C}5BVi%<X8KOn6Ag&Q}!v&^<0L-s3HnVdt;wAx8d3m!e!e?ZQ_+>$=#{U z+|XWHWX~iT9(OAOXo_*eSi44VX^Ycz)2o3B&kKr}YZzl)JH6)#rUd&HTE=)A0<Pdi z%l;b`0#pUnikO*JnF5Xx5z$PNmGGoW^nlN*Z3KE=v(RM~@?_k+_BR;Z%_(@c6#i6l z%iJ+ptZy=-u!_JRt&L|>&d?eKR1zgI;A!#_o=h7OH!`^DTA&8*TOk=+d3MIc@3Gn0 z@uEeX37K)g>9=)MEgxj~=~&w!(*T87q0e!LgrK2gRwM`IA>w|pRql&P7!EiW$BRc) z)FwI7LM6J9Ckw#|a<t1=O`Y&3D$JMxlM{R?Dh<`0`|!r7EaVZnP?RbjRic_V(8tay z61~OwMC*x>-8rH`SY3)>m*6(_fp$=l1M!?1`ED3)9AiN5NU0zv2lu+1yEjBLR?A<E z#265-pfEEYI3Ro0;AY;3yFe=vLl<^;r!X1+Pf#-r&c6iQBat14rZER>#r)gbQ;-5C zT9IkwN;VZDk~k)JyTjObR7b;m`3gMys{Y}(3ZjTydzOzE@JeQI)_8+LPyRhMdE|)A z4q>jKbac`j;}|lI$-Plewn1INiNsb+TiZJy=$25TheX;kjC`kJ8u<Ot&6wfsC{+UP zy=f-s;27vH`JRr!7}hcFKf16RNr-sXFT74iql*%KqIfq4JyY4UYnk`P8ACMqyR9j0 z-tt|nl1EKD0w$Pn^zfUs4*MBylg*f88x#1bR{IxGKvzecqS_eX-$=2Ew<3_?<9!_~ zMT*N6B2}iGOyCDf7YfG*g;?<*W!GWPTDAWcAi@t2+B67pWO=+rE?N6DYs7Y<)Tdc! zKX>4Q!LW<s0h|yC?sDC+U^4`smXFM07cIZsa%|Lq&A5BViWfjhJvEvpPHnORN)peG zL2Syx@6e`wVJpHgcl5?^|D+6+E^t^ot3#>2V=AA7k%iFS5XF-6v~zhXNF5_}XP={H zw0>j;joS2FA>wfFU0EC<3^dSh3F}{c8#HUJFw@^AnWY6O!MS=-O3YXlL6C&IquOq; zJPIh1)7`mv0^CuJWRyIa5u&BR+x^9v@+4f*oto}Q?v=@?XvFE>dZM?}m!`ivG7F5} z7+L0pF%hvvnco6+=l=ul_kh{yi@U`rI=I^~lHO}1Fp5WKt+QhsnTW+_cR#?&ZgrF? znCQ_l87S$Bae*7h461c;P^qWC(frq#dXXunXR(m$TFHPs$&|A!&ovjN_b#`@XFInR zX~zOE9-3i_PFWhN2;ExAv+|3yg|b7)8w&L!H?^cuN7C%{lT*_GJ8}++=$;Zok#nmX z%N|tbR#fXqzI<A=hz5YpMXtleK>d~WhRcA|D0)s0W(bVj8>R`l#KQWvk{E=d{T^(8 zP_ha662j_uDY-Z;KNB-&@aCOCs&frgdzy%jBm|v%^iP|)YNL8d{CnG1ZuArNbN&IY z_zt>hY$+TTb;?T4cFvqk6m5p>C1kq>+(?j}*H6!_d|_B`ag(Rd*J^Y1rMXfoNes=n zX6Bzu=1EC0;w1=<PSIpxT27xFtD<L}?__20qp1F!zeP53vxu5C$U&U&O;g%}#nIPJ zcw=3*>uo12o`;6aWXAks0=jvutTu2o+yfQLHpR;@D5b@+^P-|sk@(aaav+|Iri3*} z!%+1~!qi<4IebPmZ64O7Pkh!)C$4m%DD-HyNTO*X=_$l}36pqJzFI#S!~yK%Zx_2t z<32QHAm1Uy^4^rE*|w~s?O{tpZ}Oj=#x`QUo6_l)``Re5x*flSefq9k?n2&S^>es~ z$(DY=8gc$Mt(=Nzzr|w|uG8>~C7)~QztO_aQav8;^0<|dT$2>0dDG0`=a1qQGT|5n zxviLk(8>8U_xuhfsqKEh(c{n$@juY(ttJCAOc}o7)nv-VV=-2(WVe)ezH~w*ENN@D zjepV8Px+T0AXK4|t4pmqSx7TCRgH!`O3gmsLmf)(otTZe)rxd)X<S7^IDkR|a~m0M z^nfX|4I`quA0!n_CDjh7osLBL5+`?@^L%fGl1Qqh7KTRGED}${eP5>RP4OJ8cH!yC z<|*|Og_kgAagn!}l=qlQ_JK?37R$f3%GK1<b<!!MWoQQW@O2snlS#Y0f^8bx<5*I$ zb47X1AP5^!dBxB?w{2p}Gwy~3`wbDAuEt{)&Gr<ys+)zXV){t{siizrz{#PQ@Ya2J zCe@?V^$u1|85X~-vTaakB>lc}Vtq@DF-TCuD$*V!$}-Ezi0M+EBQJR;%qK)=A7Liu z-$5oqCzF*=GSAnuBNtJ3o8tfVIIGeksY&@sY}TGoxI}V2Gp1LL_)|iO#FD?Pr2<ak zJ$BS#O@Y95Y@{bHdywP^Up(!?-)+XP#AHJvug$gqn1bdNdN6WZ6)>WknRUsXKx`l4 zX!l6J$!^obyjP8^#dW~grKC;4?q<qY21MwVi=}RNlXG=6d>P8##sY07{nf7~QM5sn z3U;Z5%PwqhZXNQyvCJRRFudQ^d#9_vYaTcfw`+MHpiw*BWRkNM$J}hZC*1<EHucvB zzf<2$k~I)W&Z7<j+ZW;zf;U}uDd*a>Jx~KXP3r-wpk@`G2&T|4w`Y)DBj~hrDA6c; zs2)gm=))svq&<h&f*S^l5dGYgS|HO1%SD6gcjA$!@;EJ`jpB6@y5)yFk{5yezfd{Z z#F3G_oO9NhjT!&-@I@lB!C5kkJLl)>jK_%kU()-~{+Z?pm2|++np#tvME>yTNb%26 zZpGN=s9ITFc8bSoLL1O!CK*eY8*qd|Qta?dW%Z$JbrhDuif=e4nR8D=OlZY8q2S!J z{UJ#i=JGwF2*Zp{L{=l_e6(@o>(Ke<Q%Cv?m4qkxyi;>u(>}(1q2TUz_z0SV<e*u~ zT$?Yx+VNV6CCpALUa|<&v*6m3i|1K|DhQckm)Xypo-#m=20>>rJ#_q6edVc`tS753 z=WFesi~wNSTBGq!IK!=Glt3{QqW*3~(%PV1u|?2bt{A+lyq(exk}PV!jB&u|X|>Zn zJMB_GSW5iPy)bdSEW^pV6`2?EnGWoV56q5-Ua*K!(8XNm8Z%3ykQYI-vcrnK1NV_f zYP8MAL+QqBbyx7J)RZO;51}Sf$8S;x8M^>3KaGLfEjDeUaU_j$BNbVn&w-G14M0bo zAo*mea_~yaLlkuqB)>xY!Ixl_r6FG|dE}+>n^s+**p67M=NGAF2iCGRV>#6F0x%~q z!-k%Os776skP(8ufGk7h&hhMm{JIal5O{*bE0LF@tMf#2NZAZ6xfSb%;q&9Xj`mHW zkoZAhy;x86b-e;3EY0|gG7fL?E=k@{#_CovI~8Irj%jlOGFVZ(5?I0Fvy_G?fW<9= ztu1$LyVb96?wla^du^>*H+64Lw5BaD#j3ftuV1<pM**e#@QRRCzIIv0Xof<JuX2!O zJ&3)jA1!3_?rSXqPjPS~VCqU7VN~fUEIEfi2;^Rdroe;FyXKKFXuLfgJhjM+s9_9Y zDUFadl+&yP>#?Rh>;cOs04ri_#xGm3Wn*eoT4+n)4|~DFqVXqP2ll}EIVaZC0Mc)H zi~xRZo{#F+$+KQ-E%8}+HTNzp@eS?T7MFjAulO%<fn`h!0@!9P-nen+mi5(i)b+v@ zz`k*;z{uWO)SA_owr2AR0ND90w6JgE%0&{rb0*@@lEP|54NFtZ1)99+KezU+tZam> z{ApFwUTSYWvtoZn8(*|=)3$%I>%{B)h+Yx;Xj|{son2#ODTeMXdEU^PUi+)X3(JLR zK))_la|=WVHgE=Hq@e2G+?zuQszM}3D*{n*1>hARhCOJt89}_YGe*ZyAc38C(|2ye z-(33WOpEpR8cs@uMWx+6;aW(=<?QJvdk4<CWWuA>Nl<5nt{u}zpmbTaFg$nG+SI#r zi3&?zDE}b4(!d01+L<!*y@NLP<EVU=1!dnSI<0i6+9ddE_dln<hF)N$cmDuKtoQ%` z=>IwWb#*rS-`Q`krnmB@1k&$rei3kblMiE)B$cW=NeNU>gETFmk<4*L$WrVv;|fuH z3p26C?s4Cz>wHXJ8l*|Joa)*NkJrch<&ELzD1ovQL+nUEw6}!1S7O8*+trsV_>c)& z<R<ULlh3I=%b)czOs_uQ-~-6JLHVz;Np<cMPt#K{4k%vwvq6FieuNHRw@r48A4iTL z`(wJV68jHo{yqI*AFw{Q_~Cs61F~6n13j!_k;MrCBn?U$bB=db2LC`!@V9FF$qq&8 zFA7O@rY>EJJ274l-mUHJ!FYBDjB|x1e`gL37wCIi)_7t#a~YC5O5<h*N!E0RA;H4y zs!1ZHgsCI7Cepq6&LbQZrd4>E2loakCWuUcN%O=%Oj%}G!X<%`>ja4+29a!8^%gY9 z%p`T_IClx9K_+&3etg|Q`JH=7qYjC(hZG@86h}gi8*_IqSSrwb!RJ#~9AtQOxbO}+ z1cqhBB0a!(`#mAvbf|s9)<t`9jx3)E5_cJ7bEE}59d+SXbp&QzTNmxp`cRy~5*S_4 zB%*<65{RNc5eFD$I839bnp@;Z9T<H1GJc%>Sp$RXtUi1g@$hqGtG5n}T}*Qi-gc6r z(<rR`z$ns8h3XSrif<k)c;7+VaB%W+@?@(d1NW0hS7#4Mar5I20O;U{lapr`PX;jP z>W9&f)5Q3DNyyq_;n}P(&LnLz3en7UnkdxyEBeKXs7+||27@=8SnNlOyi8*Z2Y>z| z!=jTPtV~2iOVjoRTfh-5`g$ZFeniQw$VzQWSHJ9wg!tj_+#FDm-59BSm5x129CBn4 ze;;y4n&87BmpXPTt^*F-J>T3on7__Cw8N{XgZr6VTURS{eg8csoFR!K{gxYFTklKE zT=Zc+ppi+NmJuQJ5~G8xACWCX@SVXxghnRxsEB=BP_&p8v5H9E)YeJsFLJp_*Q)#~ z*OQoonBvOqlu6qQS1OlkzJuF}TJ&&o47}CpM*WIUz&=%dPnt(U^&>5wq&jv}jL?yT zrF~4CR#*C(j8Q?~WSxRP&CEiRK2^8c5bP$L?t@MsKzan(34Sfx-MmDQ=^V{x%5#L; z+&vc$ACFo+xpp9j&<MMsM`U^})CMf4lO1iu{QWZ;Oq;x&Ef=m533PSJ^=#kC$7-yH z0MT~z&lvB*WjK=(WK^y$b-^KesX;BJ;stc3;NE#Z>0mY+GmjWWjCf9PhZ28kXWyBh zte$Y6{rPBm-07FA)EKmrQ}wz}gV@8DJQ<O)R2%=t5ilLe6}_ma?1<F1d$wzr8BN^l z`E5!9WQ?jdIYJ?R25iMu`xNAq8C9aLgJ5@zbsVO*aJfDjqd0}HpvBk1bOUzPv~IIl zrK_~l3?s%2jOzHGCp4lLEB}Zg457oMtHdnF$ezK2f7m06Gotc~!NXpcREL2C-yg%r z^V{vs+W*z~_jx>9uF*B<2uc>Y1qnRAhJ{R4?wUuil1<V)lZNqcP^5s+WscHh>k*j^ z%%l)SIpLHbWqL$s*0xjr96d#f4}$H6tH=knQp(|>Vc=wV;36%FVTPk=L0v(x&gLYk zdX!vcWv|D&*tWwEb+yVLdLYW?jgnQP(oz4EY4w~*hke)INWcK7TP*yFf1*r0#G*RN zR_`6QNuAQ&OND(}Ib8;}7Yo_%-|}kO@%Wmp-rMi;*}7yszm&mjPwG6^tEZAFA_REC z7KV5qTyu2gvH<|h&#jtBO%Y61$Wbe;C`=gqyc4r4-ux|LL4W$UKUFf#tGidPzO7Si zcih+8T1Wi^brrC*NPrx$&l@@O{vUQ!-^QddjKx(M=U8*`GEU}O=tORU_~&uA&R%x^ zxavZ6x!vyyYfu@A2Mu|v7G@URb-a5(qSR|y#R<rI5;r{76jhM5a@L=9km}94&o^1P zS1<I<vL&YCOa+llk_zh@OsMsfBx`U5L!N8IVHb!mpBTUn?EV7LKAaU%PLoVX`xs%V zj&42V4bW?9EiDY0`6SisVwLnWj#@qc1?Fz%J62_pDli^2ZCQ^wY-7oK+9GpY#}}uh zOu+eEMqIj&e=DIhX9HpM3a>zJ&rK1a$DSLWE6T_Xi+mrqRKbc2VgOpm1*#MHMSCJ_ zu7qJ<&~P$JvZSDC`3cRBnj2)J1MTJ2P$M3QR{e7E46aHu!-{eK=v9m-8^B4<y+!8P z%&WEI#Bpx<lYd+pdgO~iS~kXmk9>vx2Zuj&SJ6<_y{knL%@92zPEhaoi>BAQOKTRf z4Vs4@VR&4O?S;x@7F608HgdJPE4e+-C988uLIrF$i;nU#r}*_IIQ_rKI;S98qiso- zZEKfp+qP}nwr$(CZCkr+W0!4p-R_9)KKH(^r$1sv<Q#L3FEe-Eprh4kKYCV3>Yf$o z^LCtVdQ&|lbvkTFYBE7%6?QnuI%GBZ^@S=eHO^WD)z|kf1u`1K*MTq-8xN<E;V}73 z)=F5plE8XNDpq5CJkV<R(?y2BdbAzet{kAh^%jOsR!+jgx%m{*M@eK?Tz>1MGt2Yc zd0J`z;>$_acAQaqNlntYTxnh|RW_Qb7}Fr^tQmypLFX1K7Vh)~ByHL=hJk|+z|bi5 z#N*WVc<!~55cKIaa@pENjT5pUwZ6QZtrTc(VwzTt{IOdqqfk0e@a-B_w4MV}YMs#- z|C8Og4g)O2!jQt*VOVkY5DB3&)BWCa(8Utctb9~MambLPmi*jbyavEW5)vj7yn@dH zQORtnm@s#x($dYal$>fD=mPEtc{w%XBzcX<C}b}VHMePT%uaKUUfEKD#mD<LHde&r zR5DpHGKv&F6<&~MGDWc+7;(=y$7<Dj?5j|)?|M13vc8wUa4~ykixgI65KLX0l6ZC3 zH~>i{$@nO>I(&qM4{|2WLNHb{7K%YmKh8Xgd98ucWHH_4Lg*~g8UgaYW{!3cI?F0e zj12V=6F_CH!*&5MrCV21<mC`?wi$5WIO82R)x|2N${9K0Qsu!A<8Z}WY*;i|V&m~u z4|`ZN@#^X9>%s~N7x#Oni4Dk+r4>CiH5L5@N$KX=vM*Z&Pm3WmcrTE7k-ND5-iEF? z2Q^^)im5HG9G_QSNwS5Qc^O^#J0YK^X5nz9itXo_*3?^b{HtT#K()!UnhPcg2suQ` zEXs{?E)OTlW-DK*!UqY-%DV=Nf*Nneg)uD-rhtWKRV`9<QNpbw>Qeo=N%?KDQ%b}x zYS=b1z?=5zY`z)u3f9|s2SwqxEj-t{6@h#)*Uo=36IRoql~7;ygqk)fn?+q|e_#z# z{V;dr$H`w>yWAE7KOdK}3YZtw7k=bLr+y3w86Hx3TV0nHFYLT1G&>3@ek@ep)a2TH zm>!8>p-sO#SVWwv^(Q;{jY=FsGu)mJs@Ce8oM+O`t6nK}D`~qyZa7lt`76NE(twu= z#nxZ^{&Pqq|H<<k1_1y7gZ>{#u92g&{r{a3V^seSrhl#Hu<9$`_>S0yLC;K1KPIIK zY?1gDK&TELlUi$7h*XiNtO);h$3<*HC7V+NR6TawbJ`0>_jO+;U^AmnvFyM6N5!gb zq4FWolkbImIYYV4uEN#hMvd;QdpNQW7uVd2q}_gOk*@bV<U&Oon_p5aYyuHBaXTt; zls1!R{;qA2fu~uu{iE!sh3(y|UZY@6Zd)K5X3)@`bpJ47i6|7u8;l_e0~3vpY(EWz zXHbi6ka;2fQ(eu9$WAR5ZcOa)-JSh%|2b5)L@MSr%))tt{J<&)J@HJDT*hySP|D?a zZ5~7LxNyarghoYl7fS(2*J(&v_4Ha7gSViimI5^r#%zI;D6PdPF*bM-Y{T6jiDz<E zSG5Xe&vpcatb`;dEbb)@+H)>4hWuZrE*fJAbVg(2<qT-ISAmX$=#)!6`wPQ#CdNN) zV0HG2Wypr%&H^r0wB5%IB4%5xX<7@Ru)()+SOUF&e+af%PzPH|zrNPnBut4_`gP8r zAZz@?QEp5W<`XMgvsXn{h4?dgWlr#F(VVb!cIM0eI&*er?`HF3Dvwg`Is_-0giM+R zH%H6c#?12!jy0XV0!xdQB}Gkqj*{8)X6WV4m^%BilpyNFl|D?kJ1}G}JQ;fWuy9=< z&#Z-^TE2RRP=KpfD2zns#D`pYePJ^%6E+hTrL-F{vzd5=^@F%-w|ozbqH1o3;uLJD z-US=WN_Nq1V?)-mfB8uDcx*1y$|!H#EYJy=Lq3)8@0-EB_p_&Q+|EJQ$fU`(xX8nk zU?cwN!-b3U8e$t8qNOn{@;x1iLeIH#_Lb?wHV*0rjb9K{$6n=>Ahc{A*2nHE3KGLU z>8C>#iU0A~V;~$J(94k}!<VP>-n`2~^JmVLdttu_e(J9_j|8pY*E%B{*{4_{9*(r` zlSiXRFb%>XV4P*3DNdx7fTKZwQ*hoUXNgs+>0jq`*?8Pv{^wPn^Qtu&@X`BcN5gra zLzk+7+S{mAU*DbhpCPBmrNPH_&I_uODe_QiO5P;-^48K;Xe2*M8LjX}$;P;?IPIHe zlwhYzBH>MmcptMND_G7Ngqsq!Sov5$kXWGgNX7IQ+I@m8jc--(ZlApb^e5JP=;YwE z*^9D^oj&tUcmJe)NlX-eOrf3e2<cOk6W)%k=*N6uXvq-0sQg4{zp_P;6)j9bX{xX5 z6|=FH^=@!65T_lK?k|J~gGH`^uc5pJX#V_3JK7U}y?sYJ%S?GK_|!+$%Le+@Po)v6 zg9qaK89q9iHpj>~^}d9yI3cJ}=YMC8JAmohqTpQe+91S-LdRlk&}kh^m5nQ9+LELH z^|jn-lBQ0kZS!(jboIgP2{sc*`BntLJr_fJ_^Qgz@0f7!=dMtAgm>RiIc5J#C0vTy zwGmwZyfv`LC)Fq}aweGIC;Oa6Jx1ST@Qt^*Hn6#|qX+_A^@Y@J@<FZOJs7hR9LC#5 z?85lc=0PT^=v-3_V-B;+<IJAj)OTe8H7kT%h4sj4hA5Thh+AE>d-uXq(N^+YWBcuE zhk=Qk*R-3!_YLlW*eIkpGC>PP4DO?a&7)D!Gaz9YKZ<`4NkH4Y{57~d-Xu7d`3C(@ z<x4;P{bxV{0P=pLegFIQ*!cemUx}*Le|Zsnf4vA+^y0r2ezL1J;^*LFF<M47N$-L9 z=8Q3^<>@ifmc+-yLcX7H6dbA9%^37RowwS&xn0h;N?r1eJ^I};Z&>#+x=`0R{1-0J zh6(h(UN9lDT7B4&PX0JexOn>(BJH=aazotK>n`f|8{(k5QQqcaGoT73YLz^Kr~A$T zaa=UrS!ErrY_C;4$Nf*=4&t#JsTO$&+m{Nkg--+S@}3Hsq0<-Rx(O-3-q4cik(!)* z2ydc|n<Zd&dqWCkn>PDbu-S}%r0(HEzAZ??yJRvMpo|7Vy(z?zqO_GDfr%Y;Bxh2k z1!zZVh^hKll@*~Ri{Ep_J%O+l_@&v!GwDl6v`{jE7Wv&5&=vry>BY`Q=b>`(+jSND zg;b%0E!pr!onHAlQiy}13=<kKcpK6kMPfJy7GV`=EP$e7mNBrfOH*L!Q6Qw5kv~Dm zg?fWoQlMV!jS(u1D5n8}LE_AfIzS%LkG+}QfHD7aE#I2lxXF_Cw~y#V;{4GhB<ysb zYlJ~Vff89HgoXiu8ag(AzVqe{`hJC?{YaAV<L=@VFrYR$T413mSfd;pC-b+J7<>Yg zVS~t<BMpixU*P-WgEdnd4LtPM+M6|J@YWm1r~RLtY0<!^k{=NI!^FtjBQ;36qETwh z{tFQdMPLnxC__PJy>y7^H&jyPd^2?biH4H2t@Jt;EYX_7+X){jE%N8ed-z}%c`krd z0Q8^!9%FSXO>Vggg<TUCf5f;UfE`zb$lER$V7_JYI1Hgw!f$$HK`?vDWKjp~Mqd8Y z^3AK}PCL$RfRjbvf8Cx>P+&>xpwqj0{az8c69}{+-J7X0Ce$rJk&-C%1Fgo@4ni{j zuymZI?W2h4Oax&fB8vVB)3t<)gqm@r%M!4N+I@t!C=I_`v?<6^jzD!$^cG>Y8h1HK zs$xjxkgY7y?7GWi=^-m*4!gNTKpQGZLcSv?Y5lXLa-?A3aGEg9!l{vpp)pW-Lp-eT zciZcM{4^Sy&XYWq5`eaRzq5Ndn3w(w)<?{xAPiM)712}=ZfkSi9-3m3`n{Y(=5ZF{ zb;vH8jaaf5adMR{jD1M}DdWJ*IO~k!5ou~+lC5Dha3)KMmc6L1RR91r0o0$^G4z(o z(1V!|2@NAF!JVWyPE!%;4se&48J?QLn-?wpf*en5Fle1eJY_jb92SX$NyqadM;(3W zy4hm3N<WhrY_Paobkku}(6$`XUwgxCfdMawtqPOj6UqviyNgl*Rj#%itHwL{O^+2b zXDT29S9Ti2SNMWQ`ZeeEPAoxe>19i5m`KwQGyl44-{UT;4qv}qli>~UMNEO+dwy9N zXZRtbfZ<Z2C#;f8rs;nDG-U7oHGgJH$87S0pLA?VD#Agb(>k$YE#j4<IqeV_4?y{I zURLnF!5p@Fh4ZD@gtutnoT<TtQe?NuM%~V_=!8z&4MtbA#pI2rIsXJq_0i(Ag}?g> z+x`hR;3{)|<s`Hz+XHoOnx~~<)Uka?s->tS{+odo*Sy8t!@v^b5U2~!DI*IzFe=HL zEaDa=3J3Y@wWyeBQ?Sz$?A&LJ8InQ$&uJ%4mJtiknd>900^Qy>+Q53VAX%yYyr@Z~ z_T@m)fF&%VV$w9`_=$sHqQ@ee(kuWz>_f%TvT|5iD20P>?WA7S<t~R(6=KPwF#QIS zsSm?laB*7kxgOkF@8=X3r{`<g0;Mlw!1h&!{(3~}ti~s*n{_;w;TwUw3g^|gD9UM~ z9Zcs4ljh=8j7Q6LT}lVbOz`iQgAV|5Cz6$BEaXSTdtT7Nxb`k4iaH!3S(TZp@|mlH zW><^%;T*NE$*mkc2}6ydEkcFjTuR>#`+v8P6(^+n*!<eZh>`w>YX8@~>f~%-WcBMH z8&R`y+7Lzfo~>IOWfHI)&bn%@_+utI%Aam%56E`N`sWD&oE$Mx)U8qI@bl$*M*`yR zp!iL32EVwc$LwXjXPfKKm%Nm)c9y$94EPH|%@HAtq?r6$1CTBIQ{WpWv7@SoNa6xw z?EKR!#KqJA^v$bW5FO>YXTg{yIq0IjbUDWebhdMD?lZ)bT$+sgwAp^n_gUKR-i;<J z&`sM+!CFOyz|&268Vv;jCEPH7(|qp!o|o7cP6_y{u|>La<pkT1IjYw~2uP8|phM5! z^1Uk%TAs7fOFXz|lge<rs*D?le@*zoyGX1qL*n-sndC6VD_C^gfC@OXMy(*;zlMk) z2($Zukxv{|10Y&x{1YX)@wF`C#2~T&&_zuQ<bEV4W~~Hj$WjPebe#EdMSgZAx}0ws zXZL=ilOY+#J05h;+$rDz3r?X6ViaiJkO|2d^CbA9C2;dFi0NW<u+x4XoVfkmF`(W3 zbOc2vic(Mm7_g)x514WECuwIlP~N1srE}kBjtL6)fI*#LL?lgoLPhUeZ#+^Qqye)C zJ46u5p|0!Kt36j3*B`i@^`U}oyxp84Mp_e`;}>lqk0}TuKG0&+CjQ!a7r}O0*epAT zNT2m9moYct{Ovz4T1AM>;6nBLqqwnMGn=_Q!C9O8Gx|%FK+)_SC5G<ogY-i6CgBR% zjuYH^$`U_tNtE*}eo)Y^a||7{FV}w=LQ&CcdKnyiF{V+)lxK_F;dWpG<uz{+yxLWb z+p`oibIq0mZTD1Z+}HVO(7YcRZiyn^!~Z^;hVMQP(YNj~q984+j9dG^I}|C@G0UFA zLfeYDwme?0Hz_)?_XdP_;B{ygA%rxbctRA#(d~sjaImIas#FVC9I;amXpgAxqRa1; z7c;`X^(OvkkltcvE4T9VQE?sjNs<7KjJPBesGVv*Cr{gF`_ptBrk5yAJY^un4`ip5 zzfZ8d-|R0SQ>tF#GL4Y(uI^OfBxaweKs#jyeVfl)6>PtkdFn*i*Q~8-+Gn3@>ur8j zt;j>mCEs?YoM&5Z2FaFf-kATLQeJBI+UC1-aGPJf&x^E|EnBvO?ULbnZDQSN8f!OJ zx}+lMveemetqtAYWrEkl>f8Kj;lO=vuC6h5mFsKW98s^J$KF2zb}P|{&dedvQXzMt ztd<SfhP~!#C9^y?m^51p?dea7HG;UFqgJ;Mow+Eq1*Da9{R<DAtGUr!3WVTfP2Aq@ zPe)X}ztl?!0%95w*P4-MudvOPcc~H*HU(XQRsy#!dS^_+(Gs3wP>UK{uV%o)6HI?+ zFQXqLTyR_NyC+=ps06{D2Sv$_3RJNYGj}?zW0N0Fta!m&b0>iz$wz!GqUOv!pY|Bg zI)?22g%#VTt*Vc%U+g(Y;p2k5(;cu#BjYv@=>NfS^5D(05aJW`da5v2Mu?4y9b|hV ziqtU8sGTxyILm3Nb4x8!abU`5NSnk?&e;w~*Sc2&Q)F)TsKT|0I4+GkmIU$U@cSUV zb|R7R%_*_KIUWzz_OC{PhUH1ZaC0pLHNU<u0sgN<Nf@L>h>q80`A7Qsz*asv){-{7 zvC~(#sT@efaO3A$sI*sZ<P@@tFFX5gA6g_)*Ik#&AvVD@tHn%ls>X_p<>K*A)fmR8 zXuYypdd8BKY{S*RQsB6d+Ik1f5cBg?!_s}uLFBQ-vOJV}<3)eyV{RuM&%vOJ=&@!E z{1_4~E@_=ob+5`d@0Mrr3;ipKdBdw3g{RsF<0~5@qqgL#@QYXobnL9rUa(ACYAZu$ z2S0FN_`Z?#@&NE+OHcDr8Yi?tD|%V#2Wv6{@K*ZmMmE$Ax>vtU-D5ysNXMeBKd_W_ zx;>vI3*=cRO2W5Zf(sm-<S7zI4`hQ*;}$0RWN>!0%J|9#m!*Q<X*pN@!_z}T-WN$z z%VE(9y@bIgftU3FtL$hdaB(@Rvf1UD$3iMawTwB7`wwZ3Ds+BCW(Kx)yu>cK8%C%t zk4Y3<e$b!!_+igWAiuRSdP7o1ed}eeJwm3aKRm7}TjNa)7V`u6rQm})M%1tjKq3rf z$ffV@6Plr|J!ATB4{1$vdaOm+FPv5NsKs_iDbrgE7odDKgt${F4Y3g^YzR&@XE!P? zpFNX~eT`dH)V(ti)=gCAmW3Bhp)1pFeTDa&C|P23O^<Z{d9P?Ncxtu%J)M%o|A*<) z(ZJZk?*BfiEOT4AZL&7*K2goTK1W&_YdUURvBortxn8cAJ=oivGV{dJ(TND4wV_Ph z8)$7_`t>mZ$Aj?8CoF9F&_@sl1`SN>o6<7@G`)-nWSD_B(ev)z{gGN7VT|zdvi_;^ zK_h;k@Aa9SG;H`Wvp%~TK<?)C)_*!40L{CNfycX9d{XD;@>gZG?*`<$eT?#G%=`Bo z5Q7^VyB=1G?tQ@aZN<CxgR3mJ=H<k0{tWkzz{ktksF_go0FVPg8)9;A-z)Ch17vJ( zRX#tVCh+Z$SjTMts!@OT&i_yB=%LT6`(W%K;rM5t6Dv=mzkQpoFo9X!7rOyp$~U+8 zLZI0t2G*e<zs_%HRf&dU)*BTVA3EkKwH(?=Pu|_lIwyt3-Wc`a13g`%y((IE2<XG% zn?NE#AnNpA!x$SAZt$a#L?#U5lqO>VHok7(Dc?PYxzF&Nv?g+xwJG{NhuMZM_#z{t z-XkYgEu}c6;(f)1epzJxOLPMyzd3h^IVRV!CY<Ya0>k(r@ob?~<LNu-Vs4{;x_(&y zEtaUy!n5;@4!iX1CVJBDDPqvjRDVSEZup|`8FnhCUh*P>LIC~ehxO&(jCtLLvkSeo zxy7icvx_RdUT}SR6ZgrRc7D`a#rV%`K&=csbSwNn4Bea^?B9r;(s8r8xjJ8gFxj~} zJ-i*=#$|T2YsoosbhWdwyS>@E^$%_6r*^b*+M~1_i6V@bsq|U^jVeHj*$;#8MOz}T zdish^_%xYKC4OTDj=;D(fCjwk+MPR&2ZhAFB)EX>2?sCK+V$)dp_jbS0&0=PJSA&A z8OsD*QNV8Fy_mqsct2PHdvwtL;5cRbK(~3K5{a<u3W?|dvV>WTteiM;VjqWOMR)N% zJ=vW-VsW@n;%7{LxTKe_2j|&<je6_cz}Jjzt3_vMZtR=%QBK74;;L1QaKQ5Mkp#8r zav4F$mKzXWH&@4qSwSF#v|ynfGK}@m>FX{oz`QeaLG;zvLBx^n{@kZ3O37P0K+orB z#zcMrxTyjPyEPZMBaDZ<og=z-2_#e}U>XT0A$XsY#2}2ma4+5Q2%iLd#t<H$_fBBN zeKUhqE|Z}00M)Y)=swDVmh`>(XsGJ_N4E3h-GO#TOTaDw=Q<W{x)^jw&(R!mp+RLl zkG_plawK#do<X~}VsT;|tGQ7px^oYoNYj+SYTO1sBWF){3MdL6E<Zrv=)^B}o;)Z_ z^-L8<S3CCyBrP1d=pR(q9znV{BNJzjS5s7W?*}6xY$Du6;NMsA>wI?1?*6zu+1^@T zfRaJub518Zv;v2x!f`|zU_J(QpKE=`91lVMz!>HRNI{1r`lP~S0$z_sv*`8C!4B%~ zxk(S^48f&c_OuEIAvLw>VG)d=a04<R&2Ts*`7BAIC0l9pdl>vCaKWB{YgPh;I4s?W zYJo}8Cb1jqlHB@IxFxqDJ|O3K?COz%gc>?C5G)=lHxUfclVi(B+*Ilf_Rp}rSg0CJ zvGB^&^8vRTNiqM>oTchMMHoM@*RB!N0R06f?mGJIp-gc_tn}$8EF8MU8qw(0+RHl} zF#>i;@F@(lwHaO=kmv?C8HvKg$8}tDNkF3^F3cy59{KA}7BF7B3gp63PQV%5b(kpq zg~63Cv2mWn__7v}s_d!OrrD^r<3XkPVm+8K1)}s``Ps*IzrAw<IOUwB7+sc#i21>M zu;++P-6{Pte2(qcbiSGKi4g(t{hllV7Qkilv{f84CHDl;?$#LkLtwx!*M*J1R@PrM zZ_XQC`&2u3@_Bo}F8nsm?XIS9<<bw!jrdFt0XN%XZTmXcvFhvASdg5W{xEP7A#ZO} z%z^dn*tWy80dvP;=b(rN??qZ(F}HCc*XtqYmygY=lkV|uE@~TJxE`h|xAsJOMx^Y< za@TC%)h0#17jQzvc1yq)NROi}C6zq{?M~7k#ugH3G37oK-ebg`@PXxpLhD3^@s9lM znIS7of*b#flQd{H8pRmZHd+DsC2%(hI_x0idMZZZjhcaXiwWYNM~{vf*DhD7Omi<u ze9Y{S-?&B<6^3ME7p{%cDC`$|jiaX1<OjMEeQ}-+GiN6XS6q%Io)Ln<_8h|wG5X}5 zDxi+puNd3d^i0~mE6E2H^<+9u|4eS!!W&#{Kcpl_y|ZG*aQd(XOme_bdkx@}k`hT1 z*cWB+mZ}Lj4VRH(x?bH>Jtsxv9ni!gfYA6(E$4wiOJCvR<)BIu8}D4}J#rClf3dfh zA)c<zJ(Y{cjZ8^2^Yk|Gw9i)52RBw18dhhE1snhow;VWXj7IS)VJ{RCk>MUYVI^Sk zO{o#UXP8{3@2hQKSw7o7K8s*7lbnoT`h`#}n5yLu*TL=^Q&0fxU{r^ktfzw#?=1g# z%9KbW6_`KmsF`KS&EMkQ4rJzEWNuhzhfl2IIDH;0uh5G?{wkR1t|b&1jr|IgcW5@S zaP}ida?fiqz^@0$$QR77G6R_NeNim$@B&UrV5g`tVBWZ61LjsM_OZLojms|k<ut!a z{<oHQumH^)qwn4R)sp@d`Z?=5Z?e{JfbXY;Ma+5Cp19>6I)#Z}7#H{QAJcpv6Fg6r zUEo}44`e93N`RVkSDS`n>FjDKbEd9=Ham^Ji8e{P?N&Q9!^eKr!xSu$FIT^OX<YR4 zQ$rU6&?PJTSY7J~`%dg=%^l)gOv;KzaPG7<#vPXtE&}M|T-0=S@C}$}HQIw$T>x#+ zAk86)cFdxmYcM*ww2E{fnbbEzNK{J@4~#JEGU{ZmWW7yBvnk&5lk(g!%_IvhOeoh8 z!9n7Ar`MPzsoRZ)n4yZ0l3gY3zM^d9LdK$B#8fce{zi9cwzd;Vvd>zvX&u|1@pvS^ z%Cs+BN5F>*mnwX+JtK7Xop|0I>#=)8U>fu~PbwUa0({lQ$((+^=ene+2a-dz`>8}B zQ_I+_LBlW<U`ids^lsW;2_+_x;6hF{7bYV7ch`!+vLkY@OOtjei>=!meo=}jZxr<{ zlK55LPXC11ei&SaUUhz$g+HPdLeVU6y6+}9;fb^h)KWw`1Zic#U204J)Ja{?Ll%P@ zoW?T8bUZhNdUX*04eZw@XBBkB*JlNdpv89FuOHe;Ss|ZI{zjFR2)d<!g;4Qgx(qj< z7lI3O6v7W}XKb4M0qQhlg9sDMV;}N{FtXm-6VR$a+$S%uQIAW4#Nm`@w&?SPz_@2D z`NCb5gbQ^6u%duep8|Bmm&vM+yvlyx1As~6mzCNWo}i@ZytAMHi=!;e{bI<Zr+CvQ z&e*YWlML4VWbm}?8Jd<->s%7gUL*03SC!zA@?%kvQ3^&A>fG<L&|s%9whl}YGMQ2I zV5cc6Zy9vPRLfeW6&Kr<@PO*Tx5YB-j&qEM@g*i!t?OO09n$${nIlk8>bqWhis?%v zF%ttxq@b!Dbjt|V%lV189le};(z(jgpE@<zH@NPGPRa{A_0zX`Q@y9i63(iCl~=7f ziQ5IjvSvw9ha!5mso!eWkP7)_F1<zBZCftHQgFaHObCIQV0wo070<Nx4|cu+(^_Cd zbCuLFCvi@3&9c(nV{a^x1GD*b0WuOF6$XF|%Pmm;JLztpt<-Kf6L!Vn{K`e$!oy+C zB%nZ(sj3)%m4(0ah<qBlEHWygG!zR*FPhhQ_Mbrm1{_%A4kB|r%m8to)JDRac0rSP zxPrc3hI%E>ZzxUv69o`~hfLY-PXW*8Ckt5jyJ<#1B^2HbIwm#))Y+;J#mM&zS_&}I zKh<U6?v0N7JWeWzEQSk};Fxx;l;D{3vCYM9WZj<1`9zQ9xL{p7^K-;FWty!QrFXa= z{^ySVMYi^l$~Ac#R8-&QyhSDMOL-r-$C{|t5bAkBhz<p(32tt65!4IcU6cnw^dOl) zw16sd14&mA$;d~B=JFgaLR`OWO?hdbP=!?XuCGa|XgJ>=@XxERLi00fltUcWaj>Ch zT_kVJ>)89}5Ip;{o63W*5vJAr(zq4M#V(Y@>iu`tWs;_8g23%g+(pb<y<P84jmw6` zCbv4-+yx1q*bj*Kkvr-~BDAzB%==&bG0fYbdVLAJ^!;gIDcwpVW57vX_UC#^Ta*yB zW(iSqBK%#bNPOvPUt}&|c~T`|{H^LdnBEK{d@T-dJkt2*rR)Yv#X4oS@}g;({!TGU z*Ac#D(2iQr)T8>tp{WfU!&bjuf;V|Hh-IlnrH60}EenBb?cu4#cK%3~k^?M=pndR} z0U8y4*rnV-Fvw;gP2YHa^d7PGuS848js!b<wI6gNyc^NSZJt1D&v&N+I2>~j6jt14 zUNPcNtn_6y-VX{XD@j;hGXG>s?5pL9=Qs=j^=%X*+r#+^*5}_8wV<7M1QH#$U<JKa z&+VdBp!#GZbv+HUsvc+(%0VY`Q<iEX{(Agj7rE-jPMACPdWwNct|yS!9o(+TPj<bK zk$`I9sT@;{BzgF8OOv7#<5F{TxP|!_5vN$ugBjw<_h!y*dC`g-2YL3Q_fU4)MG#vx zbThKFoxc-jSy9M0BkRX^S*!GNhYF_>az)Lkqs?86!!en8oRP|#c`S%A+hhU549Y#S zmg2T;Mf@8*fK}Ei611=YE@c&ly8sivec>(chXc=E*r~p$iP0_F#<@WgUQBSVgFU}Q zxskw%V5yY?3^b=S5a~HK%yssUswOu&Y)%@LgQB({MzY393I$IicLv#uIzMLCcB=37 z@poX7hO?9gl-PuCJ(zg~!-|Tqg+^s6MU#YBmE~2F>e)|fa6?lK{4bCx$xyQ{fq#82 zxgo!@%=O$*`rt7;+Jvx6hFB&E{nj{zl#bZeRuX52@w<^w%%)ey1qYROU9~dT6oU*0 zcyS*<jFO=Npi@dL-x}yIbFv;(Gfw`hK6gfgq1+`y5?ieFy|+f#na)6VOgrAwc6iEX z8L2~@8G?CAdfu@Q%bzGmrGTwISgQids$cKidjyI#az%JqEy8}@ea#&`L!L^4M;4OG z<1vz33rh_YbaKJ~f0eQ5P=d69#iIquUt^e7LN^1pyTxZ^$>+n9PjZdy_7HCdJ}auL zfH+<&Z&ZnOnKJw^y%5FXx=Vn?UYlG}j2c%m(JPI%S#ej0%-+zxS&|Ti?51#tweZzp znDUvXsB55iSsZ`gfsdlvP*=%@QCW$Ll6I4953dtgRyZCd+8`-rb8x?$BW!?Mwlzzc z#x|?>>Yy>g6^+tQZo`SQUz<c%Op<PK6UM|o{l<RB(Yilgxm57?cLQCcQA>eoDPwB1 zfi>advVEG$?6Vfy%=QCMR#xNMf@vOVRo8?YTk)dCsyLC2UaPgW$>m&D)K3V=FZe@p zlaK7~g8NxVWlg#5D&Ng7M@w;UmI7}@L%R$X(_GvNwr?_LVpF8P)QsHJL0Krw8CtR9 zP%T^k!fGCA)7F{v+{<2Bm91H+t6S0{3U(u;t}Jj+?FC$#XF37XJ(M|PKUEpMSl-=p z{6M!eHdFay^3Cgu=a=!ao`x+QBV3fdlBN*@e&7gpqB@0}HR{_uTa~0v2pCV5chOmT z&+4@N=9r)w?oALGe_+l`y|Q@N*QhPqD$e(jN~nVrgd??6nahzSs9thp-cZeh6waRB zbKo0oHtCZpwy!;{4%1t}X$HrEwwIu2-Zv#!Kz__#FTV`rP|*QeEz((=SDL>L7ts2~ zO0+$OY$`^%i@#_Ozvh%bevcLp`|v%CPc74*MF%xi#ame)a0VLe5@NK6T@Q>cpl5(( zPBy|B61%aXxWokWenb#gAVOd1+NnrDUVO7f_HWws(r(M<x&{6%#3VO6E*i87k+v*n zWh>{>X5}TuC+Ay5@aAtV6-gPsPZGs9!<|hAuI1O!i7Qjtn!W<mXC8LDdx*d{ABqY; zv$C8Nfxo?r6Jj5AM*!6cyogUI9U@u6KR*2YqRNL<Cczl=f;lJCsP4hn?n(SiwbMVC z&hR4!z@6B9Jq^LSp0EM2Rw@{q{VV^PJDbT>y!2aQv9fhztsOwKR}ua>awf}RE**g0 zZWy6+-{TES=yBp=P=2F#S7k?eW$F)_jTGHq$8MmwiQ#1~!PvAPA1o7RsS;zLt`>8J zgZ<ON%u<ukSc1y`6EiS{Ran6j4VB<{USH_>k`zW0sR?E#6S}df&O-PR0NSre<HAx* zRSD6`=sCJmFvFT3Uc}@-;)aytmTVX7FveAmCb;7xX>Q4wM38GUJAwV@EMDm52jD*+ zso<?ObB}(ppO0Vc2kk%Ea6LT>TMK7Bz27ZLjjGM>?i=CzH=EOjepnZ^uNi}t`1W`A ztpu!*sqq|`Ps6NPXkEy7_6z;kt^4i%5fM?$L=#~EN+>yWg1^b-O5|`~p^Lt*3%+#n zfbQzqCdb6-|2roZU#>j<#DK!e^&Ue#0606}-WL{zc-T+&y>Jvo#HO3<<kKwJhU`{= z*9JbkQ|H_jHgLKKxwWeMTCDe8g?Fpgml^O9mnP)2<(72K=86|rJ^arxA7+wza@_vj z=knVy>~{k$g=I&Rlvlp38}&3QXtofN7PNm0fmgSuye8b##}O^ZgV6V^LCdbqSg{uu zSQ4?JQELz=Y9X~`NCb1)tZCH>>OI4Js;_K%lYT;0uLepi9e7efuNtLdzySd*UFuU3 zp&!LE`D{#O9C_qA1c<(lC7<!Z-lsjt@f*p9QyZy5i`0$)nHHMFHMBfo&dMFKyyGEF z5js8wpcFDZ4Mig751qYgKh-i|=Pm)`i#dlGxG-;!O1SF(MpzrQe@$T4>UzbK<C9|y zCCIrGvtb~JZ9I%}Bb+-FDP-WTdi0wtjZteB#b%cVjiI;G|K!e#r$=imix6EC-SnB7 zrfk?Hbgb0h%$(#JSAaZpWA-qC?Tnc>OKTd1Eve6`rJXB+D7`yt0Hb#JX2`0c8+~fu zlC9ShGwTU}SXQ4Ms;7p*NW4j@%y66<vGoYy7bL=hp_w}vy6s49J2*lEHfle1^}MUm zu07E*g*ea>NrulDKN)IY2KpSSqL-Sybx|2gpCmyStQQ(?cyAOtD28@7&VY(}FXvR^ z3{f_z9?Uf{3J{bww7+Nmd;fwlz>M)4csQLSx>OOGfs8m&w+n)_X$wJ#(1Nmx<cV(x z&cZDOrVd{~b8OK)<Uj_=P}TZZ;;mAx6ccHF8@_7nc_ocI%tyAxl2$>#iUq1+*|2ug z4sMYOwQQQ1R54=Qjz(=)L}+F;5b3-+O1-Fqt*;sfV0sKFfYSt&rEmzy8aOnn;2^H# zaeaBi3j!z+08=EHw3E3BZFVu-V625Zwv7*=J7?yXJ457XNsQ8Z0Cxc~RO)Z=XDv+M zks-FQX}k`%n0p8d5<4v;9WKo}<zX#l7+Xv!6?=yV?%(Aw<t##66x1|0lf(8&k4_Av zNLT)XXdrwqalXM*?{|Ix&E@`_=*+x@6)&Q~W=5!7)tD<6?V>E?1#kc4NkCI&SS%pi z?a9z=+n6)hU#Oysfw~|yniF9OD&v73d9W;=TCUEa1!X5A(KJccBft%0_{k-EGN`T* zp#aq?J80k(%ctThSqkFojT5ty3u3d;_;%h0yKt>m^^PgdFq9nUv`@Jcdh14)O_GFB z#teCCSm`p@%E7Aso>t)$L7Otp8T6vW{R<aM4olKoa%a0OG|d(1UjBABtfvSDQZ4;) z_!5rO71WaKe502sMwOA<bi~hxn>eW-9l}(q9<TZM#{8V!GhcH_sT0Z~Jk;t(yYdjO zy`o*^9Kk4r?0uzx&CTmWkYkO8qoNCYzOj~3qZ$^aU)nc~Km=0T#&RLn+Dd@!!IAeu zAcC3y`xy3QAoe^Kb5|>cic{b)1;G7m;LjKkq3IO$7qmjb9n<<etdKFu4YJwdkIs0Q z;(iB#hhbmAza+!fb?*tvg)tJl9p5oMjutHDVy9cY|EG)KX3|n@TU=!zWB>qPdH?_n z|6LdDJ^pvUx1Ju||DT>{Wbff@Zf8rw#PX|{Mm^qE_BiV<J6G2pa{xhX5WHdV@myPo z;oyMw9on=K{(FLi0<?g%ZeDIIxU<auU|>u`*P}@3pxsmonp$*HjU*b4NMo+uiX^Hf z#g0djMZ(8x-vyG!X*g<?N41j2DjxW<B;QGrmQxio9H%>*i$NCt&M8O$P7WVCUe_PF z4>?Y9a(Y@?hAz*$-L7w0(O=*vA7>$RsIO~wRnaLJiv-H*5+)`gXOYoW(rPB!MxCUG z1f^ld+|!Ts(PHVi33ud+MU1#cp3w(bRAcL!*=G)=drsjg$ksFykHp+UEQqSI4K1vt zZFi^SRBcTy%!`Yk9HMi7q;K}-98|B3t#qVs4xUKVJF;q?=zGHW$TT|AYMvN+;wVIu zYaW{vBWWnDQy8c!!*~AZzXMbi8=HaOHh}oBk4s)zL!KNWFe$e>relh&8M$*$)}Jw_ z+~}9cs-71n+rr4Cr{n6`(j7l5*uo!|dUt#!d-*#mC3Eq2_)tfz`}9_VlYiiw;2o@o zk$=#e;1ypICHo|s;XSGN1~<lCt=b@~USf19Ox7<rJX3`38?6CgigN}q1xQ>?n;XR$ zP~n6vB~?2|D#|esNmP*GyTqr+DxF(ocp@pz)h{q5zeh{+ge39g&7kqt(x;|VRAXf{ zYG}+PQ$NrQO;&G;QXDEXksJ=ZD~@WgGQOBH#YvlWbYAn9YV1cSsTTBhsI$ft2pa<C zR<R6GvYWOfR?rFpE~Y-ALZ?gv6Dd`z;#6tU3LTr09CBBh;-a!%X^;A67AytLfFze= zh=gJJpUjMi3^7v5p6qOEa4C%tVs4fv)BDZTUkxT27ztcXGe5gzwy9NV$^v<HHD_mZ zcG;6D)u2>(RBw?BxS8cQN-k?sC7UohZ_c9JPSmEtmM<_u&C7{XZ7xS&p-_X9nRM*+ zOD9h)#SJGa3=jx~76)Ng4iNX4pp_pN48!HVc2pmXO3KeOtiptgp_RY?N%sMZgQTAP zpv}8RiL43@GJXUB4s<{7RjHxgZki66!BSmxZR%{6r_rUuwxXAckMC8ghq8(({sW6u zPF9y8i?}j5uHAD&>Vtf2X=Mr;I5;{RCXZmaoQUlM9SZey1K?zM;`hcEeU(iAjQ#6$ zhCsaz-g6*}w)kU)|0;okOZ4h~8ix-iSN+e-Ez{U72>~No9S3<Dc0E%PMn)(UBy3*^ z>aH2$9&fE_e35yrk|C}2jK-+O(ngcr4$al576YwDADrF<N^9`B4ds{L#wDZ_*;6Qj zV1cOyUGTcaR1}(?Y>F|<KsJ=czzbOJ-+j#bvd+qF8?*+PtTo5zdbH2n4kMU0Tjn^I zWIYJApWKSKSs|cKmQ2MCe4=ePsFK%U)UL5su1~f}My~<9{1SkHGqA@f(`ER<ZHg7T z42l51Fzs-@7MN(xAz)9rz{Xo|r%%XZ_nTGM<WviOc;3_g>u7oU&-osiRe96d=&f6W zA;;Sn&Mg1Wsc^)iT^N!AShA;^5m1=%dLdyc{7;qR`#WZm6Nr(icc%F=mXPWj1l%HA zYplU%J9>6MLCC)O+Ne*pd<p6KpI%&fQ`X4sT9lP&?;V+=hx(tDDGa&e2l!QJliZ>) zG~F&I9zHJ45-|!^$6d~dnQTkjWvdNNfB~_FeGCu^3}0cHF$xxUGu!JHCWD)OQkaRE z2~Acr7*K-IB62{1e+Jy5iKQ{@ZGk}O8h+p=Bp@$i?nt2h-mPPj`wTrZ9_q-*x*)tF z7u~_!H#?UdhAuWXJ%(r;c{V2#A;Mt3+_hWHtri`vdE$(%!^3|O5C?HS&BIYRDe5=X z1Py<)e&5F5(jA)fiX2Es<ORY93KTNQ7ip6J2)}vYnV8|5s6m^sDfkYEts{%CZwju9 zCHDy@UkR_{iF@RSIQo<K{VU?e5XZDF;1*8SyH~)4E9MqV7K^yYP%sU@pAz=SChr2G zh-;P4#h=uBR>*}Z=3W-$5KrzqDB}Jj?lCI%2BTmaaZjzlE0x^AKN%$K5lqe}m@Fh* zfq2~E^E_`4eLSwD7~3iz%R_SfhBkRuR-BDLNxQox%S&R?XJ<=?aO@=PkwBhDHYpX5 zOxG;0Yg^#W5Pu&TcTcIH>ov(*rn!+#I(Z??(Il6}=ABH3cucL}n@rBvI)}@7sg;r? z>=8wN8h-!Gd-@;?ef;~uY2>Fb1={8X-KSb}YR?*TA2i8zNXKg7_bi3pB=L%N1>W1M zq^G2IAd0;b$vwQ2aUbLlAM(0nlg)AWr{2j1h0;=z1f+w+q=Pet2Pi5E`INZziU}!_ z)yDEoh;{4sP5$iS%u&Kk!pu;AslgYV-%7`bGg0-p$bc<8wait0n9G1I;F{-?eVDBR znD@~#BjZZ3#GQu4l!!9Jc(JJBPt2vbTH{6`i#d*qH0(0k+JG!(o9ACouN3fS2GFp6 zx@|xfVA_6vuwjZfZ4N2DF7n`tKk<f+@!M$yvLN;T@XRvz-4RQID?YO;@HmZNrh7Ht zA<2|`ofV{?NkPk$<4rJ~bUVRCo+<NY&Vwu7m;Q*3JK@2bp#xdKd47sn{5(MZa2*qS zz$|>bM7BWFG|%O>d(konI-NO+rVWG+OCWbLv?iIweR#xhLK+4(0-}Flr3Zm!6gEkG zOgE;YC{`4YdOzQa#s(AFq;}A0MFwt$?qm?xX{@|p(P3I$k-!$C5s#y`(OmuvT_%09 zg;wFN3QBgCDIY3aI+<Oiud7N>+<ikVC1xPeCP#a~<|;>2=g}QJksXX$b)(-t9|CX@ z;4$C|0XM}=){=rRfHV^;8)R9eprv!5IrQsm586nrwL!y;D4tKrVJEF<Vc~gP2?``y zFj7nXJ{o&nbTBzv?G51T`zgfLt>RRfQdt#k{|op5C0E2nQE6ynT^1uYd(*twpKW5b z?fN($6sWS?5~#xpACzl>t0qx5kmvVtAPbHfGTo(H_kBL{C)<`sr)p!>W=xxkze{Z@ zHkbZ2Nnydw{+hpnZN-wS{Pa3|G#`87fS>g^IRXE?UlTLd7I!2xu7dr&B(uiKM1GFe z&*--Ot;G%wclWHsf<leTbT{vt-cr@~e&`?EYz?kvFN<Fi3>6pqjIHxJdA`Gx_luRD z85j8L{md#%k+H!d7jX7J%LemrL$=E7s1vZvKz+E$5EHeEjs~$*NGTOoG<&a<RaiD- zRWt+7NYjbWGy>u_OH+weOH~>8W&H~MEDaV0rV1+0acgS5Ra73(kO$B)hMcFwf-&=+ zhbj_<eE7*UtYi2=BS47Z!@pF7j@qKKljD1+I#eDrxd{{NRGvW0t0g97|I|%*x*JqO zREx|FhGfb1`HyUh4Ap3~;(DB|EI$WB8nQf(Rz6>c$HQ^8m}^?ZK&R#pQ}0qOf&#g% zzfG`dGrV!v-@tMh%2&0S4RQ|EOMowIFaBz|UCY44!DsnBEyD9Xf`Wf{QoOE&$qaOz zEQGDIwplgQTW(b+X3pApwPuYQ8T!tsH$6FnqWzuK3Z>WUgcPWkr|C=(tO1*_g<32I zm5V!EH0;o)>*DdKlBZBvy$^}}8n3@6DbikZ9)e$mRo}avdaPrclL@60m}p#uX3MEl zaP-Aogq?y-qF`Dx7E(>&)`Y}4lHBqx9!(LFlsxklT!Y@{S0Z=nN^bS9Z}FzvumH+a zEd1Qv>q9G3e?cA!7kfHtoI&AB`k|b4z~W`!XjZ(r%P_-M<y293y!DgTbfn)~C6z+* zqN^AL3;4B|=?7c0U`P-qk3m#WBWOehQcKP)Cm9=cx?gYIcI<neZrKjC^Z6C$=2E1a zFn2`(eQ*7JFIbms=v1Y`j!mFYOJjs?D`PA<FOuxgB!82NU5=YkwH|V0^tLlISK7?5 zBr(ElX|!1TUO2rlk|WOvaL$OZk=@R*tTgEMm5;s{=xov(i0~X$Ljdt_%E<VWQ}}MT zJGbXhikzf!_PY^ie#UC;+5B9$MTbUJ=O3#_gBCf&_&o@MJjS4WS=8^_75V<@-J2GY zBIgpK^A4lq+B9@}dZoOOu7PC%+$D!0-&AjElo*6xJ+Q5l-w&T`(a$XU(u~$~3R83F zdGT~@4grnCo5RYyk{Mgw0H-=Y@D|7@4p`BDkUJ@FodS&WQp~*ix7-sLY>v5O#QBGd zdEb@O;XaHU_PPtUVj$6I>J2&_Et5JDF}~ovIvO#uQ9AiuPQ^@arB8p=^=`FK$4qVE zj^u5I|Ms?xCl*O6(Sm1CWD~NVRLT2WaGR9Ga9qi_YA$so`HQeXM!wK4wO1EYDK8a% zko(m2`BKi){lL|i=$ccYEGg2p4Bu$OGdh%=*Hxu`!zq12jKn2M#L!B-^^o_0AHU?5 zXFn<in5`}J|NN*n$*rGjSUzbqJNQ67dtxo#HA3EGv$v>U#ErN33OI4DNs?(wGk6`w zt6!e6ajm&R+?1(yinqC^FW(wMwZz(548+wZKgE*b8b0nl%A3-ytdMWcsJ@q@DX>PT z5mY&tewD6>ODMvNhjFl}#rbL9&v<&)o*P3QOup`HuV;8}OyO{P*&f0A6zr@gGctaL z?r57kyA7^g2S0QnkM7QQfGxKx3zcuRYiweU>H`N^Vc;hb=uBV@jQvChL<ztKGBy_e zI9z<+`TcCzxd2iANKL1Y4x-azjEsR}?6EA&%D}+DTpQ{e$`1hSQ(Ne9z0kXhtbFeF zWb(*H!64NYoFu#yDE8A>*_E!b>WKPin7|X!uS4OHpmW!9GG9`L=v2Q14VN@paFP4a z(Mg?Pn>{i4o=_P-&zCs1sFQD|g<&zzAaemS<$Q(zoZh=s=|5Dxv{Z%=q8Hbd({0{V zrtXVc7wMy>(F~KL#cp2-_XS?0s<f0s9p3}@7uvFs_H^r#XU&$Tt=X!k&VZLXr6AN^ zxu#UY;s>z5Jtt?m%hzy*6TwV*Vp842x35*8J&079YyFOKS{PfV2e|W`fg(iyBB}ni zsS#d6ZOC^|D1EKy`W;TDZiyjOR{KDvL)u$b7pWFCMwLNvlN+{x7^q5)aB2CXR$C>- z%KRk-$%MWPBI{oT@>eS0fXKM=v6OQQKe{Bcc>(@qM3jVQa3wl1RW=AgWa1TW;MD9k zd89ZQ$w)6B(X>+nTZL=x2{zB+R=cPo5ZiAb@O@)~<0;Cmnffaa(hA|=-C$>Rs?-v2 zO1BR)N16y8JsIB7HqUGc_O)z&eT;i$@3mqo3Tsuv0fL{jo~8s<e+4_R^r6|j|1e|) zn-Ms7m=BnyDlqGN20J!KNV%lvOG3$Oz)M?HA}X<z;C-_lHlILclCE@#iV;P!)zXv< zaHMej`|~G`wKg@v(l~E<<NO+zOu+$Vg!e*7^-E^2L7_Baz@5i4;;kPwBC%*m2z8xH z0{Q%(WVlpP&?Rr1nZ_clP@mb5;_3Oe(lKQNNFJRaD-blyc5VuHf2YKSKG$;Q6RQ<~ znMuQlQ9i^nre6O(iMhK?zI_Xk=(Y96g1RMbRwGyf5)IP|Ca1@nHzbBYE*E%r<bV}M zckBQc2KVS54-D^NOScrLs1-8O+IXLmrLfGG0A<3$-b>NhZ1Qimk^h4y=+rmThu<Ne z|6M!3(V&MvK!!aozIy0gGJqL|oe&7?Z>IxVzS2`uc3c9{KqEb@@hci&%EV4JKwGV9 z<%O%qqEiXvN82>teJji*0Hlp_hhK0~3~7$F;KD?x*G&BJ65tVn4TiK-x3RV;5@TX= zLUMF71EA@K3GoaFlHs>iIqg~NJPp53Zx|$41HBOItaV+8VybH>b{ni&CxBq};5rxQ zw7MJj1cRIjKjc(Wz=$U_GM<4yc_49I3k4`Z1Q6TcF~a)`21)Pk=6yaoR>>zYLUUE? zra}epL8DD&XY6@SJeg;A=k;x<bK}pEfP4Y>;^tXJ=n1}Otk+60e$~wC-F!AuSm}%s z!(wIh2*pb1&+_|Uej|nYo_&h-_0x!-l@$`?Cf+~x?fQO=H}CDM6MMeQ3?pde!Z{hi zOECr|1gzzJo00lvD|3*q&|GH#y9Ki00M*Lx{DTnr&|=7-yBwa;dkiB9Jj5Iz*yyrU zrhP;+pOQ|k$YxZKly_N!vv|scA|$?XEF`T82XYbBJn_^rB)s`Ze*#E2D~1iuz0&GH zVq3MyOWfa;C69Hj8ahA)`=6+S*DcftwfOA_-M6OmPc>`zPsV+OU_l&6J#FDq8B_Q1 zfr#(4_+Xc*jX?j=P*_bR3=BInK0CVfXjf)CR5LRWTQ438lNxgKNdbvR>||xEf=k(% zdYP+f+!*qg-AZA^JO4cfbQV(Ixk3V)?S>~RBrD9#?)AOei8<?Ps?+Yfcpg_It_y~) zz|HIQxma25upme1@%R{xS?|EM)l8*!Dyqfqb$Ys9*0N0`OG;T;w$<rdHph%L?Ukn% zEU|r57^nnT<~18wu6~-lIncl;ZORAqJgoK1Oq5@c3<JXxABrRWUKATadJ5P}0(S8X zL$8zKHrjtt0rId{Z&it$PrzJTISPuzd03<*PEZlaANUDRMc3c{2Z}j5L@1juI0v6Y zN8J{SNG6D#!VQ9^LcAxNW`8m)3V$a`bbtgai<_NO6K>z8%+A6MZ!Pw>xMA=QJhSx1 zZ-Ul9ea;}W7fyoA?c%`PRVwAj<JcOXHI)Ps5n*N+Q^1gS^?mO!IR{h&JE=99@vh-g z8~bLY0(^@<E|_eLq!N)QURkXWEMzC_(Kc)o!gM>ifX(AxI0_}k(5dg`{wXSJ1sH6c z-090w-^A_F0qOB=B0IM>!@|E8+@n#B6K58vM72wT)||o98We2vNA8h#Iv#I{9y(J7 zd&g!n*;v2&;TlCJST{Yz%8M&Dm@&ji^OLJ9&!dGFt5s7y*A$J!r>7=+YC6+v!b=aY zkAc#lQ3Eoj?z`s^wKk?GRhJm6`YdtmPG_6v%qs0FvxtAaCY+)GDM~i;#$5tqK}>oK zlg0-1^G|CsYwi<<?$Kj|S)_Tq=LUvsjo~LI;K?Rqnsl7~{d>eWj!>@ui?4GE5-sYI zblJ9T+q`Alwr$?BZQHhO+qP}j+>V%t>3<@+U(fSeJNDW6Wu}q`ewrKcB`Q@=g>_4H zztR?h>(Fw96)C$WwKdV<;$Sn6K9m}(R9^J>2a!o(!x4>9q51hS?kq^ynO@)?`B;iB zVM|b4K6cV72f;l`Sr(<ftWO-8f~<c-cug~=cz<OSTmY{7{$e4{%Y%Gkz{3SVSruaP z>1yseux}HCVr(kuR~L+a%brQou*wR@<E~-MpHEq#k;Z{rk+%|H(?%Hr?@WX@wr-lh z(ljrD_-qUZ@@wH4dpxmvG-txqy)h<@CU7}gWysRRap=Fkj(ceYhI^t76K>^3+E1Or zI70HVxJE!rk^fMEiM=8q@Cs{08Swcml^2|-GYN817X*H|@tzNE<?(v3(KH1FMqvfJ zye>FEU4ihm1MNsS?OPmvt62j-rcL2dPpdG<O-){?(`(YVdSBc`G6D+X{?Afd?Z0xc zjUVAwIWRqG>FBpsd#ui2GQ22_GX^3Xq-8;H?C;ol`LOUu&8Zh+Un*MwLw@X~vS8i0 z2C*!y_O%UAdmTi~`(to$u{{-~HSfL+<0A^qzQBRI1ADiIcbo2f1%GConxB1chkTLc zv<JwCd!zedh$7Wt`v$u-zya>{eH`xLdZGhfS3$kj@pDH%Re6r2z*;45xa@la>d;== zc}eEHB=-P*Hlfw`5Hvg#Czy$D5qMq7<haCPX^wD<5FWe9?zyMj;_O4cL1Sm3vdN@N z-DY?c3O?-p=N09xP>v9|NnZB`?LJ@j$cKJtf{k-Hm<`&&skfOZiMUR$r^*mOd+Ck^ zedc~QW(xzNJ#7`bx{NmlUR=6z4s)KvQ0PrF04VHd&;e!(ND~{MrtH6uc8WbP^TtN1 zdJk=gH|Uyrc?R?BUV~h(@w&SWc{<kX{BL#;^!)e2sHXa1Qhp(5UJ&b#97q9kKi0p| zci`>1i^T%<l<9m#H=*IVD&{hS2*r={0&71Fsxi4OnTV^o3=UMjxQK|#K;?yHu}x)_ zo1W69yekP!zhkViTi{dV!^J{CSO);2Zy|CJU)&-LVV^Jcq@JmzAsXYSG4J%0Tr*Q~ z`@e$$%-s4FOd_wCf&Bo~jGk~rsvKcWM7V+EhOC1m{O5^(Jfw}l?i%i4ih-yyd><JO z*Py|`{YK7(^N96t2HBH7bz@kD92Q#0<9{rvDb>COa`f$f69;M?-?*hENh5*51Or<% zRBUFf60NrTFYn_%3}De|W?bd&rKso#ryq=fJP7<UBJMG(CJb#F)X`A`lkiNxYc8G& z#x%~YFsgAn*pgE9oe80&U|0;dKM_$9w+?an2sWQwz}+T%z2vL50nU+wI_4P<2+9!& zA$hyU34NWy9y2}ZKOpUe4=Bq5NoV}Q2;h@dK(gRh=L2EhhOSuZ!al_1R|+iF;l}zB z>KR##YqeM>o1$^3CI-_Fx8U!<K%hx{C9rfGbNZKPz|08K2*vt8NS1sVnRT9*%x|0k z%iCc#G_9T_=L&$M?yCb>BVkQ-+p;j}3t^9MbGzMQcc@LTz-ReAi<ny9C80u155Z-s z-0@u?Y^VpEr-pjYL&H5mr=hmE1!A?k*;sviOyM|o&>@`u;Zvsb1bLBE&PB#_=`pa9 z4ycXE(c9?i_fl_vjzy<CwB>{2DF!ZPZ)Y#>ZbECLZxy9hgi^hq3)#C~Su%0?>4?<V z%Jd*KDHKRfyB#F=K%?y$x(ROS2ha$XjnGsf@}*t?&>=%J_j;Zur`rNqfEsk;Qtnj9 zVB>lxiclK>W$utBmn&4mH}Mh6<Id-or=avBP}RL_kV$-)PP97pBeZ?gC>MVmmk%27 zhW$~h3-J8kJ1vx5wa7a(OW8xM8vZbaHvu^s9b^CwB(cRQLng@S98gi^XZe*HNtQYy z6rsZ}{)uU}D8qN|Z-fZWcLaDi%wyEA9?dPIWZ^oMXva9b4M<4(RGUze<Ydva8XNOz zxG_SK{AYUbm@W0rRr78R2GK_Z8$bwydxJ?D&@Msz+=7~X8B|11wGR)9k7XO6Gq_DK z?j}AFu8QsoRnT=1f-tigh`~HY3+BKQlT?OPlS5faYDTrSHS41uj$^mIcjKn|n|Y_1 z2KHg*#e$OpMqu2cKo|#dyJg3gQ^Rlg<-mwkT>f_`137>dpSW>r7^a61mWMqxJ)l|; zG3IK_uy38}-{Uc`DnDu1Nt77oL&9_ypLwr@8;P+U`K6Igw{x|xcv2D?xGokn5XjY* z&yLG&*DoJfSyP9BH{;q1?$s;r%$z<{4&EPfygHLU3$nlW>j~JWC;$G{7mNT%%Eg=) z+z!WTh3X>AUJBey_k$8ja)@Ai<TxS!Js=1N>-uImzIoi_c}th$@6L+Lh0KwKo#Xb< z2jzIbz11&%jox%D;SJSi!m-Ba&@KsNl^g`d5ISswjJmK+R0*D6;@`g%Nm7Z7Z7Oua z5#uS}4C1Gf0fd~QsSmgcbKQvrRU;u5+?}{>c$XGt*SrLU<dB7l>J9eOI>nwBg)Od} zXSZ0qG`Vo-K*$GFTKKifEvS3N!H-38m~_>!{gb%jgR&3-8UeW3`N+YzzfU?rHV)3n zn}%z}ee?DT?U5o5**$r-QLHUKW&O`2CN3qgUyk<S0WL<yGHFAy(F-kKRpk?TEH$lm zAS3R|u>rO=2W8^b|Blwg`>tT0bJG(0=nanodl!MAJp#+s%gV9O&FBF8=sm+aYa$nS zd;wpV=(>aksMeXSw(;#pUsk6$*jPoQerdp#x~<x`u<qJ-2pMjFd=2iaS>{59V|{qI z$Svk3G|Vbs#f5~#Rds>8fXbP}K;+LmJ-$Ro(k2A#dE=Yv&^q*ms<mP!GQ~GKY{|rR z@rkQwla79iu1lik@d7z~J-`+^XKhx(E3A8TfD4V91f6$%>06ZSNVP8}X&;==?fv1M z<dzUtug#6?hz^fjewGZEcIv`oVq^UPhG-s@dRf-x4=j)FIM4R$tMKZ2?@-#?W!hWb zB2|j!y{u+E{<uJWbW5%B9C%704!uO8WI^>UROgo)zF9s4Q`|vZ;4NktUQ3@$N8}56 z#-cK1xLgnP4@ftDKrfCvZh7nZl0F=cJ`Yg3>-0gS8J+ZY1lZhk#bBeURCFO;t?lLF z?iCQlXO|2FbJ&ijPiO0iC$>YX*6aIn-YI)i+7_R#o3gZkC;0^zPZUt=z98xYXrleo zD`I9=Cg_#zS64&FSNB5!0JleNkSoM-mrVw-OSqFMpuZzXiB(LLL@q`A%`YjR`<Dv> zk02?|gn?FYj<CWYTvji=Z9!4griPS5uO&zEBJh(M&=8ClAwaU)?4T*lS+kCB2Y|3L z!~2LG{E5Q);t1g`4d9LtfDSGnqDf?d8kKh_t^h<+W%g@;uxFN(h)rxNpiu6JlN+Dm zU2`LuURMzO%h4c_#kqrF76vYwu4es-4By&6m6t#QJH6?gqM|16<=yp(+~RfJWU%ZW z_tQi;HsjWpLi$$XY6q&#>KEG<)Y;YW0+6)&g_4)y{2AFxy7`vLl5VqS@_yoj2JFZ= z7!Ge`cL3lveym02McVhRhwhbdv_tSl?X2lZMFfLiP()b?Tv78v+>*wHAz8LNZK4QD znQRRnntb2vCX_YTrtyceq2FO&YWa&)p0CqyE&Pao-v>15R5ke_@NiejwOz$Qnx?Dh z&%<UU2TZiMQtn-3grpmFE_?D_r=&Q1S&?&}q{L|%+rGIXkxOgr#bQQx1rITgGIW@G zp$;GcOkJYZ!+gjaZ_=&|+Y)-KgiLUHSAgjx1#TI_Hk%7H&V+=%@8`W<fZjjGLXRF3 zC~={0bUMV3CL7rN1qb1Gt_12y>L4Iv6^PgSZBzP%obb|;_z`d0lo~sgSM8m#CA%n# zBw!2>gup8L<c=*<H}-+`(H<6oLPJhOY0Ia?$kx9z`{9;(AT^8UJ#`QziCE?q$TR|h z>)_J6j0POlJnKN0@uFCxCKqW4BX|9qZGU*mN639)PD=&U12>u;e?EHkUG02%?_&zt z;=b7kh4+gpt14_MTN_Me8U5`Uvz3$Ra{`V<`;>;qqDHlx&+#w_bFO_QT4fd26LS6o zC*?d2C^9mi-}J~)>{_T-yrScL*t8z{0GdMzkV@(<fxb2~<{6i=w0*fMpO0OgKw}Jv z0rTL>L@Dd@d+idWWmd!^WdA;7f04V<24Osqr#VWoNB@%2Tbt$XdnI6+{=(PKg<3YQ za~ph&w^SmoW&Y9&HkJElvwUb7t|5~2jJ-JP&pg;4T1Yu_?8w2t2<;aR#lAEc!61L7 zQpq>w2(%OQ99P<6j9~d124uvVteV?{KaB0U(V15vBgg2wiH#uYIAX--77$y0K*VmU zL$P%ZCPk#WMkkB@Li9VVak&O{#55}Mcdv?P&dV?Q@#gj>e!{PHk}aK>Ud-OGE?LBk zd>KuLxWdkUJa&sc&k}HSTPd5pU@g;~t+LR});3J@)9h<>162PS-^vmMd8=BzDd24s z0=vWSu|_zKJ?6i`eaQ9De~}|1`q#YJc#`Nbcz-1jdAlc#;L?YRM%<mmFPt;3yS=#) z+dGx6{grU_+msNHecIDOK!wS_C93r&!4wap)_Tghh-AvxQ<!@sQz>&hoE`RAc*^8Q zx<PP$Epdq19w{Vbn_HZ1q`Ri_hru^i3_XxSAeAE7@pEUF!7|scDMi%_D3XxG@~tG1 za?Z<VrmRMYcCZaLPHhinp1}JNy3vwzR3i|x-Q8a`E|zr_Z*z1kU*u(Poa;+6&myTS zvvL;{-aQsr2+Cp;PoTh~FQJd<(-C!*hYz~(hTvb<-7xzC0I}d05|T*#=s^Kk;UC@8 zBfvLzs*ufxxvNvJPO`p~V+8Jf=>HhSLl%{m6kq;`Pl6nHO{b=FNFpSVUa_oEZ1|Dr zvlZjv4C>?+>+Fu~%HU1{&MP-g^3^ZfwhZ+I(ziyhQ-)dwJSORGs2^>wTcLJZf7@Yr zfj^cgO&kHVLC_RYf9oZQBWv;`Lk-c3b_`&og8MKFP&gG-STmFhlsZmLWIJ3CAh&ZC zwQ+q--G!mZDh5SR0g-)vQ&|f|GT%moZX4%8KlMm+IEVQ>^a~em*vxnv5EWfOX^Ib| zy*1+9kE9M%KbKaWM_z*6iR|XQ;KdiawzBC6PZtFhDmLZco3>4~ZI_XPlD0hDm6(3~ zy8x|d|ImuMU&+>94K=$qZX?6N)0gr3oFAzvyw%&Mq@K}j_=bY0N23(MET?mp$VJhO zbLA!efv*VL+agjOUNWs$wf!6S!f%fb*x$^}$#a8RRX%x|f9^9X$;-&c$HvIQ$O$Rn zhS+N1=x*%%)t(>zcnFXr6evU-S#W2ic5x1>4|K*4H^;<mPJTfyyWRFUF%Ye7OPJc3 zjE#rY$q=6z_?t+K+#Y*elY`rxQ&yTk6^*UtL~L|;csdIYyDA5N3T8tA*8jXEZu{nK z>uhfLuU(S`&_&>&TKneeEm+tG1oE`@q~>JA(TKQxet+vs-PWCn{O?Feh#2Sj*xcLM z`u@GJPlUMcc(h@6;?t|P?a_d^tufBVtW4Cgs94TqwCqvdUjd#koFz7(;E{aGF>F3= zNZg)16{ZMQfzH!>zC7$f!}f8B0_^M|*=T`y#xb9ptM_qX9~erzovCq7T<+LL!c(UQ zpcu8O0S1`Mi}i45$e11C6}fu?vNot&4D6WLP%mpv>|?vap^4=Q#h>aw8nG$RaIq*8 zJPAcSzNxk33|b@gAhF=}H)^csTP5*QnHdLZ>NaY7>`U~z>gPdS6a+>v`-LlBTCsV% z-8x2m<{bU&D@MMnMNrJK&Pt_9r}YfJ+n4E<N9Y?NJ_omTqov+xsO(fc6+m{IKR~VS zfr0*h3kR0p_5k3IXohsyn_3{OAhUW`q&{))yGuipjwC)rl(a4Z3ypzYHTX=B*7IS; z`J7W9bjV0M%U3d)c0h_(2RJB)TnAGZkY70lKdQOGQ?ju}Kw}pNRJm0YHnjiVUzX0G zoBkzacW3q#xtE>!@N)F&{Q>p7y}{|QJw`94GzaZ1B$xZie?vn1Tgn_ii@uV5T#-C` zi0vEfh)Luy$8Y<<?r8xgLHNZCbC#@!GHOgl#3_x8#1d$Gh4eeJKlyfo(v6F$pxEiF zAa*H_)eFI|SSNL8smWcjcgy&}TkPWY;xm>LDp!BI^ZVa&w*CvLYp*0<qW)L<9rQ12 zi|Kzx>YPj*Eex#xuQ~odnK~CGDZ51hgq>$%_`?E4Jam#K@E}WhtRRF~D20s&d3fQu zP=uO3$19nJrTRfn9jr=i3Vwh7{^;F9XmHstP}!+9NErn6jrl4!*B-l`^zNoQeOzmw zzu(oeWAIFmn00vllCS+iL2de!kgP}w2LXkNa|H3CAzThFe;n)*#t4KG+sLl0hN|Q1 zWIqse$!7<^Z26Fzw8_csEB)79vrK=6HDfVfO;}7RQwL(zNe+O~Bpt?%p*C^Dl0YTU zf@xHUBGgkGX^siCUc4ftQpkj6JP*W&d_v2I5;Ug33i!>7iQyD7H#_Oq!1KYRVL3LF zeEDuf0*rKLURGM&{u$xZkZ<23wmo-HEr&nCiJW~E>)>c<rXJczK)64Xr4N2`P&yA0 zXJ@S;Pz5w+R@kAuN~`jqU`;`nO9Be^i%<}&*y2%(0CA}`=Go=t<Pm+4Re(X~!4)#| zGDu~_k>?~Fxim5%=E}H44X!zw9#Nqg6!D&oVPz#BFKyY871nM-h*YQv++3HqI^0G( zojRvKzg+>KTsHlc3tgAvCFn&D3-&#T&?X*hh?7(UPSMROb<;&bMuKn^mrJj50u+L} z3f12jNy)J!Y7vU_A;^=w3l^1p96#m>M!_W5!>ESK4JS6HWNo{vA!=GS-wnwXrgCTI zc3xC{ub-SfcI}R>yN??(t3T~*Ij)<JzbCXhGw5xGLw!jG(mP`m%oEU?QNWln#A%An z`8c88#KTEkr8P$RJ;{Q-@J63az#y007h?-*@NwEs?@o~^k>5{KA^SJKnjn#|Rh9xt zVm$IRDPmM)Cy<(-Ni_@KgE@7`{eNw_kU#|8aH<1~?lmC~<`T|#%cA+zbg$sww|`q4 zun^6ek$FN_Yr(1p=BY$3d@&?*O8x@p$n2;0>-R-ozXR%J`*-tzbK|c%TyQv!4L(9m zK88r7iJWcbyyCIc${Hj4&lG3~H?rtG;A0(EYUJ=CX*IfRHn@~(Eb-Dy1BnOW+SB5E zTb_`@*&5tioGx0T_=V?|3ljN5ZUv(a>OAt7i5v=weD0$Lwe&BQRnsnrREuVQ*!?HX z3Nwsq@&*V1VES+U82;zgGjTUEv3Itxvvs2T&&A7D?2lPwKyl7sqs{lae$Q4_4m$#( z27#c}Av`M<zp6p#R+qhM2^pe`8Eokun7yO@5~Ra<gO+`3-$Wvj6@D1=NPp#FzCSx6 z`QiA!_eDZ{NNmcf(K@wNsl~Pba{>p<1P^hGfR|trI>mj2dVBDx7C`amft2L2rt&2& zVEInoB{@tx=Ckwmeo}^RMb#42g_L8fDhQ|($^P3FssX5&mZs^xxQk7c0(xs~c3|kW zNW71M?m3Z#H-XB4gxZ!fj%1u8M{`V_)JYXZivm<B*@y{R+TWG-L}126$9`{P_C1f; z`bblm!OLm+#%f&4a=Je|ixKbkMz&}gb`#Q_(IVtFN_EnTxVFV=K8ns+V`aiZpi*qs zgZpqV?taXlfKMl&-Ee`>)RPkqw!yV@uQbr5QINhX!v{b%QCT$&bP{xGWZP7r+^{&W zDV&m)wHA5{p7L9{@!&-&SFy%PvKMjD?U47&GikYD&tk;HB=Jv$=cE4PTT~9O^sr<4 zN#q|>3)?F$RB(2ch8<6z(lemiDTc6s-@7%zSh@Y$DSaDf)iB4uLJ$18+A!=3HGciU zlfIYE9*6%z1}Fxe5DEh8(O?kn>OO7y8y$|;F)%8xB{O}5Z$8?lvkzw<Ree5tPuK#@ zKAUoZ;YJmg!UGIAF22G3bBaPpNYD&0006F7|5qmZzlWRr=NL6>X<6f}dhjtfy4^g; z#-sRP4!aga+bAaBZYr3McW}kfZlGBx?I@?yxP?xVrZ!eGH@38qZId}-am(bB2`V&! zVxdrMponjPiD(_Q3w*Bep<Z{P2m*r$>p`)=i}(?J_x?_$XBVsbXO?I`T%|i@{(hbI z{)Uc977xrw{eG;p@=*`<h7ZYQ{OIQK@3ID!{o}+J5L}d+U=$dgw^2})R%sRLoq0*A zD0So_|MmPb7bMI-SCtvN@RCz;DwLj6&QC;c2b7@%`JXnKM~7_}l%brbkC+NqlDLYA zm?-m_iC9Tr#Y9fDF>F<><sdv~t+5QnAUxbYUnCYVk#-gMW(^qe(o-!K=pw*w%tqNO z8GfeOn+@Z7W+6Yv`|pBX8|W@UMjajudrB;c4Sxb1<NoObVvP>};9!q-S_EEV@gJU7 zMxcWwx#AJ8PAuRXu2veD4!;g<J2dcX*37x-)@dWD?B>;|X5V}%zO<@cuP$jdS~YpJ zQKLhHveJ^__iQL%dEV~8ZMxR<a%;V0wOa0L-n9VJa;-bw=vpwXJYT3QSv_mLzX)bm zrQdjNSv7Bu3>Lz9n;^t(qQEu)r1!1X+;jl;q^gm^dJeI!xpvXs_DUDrD|H_hiY$2* zrDF@kYHoiCj@%z}aW3l*<uAEG8~JLxhp+YBtRM}aUK)B~q|)vOAtPD<Qb^B(9l#2s z5=oN`6)|(Eq}t}{&39YqQGKp}U2Uyw&ba&(klb{#$sJv@9A*1nni|3eoFeUViI4C* z_u55p3#z9NG79TM*+k=o;wb?Dp|TKY(QHv2aNhRm)JTnLj+&ZNOFLl?e%F`kP=3TR zxJY)jA(w8JPwC+6KU><+p(nUXH<)nK%5)4e{V9)2e0p9qW9yh!^|2`2c?uNa`n<U& zx8r|}dYoF6vMsDvE<D^)uNcp39HNgnD`-SN!6`jw1s-h=`vyQWkj63+wId5J72&lE zW)N5Ex~RG2Fz9!1-TX%ZJ{KHrU8rg)$o-dbI^%H6LNks~8byf$N;zwgTS*yZI%=F2 zI22nd;bLwO^t9ODGyw*-pQ(SSwi0yUbBNGG9LUgjP5@9_PCMoU;!XV?Qv%{(Y1xsH zhO<jc1gXI@L3Zo}%}b4SUCXvoNUvFS`8A#H3Vpk;hU_iy{jBPu5fzZr^X2iS4_cN9 zH)(mTnRXReZ^P@lM!E`}e)x;CO?SD~DlqWwQG5wP6#qzv7H|W5)0WnKz!nSx7|H3< zGPqKvcEj>|9&8f?>bV!Vj_v&Jo3^zFqg%APcPvnr>McFP>U?M%l{N8;7Ig@353qv5 zG*2v&`YG)of)t2vw$m*b(fExJI$hFd^UoE=z;AMyLh}?d<<(Kp7n`P%19SX{wc`g4 zEU_T(ch$MENL-|-f|z6Vv461ArU#7>^Mhe_Nw4oWm{UzVQUBNRpEQTJqcCJkEtOd( zErXqMwZIAzPRZzHPn`ss_{Y5~qWbFAb!(2Pan;G^FiwoWd`ew7qZt;Q{#+bfQx_sm z_Zb@9M~GxVZq>k}qiGJ07e;7NoQG+Q22<FNrnhSV)5BTX%ms}DuWfvlz@&36unumi zGyay|x+F6Yv{h-j%o0Vg&en}#n~cFphIaendYaZ|eT5?(smLJ)UB{R}XVNj6vWDx5 z>Z%KjlN?F#`E?37s~CwQXqnOhCPD_c5RQ1ohRB&%r#5I1n2#YQG;?|zXELw_!RT0h z;pGkwm5j14m}ee9=`T?-uxyXI_kBrjcBKV9Uw1P={82F1+O*iz#{~l-_^?LOG|L;+ zwn`mQu@hmpU>Rh`Kp#@(fVi9lB<}zl?nxzO;2Li5LIjA-hky3tjKT4sqS7@U1q1m^ z?OrH!M2xJ;A;QZ^kkD^ph51}J^gZ9eiZ>lAoyRCc7^OjtWrNOJE30dyJ``20ZotxU z#0<zuk9WYbU+-L1cSgFa@<OVTq#VJR`$ZhlhH)a0BIW^sV8rP4+CBH9)mE~gQ|a~G z=qSFyBooOMcsRpG_!teXazQE7Ytv@a<UN>;hT{!$KEY7%8D4?Fe%s$5RADJOmNceC zpl0-~I92U6T0|qY$&bsX<tfB${{G=yKxyDj&bMfYAmMfstsFBd;G1;GkafM`Srrrc zZY!g=&rb35lYJ0OCoc1HlITuk5WU`)eo;-}>jQQnUVx8(AHw@%ERVU7r<fd7W9$-4 z3!to?P@AFz69dhRj>QN$BT2C`0h+#Yz=GofmSk=2V#1s?fHIogK%0$aAs(mAF&JIv znbEJ?%enegHV^92(kZAs%{9>kJ<79M{RwxUbJ;)F8G8prp$B9*M>3U=ay?(lo?RFB z$)wYW_cT@}dL31+fW2N`a)%!fFPTOv{daw?JLN{_WM}DaCopN{<jMrMD8D}+m<fZv zmn5Jc?W35nC{cn2&)69~Qk+PoEc({o?j~o4=k*8o_2l-P*8Vp3gBl#vA#T}7J#K=O z7z5KBkbx5sW!M!G1~Dq)nz26jkZwa$_v+LGapQpl0~Bo}1yP!WjTNi9QH~Y_39t|* z&4DALpF~}9UxwE4mC`|=p_`zkw9k^;f=L60M>cR%;9OS%gxQ`b{Q0g+_LkHJV=CgB z^IBvI`nhZ;CgqSwJxtf%F=z77T95I3*Ffcnr|%j*>>6BSMO1ZFXl>KdqXG*7d8FmA znC(1T(;hxDPENV`J4VaOmTjEU^YBB;)hkiVrsdd{^-L>w0z*erQx&e@+Gfm2YElwR z*z$a9;dIvfVrfz?tLJ4X-HILhUb*3~&GaAjR6=*1do&mKmyio`fC^&=FRvF{uT<rj zZpzJ005aWj_-1Er8_cyX<F4{Bz3URQL`uCv(y(dt`ycmUJ{)!I#u~rJaS*#^B>OrW z?Pd+CwQJ34YM+*cLl+3k<#wqIG`nyw&v$xr?dK8I4SPbA6o~fjNQd3=*<8<uMRt7p zTpmodb~u=u+@6-dCz|cvcs}SkU05!;qo?ybG+w*kB87!q4iMp95S$KaCN2@he;%Kj z=Xjj18Q{mWHG0DEO+uf^^Z*wsXd!BOJGULWk)wA%b-unP--XgZy5*?Q!|iX_H*>nZ zE$`1Ul&)cWw;h51r0m*ykx#&fmN*Ya-Kv_{NCClkWWctESi5oOFFyetBbZ5a=Cr?T zSf+^u>laaN$SP$9ZQ^SB5?B-qxLOIOoqOV@bYma&y)~OMPq}r|zPeVnx0B0Rfa09g zZq>B^lT2V55xWdhstGlqnX6raf%rdVRXpwc7bTrb^+r>@u`0cxDy6v~_d7=nb@&E5 z@5XiEk1*4ei6yIy+#V=V%+_cKO$xMwk<Epc{_qW)0(j9(dE9VYrw3ym8{x8AHLwmB z_CogmkO})ZEKq35Ly91m{N0&~d*u^)#w7kxvN3))mG;(p!XySR60bfyX<{{%U4X*; z$SXBZn%YrT>=wRNrqgADV=7RY(t~up7w;7y%SHEEjAw4P5!N(y`CfSykrWYih5F+Q zHUn^;wA@<u9YX%>ym96gxTrK(@(NbUPx@jCUP7VL+;KBaZuTw06WNUb4Vb^PYE;s7 zv!cDhaBmnIs7}JXu|1+n!$m+crU&*qXt(1h77DN~%B~*}iw>31NmuTB@XIxxmq*R( z^)HtDgsi%n+XA$A^Smj;r<cpIu(qZuzWI{{*<%p)=u%os&6T@fcYR5fq1rKtL$r9q zudwfzJPQWKH=b^xT^9S$xy50+DN5tx23IcUX%A>{_5+pbCFZrhyVj_~jmF(0mK^bi z2;m?5Oh^x@Lf9lUSx&r{rhTj6l^jJl;uQ2gGox^{Y4yM<o=J{$mqVJoY_n_=3qmnf z{<ej%eig?KR2rbMa^Z}MM_pdIttwS-9wgQ16#L2$uuMer)j8J#pMS-XA5~SmPO^Yx z6uQ}BZ))f)f)^VRV!k@6{6KsRem&!pRqtH7@w}ZIMqx-6l`x+v9?<^{3}DO(KtBo) zCl}}jwgIaI*T#jBWI@La2}}gW%e_~1jA7Uw5pZlpgZH^0TND2Ik#e+BU-w0i$bIHP zEOJ0Om|MU|5l}Ecc>gc)t#$(&QdLEvf2~K%VKc_HY9RC{!dE#yLQBffCrk*Cf8a`H zEtP|1B^8qTxNAU!b!51(zCyfnPg5gY;bF-~VW5#lsBn-fUYe|NH;aX=jLm%or<y~! z&a`h+)+$P19h4@aKhGM83M`m{R;#=8S|v@Hq4B_+ACiULeUvm2%xkegBGcxlz~_w_ z^posSHqDatJ5TY!f)Lm7j+p$v8Wn2e9FML_adV2cXn0*V=6pNW8^N<O2?LGBl~KY4 zj7InTW&yMB;Okx|*?Z~XXy#GwG(Pa+hD&_0_~6#>HdTxA_0<}kHC6q^->@q(SrOW~ z=4`leIHtB1GxvAk3+oR49UQMe;b*l|GcfP`lb<+%+blzkAg|R4>fp2|L)#uNLJfD` z<`C~x09>WO32UahTRWk*j_;-b=z%x|fruPfO&49Bh`L;MbDQAYC{<=K?smYqP*bU} z8?amt_8Bef9)wL(x3K_VAuRN^-$4Y^$c)LVo~6D$-JV0*q?gLRSWN)XX9y#Bn83<3 zh3>lMl@Q8gsRZ|<PZy;rJG^<j4aHoC0oK*%^1XgQNd)mz`rL}Tq7I<LD$_an1sc0H z@d}44gHcS;lOn}%3;I_4Q(!hFU32CtqT(Lh^NrrbVE16~yVh>qp62m6@X^zfJ#@GY z65})+6FVe1LpWhyoM`%(hBq+S){kOQ%>kT(CF@<~qSDX5Q^=-vz5<UVuZWKzLwq}7 zG|Bu{mg^9gRN&gTGT{Q5CXxfSUZd((LMFMv6SiSvqKZnlKg|w(jN}I;euu6M_0p>7 zXqVq$k89u;v>t@L(7uF!J_XEw`JpSw2B03K6)mnE&D`@5?Lnr1cu<JZbMYm&W^HTl z{da<Yg{p9(7`s<shb5nR2IS+VraC*l!G|gYR4yrEu@9l~ExwF-e2-3}UV9+%ekuT* z5K0&N^nS<ugc~LCEmn@=H46F7(3~+OBE%VGNmcRy+A5FhcLpWlSrFT|t5&uOu?&K* z=X07HobzArHe=rv4%Chdyw%t$X)`s`K|RaeW_LK|c8IxS>pR$pK|!7R|3*cC4SG8X z;@F!zWx6cmrp&@Bc?Xghh?Z{x?u6nPqzh=8i&+pl-7A|f#oTSkK~KudHow@OYKvT= zF62kPGRSp34x2QbRMP%#8UDTa#r+bTclp>LxKjku{~JarFd?~h1^hD!b~N=16-U1V z9_LJA_Lb-(fQJPDvSqgeJX!BG;|!VP#2;679`EH}@txqG!RM&h3m~5PTT77rE+Sz0 zB1k3odPso8m*tImLB0GGc3QiSDJ6MCaU?~-7YdXU_yrPyih_?G&juSg&J(tUq}kul z6HKZ#L!}g#Zzz+l03_5hAFvjzy^3IUmW<6kmVR0f?nhe1=%`z|Mj`rQJT;aeD~w>& zPmxaQw3S8NE7;y%kwtol$*My~5MvA1(G^G^2@j_o@`a3@!d|}SMc8o;=rf{wyX}yc zfiMY%Vq~1&f5MhrXEJM~hq)~|T%ta_g8?JdS12ix;7S(HG7s472Jg8TZpzU~WA8F> zl_A>BC74w$o01Hsh<SlQqxo7UqHEp;m`=N#cexwEi!c;0#)26t2xRxDj%4!<3Cx$C zuK@N%nQ9TNl=zVr`X0bZ6B0>$JIvP?4-)#%Qiq41QGQ5+qbQCfM%o)@2rNQ70-H!- z&ESDO+)42Q?tlIW$E1E6KITFnFcC4FI$|2}Zdk#gn3X1t%CEqqL<8F!5d@5p(NtOV zG>np56G>lUjD)V#5Z<Lj*O4}0>v}5_gQRmyzEofy-K1hk*|R(h55WXCGJ?!9<kp5_ zY2%TDR%=qIV=OXI|5GxTPK-*We<*b7TabxE>61ttAG0YZw&Ud7N?cmaR}m|`o=Q>A zSn=p()WKBa<c93oFX5V6#)PVKa3Mq5=yAao>66SEb{&I?<VuRhso<P)9%%F1g=}^T zCCkri#_1dSwP2vpV>C0zf}bnF(d_zNOkFuMOs%HZ?K|B5wQy0arZ&JCng!T?YTZVn zsZ+Z1R0v_op=i~rUyZEw*#;&`5AVd2QAG<RKK<C)*`~RWym0PXmTdL>!mX?B*izAR zsK&0-hf;#cLTm8~GFE!-(AJSqI9=Z7!vB#qaA%M{Qj5u@Y##mZszRvqNL6S3gmx3{ z1>Y-+Gzuk0NttIo)2+~=6n(}uW_;zyv(t-V=;&@ZpbNW!%eNKQw5mFG`N_I7=-PQs zNyyF<6%aOvkKr&yCueAla$w~O@f6m&Top7nYd+RX{Z@knn43dhR--ZbLHSTZ<6x^N zmN~2Ao&15CS_kXf=cwl!=C~Pg094kviQLRQIF*Rvp5Ge>MYP0>SaNdEsrbO{S$%tE zo8JM-r8>E8$(TObDPQ~favp7}FV+f1i1B84hGwJ9%hsWyQOu{`jumHEAOFY&DQVOZ zfqtp{s%gU&T;Y7Jx~b-GgSB&AhZ9jyb5>mlxhjFoXp_BOnEIiGQ>!v=$6MPz&IJqa z@@c%N)8vEn+_p7hE83j9W+lnMHM)y<5Pht{1fqo(_0JnYZVsdvJvd7B(6`#g6l7lU zSB5%j4oHoEiUn*R^L#EsBQZHjlUo|`D7)~&YCxhZC;c%NHoI*$8jG!dPUs2q)LQCx z-ay*f**`5aFHFud<4Z^?+{h=tBcI27W_tAJy{D&Jgl_LzlRy6N`w2Fenw<!zC2A;9 zY_6p6*{owq=A}L1$a*Iq^ft<NL!GnyQpC`QRqIT|v&({Zd|^7Gh|BOeW!UDgK?SzV zgWZr7qB1^EMfajYoW@TWwTLRRCB4Rev<L&0Scv9IH!2b;DH>`j>>+{JN<Wd+LY8^7 z<AN?hw4A3Ce`pzM`v8d{n~X!$;<+6mTb$6{Rd-e!AY&n+X)$)`+ju8gcO+$NF zgPZQyFB`(`7?ByjTOOUI!+@_IZ0YIJ3r$WAYqkdB)ITT95MsSh+V`k?R0bD3K<;5b zRpP+vXd*KDS@a^r03*)lg)WAGx<C*h!`~U@be{w;r*Ub1La@^p-e}b3;J5lBHw>OI zt)uxV8o2MgF#;4!`$)iFDQ0&J+OS_xwpAwe2kMfvSRf8k-S?oipR_f#Nb>P{udKjX z%=@Z@@Fv=-&)I)`KrvrLzOHB@1MXtkno=qz9^z&!(|!6^jsj5-C{fVp(938#T8tJ$ zp$8asY#J*Ow2$&wtybK`sQm5^$e`<|jITH%zqcq(RQO)enwcrY#06Ag4r9sPQ~Md` zoADA#b4{RVn;7VVpF-TSrAGm~o!)H)#fJhkEel;m9cd;NLl@klCP8)e(~j~g%tz}( zypA#9SOeX}3BTZ<>?wdw;!W)3=#`vq|2&`7%chR#5G{U%u*5Ah{72~E(XX9Ry2`rf z4tPPumx1C`8<XzMS^nAfaiIp4;pLqv%}jdkTakfvGml+&w~txfFN53fN3N%j&3csX z(*1h|o#cj!hMTt4oA}dyuy^)0LIT+RiCqC9y&qrP;YNzQ!{gSV7lm8_e=m6hK@khw zSJ!A>wRMqulV_wfnTJa2dlhb6q>=~Vrv`>u*Nvx<X##1x1SIGqyZlohl&r3fKp-+d z>pZ_@`hQoURX&viFb|=34_zHfxp#>sZNuXE6c<NHbtU6`Hr;Em<Sp)H)4G){QtGHj z{?vf6S0)_D%#H-|qZ+0kp+S|*FP|p##1b;%sst;~3q2~THkp!&e22p_qz2>FPr#)a zaO>wOf=E-;ajg)yt=5wfnaCbkWQ)BnMkCpHHR+xvgY-z24&hy+BjVUc7k^Gg9a5{Q zp+$_>c<!_e7QFl)m|dn2vm|zAG&;B`rAvtEnK^dvYlla7?^kz$b;LaJbXcdu8*?w^ z;^;J(f6W0ymzy3O-P~)8r+!sY61p4CjA~g2ISth*U%2@~n0f|=eYo%-r+Nqqb;M0y zyt&=Ml6b!ag4Tkje#0cEmZA^u6_O?)zp;jhgKhG3D7&~-Q{{ZiNAxez$S%3X7#@#s zqgpjq4FkRM%ANgaoH$={$i^G;q;fwu)ZUmP`Qhidsk%p-6mJ_Goj-R<$AZ$6LUSl5 zDa*a)S&asN`e4WISp9}ZaZZ`B*~uMfhX&ST`~#}W2bP#eeaV=9f&Wvla7IC;$oQ9S z1@kZ4>VHwa{#(7>f65ifs?)Z_A_%szzeuCujgaFF;6*9_wBbt#NLA|kKL)S?ya@7H z%K^nImAu<6TIu{9UTopR(LNx$0pxo+-ur#wYJ0*ev+hjc*{s|PNnRZll|3Ie__lVf zbh=;9PDYV&y%Oi;171M2oIw8qIf1I<41ytIrS<pY?L<)dcaVyDJ&Yl8S((mO%wjda z8z1q{S2eriGeWdQmf+j|-Ab)5+Z%dLm?e5W`P>ZClX@3kZUsmjR3S5jL1rk@z&Z!9 zG*MhyYmny&3eH#R)(8v}!_YjS#WIAg5$9cL)^^DZN2>+%gofx4;j`2u!+42aaG{U* z2@d+IH-&MK?&qpo@5k~!^J@T_)~Pr6`L*`VD@FD>bEy)2l=REYshS%U=jK_D1qH5^ z712utM9`Hva1n@j&ea~o_iDlI@C)l@wBdY7gWA*JJC-pgZ9W~0t7Lt!FYz!|?n#dk zlht~pt0MY8*48Jh<ol9Ey-~z1jm!{oIpX7yJw09u)_C}@RYS7HB@NP2L`DCIB-)zj zGBaWP3bK@3?9PgnLk-=FQy6*e$^7fNy*NjHIchZGOvm{=6o`)Tu|XDNg6KZ-?CDR7 zNHVF4+{w=@V%zL358ny6U45`$dWdVYUuv+2>A>UnoA$*KS!gw3w~^*#4S!lz7u=e! z9jH$Xvcg+Xrv5<M;fRct0>v3r-$E6^`y@T~Z&;lQg^6kVEBF}+nzg_b-aMUj6p;1~ zGNC2vTFh7OQngz?ErIbdUL26&k5c3hS{&T)<v;hS0YI?19pH6=v{Y>ob<+j40|&4A z!MLRdIEp(10p_(cC4*!1#)#k8t=QsNa(g`fph|Al!tO^EFx0jo*B8~qDNP@EPAZks zTKAw%_SID9tKOiC^ah@8W$@)e<^w5aM|@7JGDfO~#s#G*61+ygKEknL&%hnX$%eFr z&inDEge8fGi4x~mStKi!c@g%5Fy0^t6(MW176=!8Fnp4P&6O}0%LPp7>86x1S`lJ? zBWgv?pFDaPNu(bu3D`;NWOYylwb}^Or*Q)AoN~;@dRJ&bHdh}bv?@f^pcvaupUR+y zbJA(9g>0cwQmIG4OF`JZUn}C#5apN=f^#?)jO~sXN^`RP(<9D~07>;$)7SnNoZL}v zbtQ-D3f3EMdv9#w0#?m`a3eJG0js2R$b#sL1CSBeNk_i>j?OP$i=tE6H6kYXRYfWh z8jyI11~m#0qss68dm^Bnwvi3BwkLc+-qQAXp6RGi1j;tcMG0AyCHfvsvBbV#8=HFY zH#I*4q%aW3w-f}Q(@HSbF$uzkDi9=N9fL0(!V=1js)@gdLR&kLP7i{u*TGi6P|Pe4 zAOnlFTP!&LP3~0{!*TVaei7b~IFkB0o9&WsqK6LVCdG`ap@Z99#mI!2&5jXmgb3Dt z+w=x+oKt2*_=>sYvaBQA7+C@v^2cqSTii9CN1!3p_?N8!DCINonK6J1WTA$&%eAn3 zy~dSo<Jq-)QNR-leN%}255{46_Q3M7e%~`F1J$c}jvdb=&)WmB@-D!_9ai%6#eb{r z{4cQP;3IyZ`QI70{;$1`{(n~Y|6kYp|98x(Pup#+ApVU#@>NK3ZB8)xXJ_q@iLkbo zlFg7CbwQ?fKww!XOVM7(E&@qCl1yql`iOV#!X6Lh;6*tr7NF-v5upe4w1T&=`v!*k z_k|Y$)RRKKFBPc!Whvc*#7#|AbEzR`=d{b?@jer?hL-LE{PySiMM{qG#f|MzE^wE9 zkNpRoh0ciAoYM&v&3@%jM9+Y?_^h(36wN34ndM|a-bgSQwz5ji1ZNZ#ZE3A;#?u93 zaEA&S%et&Fhi;S=jixTY-xKUGXW|7ty>kc-1DT&zoW5Q+F<6w*`e4qcPB*fhYZLS& zC4F?=H`9aq3J^wZo%;r;#%HGP+4%*4gBP?>z$o4nJ-xL4n^lt|TDg^LdOW9x@@m{2 z;Vs9*=`!OS>bHh`#l^>KHuf<dvYX{an>k#X91Cu7&h2W5ng2eKmwEkhiZYz#Wl$$W z$WRs~Bq#Arp{<5r*uf3o(VUxSk=@Sv@16fOjyq&j6fR<LCwp)&FP_Kng_bjW6jf$m zro(SO6gfHc>erC}CeP!vl?HIhF`b!esb&6RuD~JV0`VkkScj6l2?4@Vc1Xv7FK9A| zr^DryQ;a8wft1CIJ`#zQd~b{)h>ih1o1d)a(rS9=)E3*b!6THDS~>gx|L_*;#bEy; z!6S1)3_T}tF`4yh>{K5-Jd^=9&tLE#l|47)T}SMUpn9JfI7}*>X$a4hfZKjJOj6gT z0wqeW<pL#YE*BI)S1gXk<@qpN_~eL=Oq0^g`b%6L<-MOOTMgec@|0wiEJ3VSW>!?+ zmVixKxiE3{7+eq^c`MflvfCopJ@UhI=WTd{1*z^T#A1n^YK?I`?VFd3{L}V&(yldV z9R?El9yG81JvHg7zVBb(`rHry&Uv?Q4vkRg1uyj5?vIA&he+(5o0|||w6$G(VWtg$ z9Y-O&=wLW8JwePCg^CFxyQy#KjbhAd^joJUZSdr;ROh;WXxuyuPOrSWH;I%uC;`&k zdqWjk)!MlV*N2Pv5ZrQZ^Ve}S_zUSTe^TQZiDcY>(Umzmf1n>T?F#jq-Oy=0ly9&N zI?a*nUIM~)`uX{|S9J5l3?)ES01bNydJblUKs*Mn<|O$33w-gP3>u5$RsDZM*ni@O z1zT;Bp)JY)1ob7axdO#hzsz_AQdE-p-YXLh5vz_#5NR_)JbMq$2QWR2eVZ}w=L$>2 z*pxU)3hJ0PiH)tM?HAR@JlNCL;ULlx-)IK>zIQPqM&IRp-ie;`_jdsL_HR|HSgXIb zLAZD-$D4cx1x=8tUJWp?tKr7}8jh$Cz4VlSSjd>PgvCVjooKwcG?4}$6}#6W{4}B; za$KETw@X)V5yLUC#bJ5tygz_apngcK+)Eb%iO`IRXiTCfW52Bgcw0)O5Pi&jild3* zCtw?(xaGo?=p7CvC(3nEaxKs2d~sy0k9W`G(-8~dowF3(i_^C5@bk?_jR3($4vn3t z#a;&CT%>5<dZ}3Ai`SbWw*WZa;#GSnJ;7M5X~bQF<<<JYI`WzPK%XgKCe=XrMW}@8 zI;sNKgmN31)rhWPKCqUAF<}qOPS2@3F${r*ier)riK#N*5Pw1VkfylxIuLu$J|~{J zY380V&7n7`taW^th;cd51}V1G+MabS9D!*&o3&6}{4^C__3?dV)-TY2|NKcvM4kb~ z92IQw_^d-<ZQq&0vV5kbmW?B-DO&RQ1B$967ZBpMf}?qVFEnVAH{>+o{)GR)klUJj za+V|zSpMY7O!h7V>>kM0n}FGY%Rg%`mR9ROB9kKGu<z^p{cuBKl>BkDcX*`qG)6pZ zV*_$_Cg;P&gX-uC&6O*8JXR`kau~jatzZrg53#t@tJo+HT7b^KC7M%&KP(G)3jM?4 zPlz6p<X1lUJz&))D7=&+V#YSblk{JJrbv-IgwjI9BHWv$3yG1{&Q08CYhoq0ZebpY zkh>TAq$qBvb%7GX<U=SuqzAwhV}8MD9zlaXfa;nDH1n1#N-BQXzvN~mo;m!wmYUhi zP5LzGES8lqt40ubdcyI6SKwK=lpu8s%4^hOlKJSUW{7)k1CMzqeqT_OCSj8Oyeeeg zWZVm;ZOX`^?k*2a?Vt+D&hb`e&i2}Zrf!b)-ZLgn7uOhZQpKW+LA6T6e`hMZ_Uv;2 zngIAE8$h>mBmIkZ7i&rd3A*KzvE)U;yRmG4bu)03g51$E@bjBgDJAS2We97D#@XGI z<z!`w`J7hA+ZT<B$6h&uDb&EYCf-`Px}Ze`)$@lXST5|tkw&cxnHmVee=rvcj{wrr zSxTknF1DUcHtegr@OEO^$xu{YlX)oQfUSxl%1L{d1N00VMXjM4gXT|g62hG*b`sZX z1r>t@-kgrc2=K58mdVB%#?9)fcGdVmi`S@f9@ZTsVsa;QiF9YUKa;`=?vIV4*=~Yr z1E(beWia>yp2rW<_Vqmr^~s#Z9-o44w??oeP3q41*6iR|Jz6RiJ36dw!4$5h2_~N< zyew<rXnj4Gu33u4a;QaKI4Bd@!pO&*1I^u5k<(8?5e$1mh^80=@WCM*5Hsl2<0UI1 zE1(pu?@e}8SKcPF1m|E$LChN!zlI$k*31skq}=2E7+ai9>H6s;tpFAj1vF>tgo{ZO z1cmyy<S85e#I4h%L5xKk0$BIf)@cbGqMdk<u%w?JcU11nh*>gLNf93gpGzR}o7fu2 zf-r6%18?R_TVK2}3JiN<W)sTY6QW1%3xxUcwW3P(Po`06Zv~lvAQx#J={fke1QGbT zOb`jUm{bU4AYC36=B^Quu$owA`EA5uQGyZVE~z%^pjUCArHU^HQowGD#o@_m9B=w+ z^?@ic__n%Ze-%Le#aD`wM3w?GK|4K#pY`CSPm01KKT_#PWZoVlxeNdSD>m6}{_eX0 zU+C!>FmeggMtd_%82Kw4U@Ym~z-408vH!PWu5zGWX7$|;eI;Jk9KM@>T6;C87cR9k zo3sj~9y&SCR%38X2KWjaO~w0Na=Kw_te%FdZ)mmt-4yWVfQJnoDi`R<4=j@9{({F$ zX?L*VUF66b7AsH<b&w&)E{91o#FQnE*QU%V7w`_yZtrLE>h~AM@0$uuSxY}8tTpjg zDZ;@>v*xrPuL59#ZIYgZrLT=mk8Mi%lX+J|x-_9t%YYg2QbtudgGmx0E2X)>v1^8Z z>4A&Cw%hXIGKNbdz51f?hc88UwKLmuB~Ci9)^wRiYeg!oXh<SljHyiDos!8+`)2t| zo@{rq&q-QE{GzrBg2mEG(~AE^JcX~i-OQ#<I+acWJ7tVTmuT$3L)an}!vjx=ApL4A zls;1nVd8wf-Ls`L&fPl{!I=L+=uc82u7AKV|D9v@RT*GdUC_SowZaLb0R^TQY6`)x zm-)@NE!G=9#_mKqcrwwK<B${P69bI7bQ{h51IrIh(1cJ9_BlMN>x=)Fao*88u7G<y z%#MN}j0@6WDgu?V{f5hjb=iT~C~>;RS<+(V6R!baEk1>{4c$t`RSy)S(9g|L`M1WS zC{_YWtQPn2x-zOOd8_d`*EdTT;a*T|Ao|zPR-=&<NdaHpF2;p+8R4QmN)dwpwv#8O z934OM<p;CFC_%JDrSR3*QXh1%q$Z5F-{17ZSc1SJ^&N2#0H&2?<J5FI#?^-#&UQ#M zEEP}OqOcay9WFpfmH3cfW040r!5k;lKSG&*ffeN`fRd@ARK$hwSs^(h(>JWdVe`SM zSj}rtd<m7}-Fl#o5v+cq)QGn*EmfGE3uPPit60CBLd;EArL_d+45K+>M(f|$Jk5YF z&BCAvfD#gKQ2#`iL)>N;+!|lDMPr2vKl#_T60II7cgf<v8&})zfgsdV#P9}JDXM_p z*_FzRKtR69uM3s}<{$7*R1{&XK!2gBMY88Sy;b>&gd|jo^Zy^d-myEgDB9MIZJTdw zJE_>VZQHhOI~Chz#kQS_lZtt>FE-9;_k37?V7Arf9HWmu`ZH>)TG_rQZt3{Ccq9ux zg4oj5`84_8Q@sD917MCEXMO&$)uaD(0sp5C;6HKJ|FZ*dRnvFg6hYeM8UIG(lFMq9 zEJT|HV#xq5|5f&J;bM`z@Ru>8RT64>&I;}C!Jjm;Q$Ts7WEi%R*$WWw5DQ_@J}`f% zp2r^5Y&WB?(X+{joQ1J<Pn&z^_U5krvr~f>Tc`WC*Gn|?Er-m<-xr@K`43ze#D1ai z{zD|jdW~A=dXHLb152q@qPfEI;8M_kF1Ij9Xa(wERT;6-NGS#C5LG#`(nu-=<^iTa zs5mZV{VavBME+B4>;siT7AHg0@I5dZi+k8}qXAY9W7$Om%0yIA4k7zfbLY!qu4k+1 zgw@+sb#+@+brSySf6RPIleRl=lWmDF<ZsL4vb2z3BVo_y|6GPloJZ>JqK{T0JqE7M zuCTtpKho)l+drA6h}fawDPL>Br(qoaxr#c<*vATo08e<G5r4+h3LteB7BlqLeY1Y| zb*$cp9r~^9cOYd>dCp;9n(A7Y-*YZUQgRH{q6no>(T{~V1-2ikulpAUYKpJyoyrXE zk@+~GEGmU%itsO)RIj=!H+?_cYKk7PJ%lqC&E(m%X))H?nPwU11hz63e--@7Tk1^B z7|B`^dXD13`oc*+V)uybY<#lWUU+bi`xAe+nZC9b+SOB07y3(fbgj%=bcQKIaAjY9 zn(Zdy=WuIX5@9Vb;%sh7X{LPF8<=+sZ>_x|00@6%0~A6W?|>%3VPXL}_y!yBhZ{c* z2m#0jJ_*E^N0dyuIq#C%yCg-@&7ra=h1qscj6ArJxA9()TB^qIFH_#>;mF9o3yqYM zT#Z0`wp!31*Pts(xwu>!pkR>Ex3Qa;1_;8q(<9af3+iJfqJ|LCZCgzdWvw;rh(HP0 z=fC1gMhgqmvzJ{po7TS@-j452pC)o4Ir=1A$Nv4`5Q`bn?1a2S^ibGbEazx8e!Z>W z70veuIDiPO>$?RRp#HU-PP%JNNt}{3raeZBjHcWvr&W&VpJhs3T?47A=d$JG5wkeb zMA6jY7m7sSNiBY0sCaO9Dq#G*>%ci&2LXw9<Q}3SPCAE@ODkTvOq(N)PUSc81R5?a zer_s)WXPwI+<v|gh~TCO&w4;j2T+DqsJ#{dc<nXPzrA~ckru@y9E?^KbMZdp*FUce zH&atTv~?oS<T9I^2>&CSLk;HEUIltZB<dZG2`3J&Ll>Q(%je8)l$C5&wS2R=%9yjv zz^*l=+S;bWenjdKL4X<&ToV^jqC+Yy(JAv1NRq7dmOIcO>qt)&wvHB=p>Ex}eoX!p zBNo<`{~%!Jc5)9K?e@pma>4P18J@ka(ktzh)m7aEVQ3^1>6kdlm|-((#P(rjpFLH? zrH@Gz=ox{28bSVodC!OP7F)A7WGX7k!crr{c9r^iO&m4+Qb4C~G_ns2(D7s~zFmeI zM4apXhirpaG4niLc<!f>u6Z%UAI7kU=as3?rG&>bHPIpw>UW#7AiGW%I?D9e;j;Dm zQZY3A(4FJ>JWq?qY{dp?by2q#M}o~JY!ixuVH;fD?a5}^WzPIr?bJgj)UcY)L2yb} z3pK<sW?2%2e_ZdW%NF(`_V1`vOte?ZTbKL}CXxnl4s$AZ6don)#1Gk}sDhVJS9PC0 zgIcxcb|}bT>Ngs}B9f8i(C4Rgb!lrNm@4ZW+*bzAz{|0wtUe+s?e|xvA$exZ^0cNK z*=c8PW^|@;Z8k*1A(#^5dK`Qpye0Cf_$1HUdR{dUIYC)^h`y%PCorBlEeW5SZ$9jF zNBH#tdh%6M{wf9`6EzRrC^D-l;_zEl|B{<{$0jmCJC24Mm7n7L;-N@ws9-ZGsQzlH z{z~r%9%Mmwb7$Z>Z(0IXtVg?7Fz8zKl|J%Wf;N}`y?t{LeRt}PqvLnx@&>r`#*!?& zvRaYwbQ#&^6A5PSl9N=KRyQFH7G1F2^QBpO3R0C&7-wOX=p&=>Wk*r|iz1e}drqXZ zG2Q|3U0;oJbNRWM2d8<0jW`NoIQ^ZUQ2H^ZNM2f<d1kvK*Qq`-E{3n!3tX{$>~ec# zNUg;;@c&fH3y98f(|*))bSNMo`u~3w=|8Cu|H~7SGHtghh7@2fDY;ZfrrnUt{!6g= zuOOuru<iaA5#@OwIlWSG%Vh<z77|)VlBIG<H^5k0fxd;Xm|;%+pfp@BOWlGYcU_ed z(gAQ~VeanccACAuZNXZ33hCeTQU`I%vGs=5;2Tc&1sMuyP-wDe`SWzt7YC~c{0eSB zNJEHuAOQo%!W^Kc?g0~o9)-{dTY!g}V5|*LRrJCRqK>gPSWeLkEI>Gf(12g6GN|c? zdbR~IcUS@Gg;{NX#Bl)i0QZ1zN9YD7-KwXfy9rbWtwYcQwVQLwmAj}3SWP*H@SwX@ z+lQdLnWXxt30w`sg|CJzdE$OH%YV?Jh>@jukWqJ_*l+kNcIb%nR{Nv<SiBhyj?6iF zcE4u*!tXVs<e{y)x)bEyK>d=YSEzXwMT?UQ@#oET_%TrM3TVkax8LRxt<q5J9HpTk zrZ87sy+qRFU~{y&_qwl>@Zhv^x9U#J$y3%M5CN~f+v4gmW%z+PLqG>R;~yXzA`o>Z zSU8j|aw?g8!h*s`0?$+t<pCLAE(Bn5KEbx~pLDFwn;{|!2@H_FwYQ;ynK@0!$`erU z@Lr;^7~h=jy?!ampSAm&UGi^UKR$VDj%UhvoSCM6(xl5nX^J;(@VY<%xA6&?&@gC9 zettt6f%AR5zY;xy*74kaaIV9BF!sDXoLA9#UqsUr#&%va-a_iC1CncP-#wT&cXDK! zIxp$tmdS8j$IAy?T1VA1gCjA{x!MnG9gtyY@c?2<!BzU`!^R$^LoU%!d6p_q&iJ)# z1`pw3;2D?zX`-}tgu)rN7nIKjh7GP&V#iPX1Z&)m)<OYw9RZf#!%iiWUd-W%jJfG? zgh({bm`(g66^=$~<z$6~alK3eaXg}mWJje$II#)Fib^eNM$HY*?m>ektXz2%9(d-d zTdrz&VpL@nW$jlG2y*G4jB+_hm`dy^77OgtZJ(q1sGabV9m7&F5^WlxZ0j&j7c#s= zJN9|VpX@iMls;e{<{f&IXhdTy>*DQ8s}<kv{`0@8JBQzl<5~hWa3j!>XtMdd22r8W ziX|4-V#3^suF(M8Ron-WHE>PLkHY5NL}lh=Y{ZmejsoEgfJQl*G&#(;Jf(;laLghl z!y6hB#K;Igb?`44^=HTtBXPBDQje;M3^3x03!HpSyz}2(RgzfpyN>SPoClKBLfCwI zrT<1oQqjeXNtcBF9i160s-!h|VuearS%l3Gwp$&XE)+Hn8;z$Qko;3iha041V&EDS z%Wg;p_*lkPdPlj^<Wlv$c$`%Rz;nO|Uy~OVNU6$)+Se?4UPYr3=9yS^Wef!#=4sn< zO@&5?@V{Kcu~7*-g>L-goRt+cEt{T5!Iky-rQMf~-FhWjYikanOU+xan%pKur!KFP z+UGfM<Y`nzekQ4(p`cgeMXUcfq7WHI{hLGcENtO$K!`!QuJx*9oGQ$8k&2P^Qswqz zcIk?KvyszQyIRQu9YsXG*ZRJ3{4FVPYp~u#(T_K-n{{tDNz<l?(r}M1&HpcswXAP$ z>VsL!diClz<o~?klEO_C1R;Td<dFW4Rq}t#1D#zAjjjLJB{+3y=gk##exMf&O3f6y zNk;;S3&3#<9h>r|E1{(5c$64wl!{2HEYsq^ui;b?Xpl_UxfTm=WzVu``i<Q=-ETSb z#(}cv+U7};D!VLa1OhO!%4-qUxY-`g=L4QyPaT5>t(qL0&x_}0E1>VNDSd=G)ovfm zP*8&+m43wm)qWKeU2tV^aZqJY3P?Eu1V?g6p}<4l2#}m&M`ZR~kZnJB!0dcch_Wbi zITb7I5ZAS0Asx@-g2nH~-mW%dxXbHED7a1M7(soAFQ?<6gcdOt>z)Fdt3*Z|Yr{wz z_glX|Rc;=N92ZeZ?f2*~z;J|E?SuW;%v^~SK4yVL#8zOjzmUr{A<BnuCk$o+l!28Y z%^{|!Ik_{M_EeCcs#P4{=f}`Nzq9xRZe#Z(u%1}DPB-3bBYYSU-jYtCFPJx_2Hgdt z8CX$<KSc9H0!0!<Qio|Hxlq2zaL%0##~XRyRW#Hz8mbq2SzIJn=`Jn`uSVUY(vBax z(o8W{H*4g&It)+Tak^q{o4R*)cI=w->@Kr5o<>_WZCW`v+O)FEc5Lc6vb4>N?W?w# zPnB7$or_x<x?1eg+_GYOW;ePvPo@@QTNpU<ukAiD+^N{wwDRk2uGnR3=54+}0VgVe zuYV5yYtFf;zL1`pZr(e$ufeDC1lsY0wGl%@sn<Vv68*mu2K|GGjA4_(EaVTQFk2`v zx-^uFeyD|VO|4}*s8$r?ORI`&uxN%d!Z3c3Br;xsK{3eWJraVWP|0x+SXW#tOjLFO zEVJA=tNoe=_^3zZoNXFoq0xI=X86gb&^bKShvfEw&gqX_4m%L1_$&4S8IXm+6;7E; z9-P^5m>!(zaQ1RIy9b8IB9Y<IyfINo;cer0a-X`tW0RW`RWuw-AjMXnVtfr>24Q2& z`MkA~T06C-nlSV)h97SNyoaQLV2Kp=@HEu-ONEYV=YJgvBB&+4?#_wCQK)E?3KHm5 z67e)&w*TUOf(I8Cp58<C<NvIYHiXnr%p;bA9MBB<itpL`<1ie^=YrgEg%H}8Q){@D zR4M7C>nn}3ta>3NuE`L_)yIKi==n{H)SB|7nbC&FQ$IAASdUNaC=nW6y297UC*N+k zelOb3?h3CC`}}KXpk@$HHr82>eh#2!F?#`?_6W_yHp!)>=2BBRMWZ^k^K)}q(owYP zk}Y<mgqT@@i69ZtO;|W4gHoVi7`eEL?vVANy~@Fu#E7*aAbZ)oaoI|dL7bntVTg{F zRgFq4y%+)7pe0cpf`*yY86mk{U7Oc3qpDTav9&m@;UOhb>q&wfvkJmS)~>0|{A0>x z<7b%)8kr-xjUT^n+Z-YVV3-@9RvwR1GqD;sCmG%UF*}>w3R`HO>41ymAd|fE4@5;y z%;#3^eY~ve%PP41V-|(8rxy4}B@jYAC@wQiE>n6(!kY7Ml~I+LfaF3TW?m&_z6LI< zVOm68a-ErcO-XZqzagviO5O5z`A6Z8XAa3+*yrf!BV*ms*<!gRVu!F4&pJ_<u%szn z_n-3Gdq^Xax{K#RN5eAMs^#Pd<uT5-#t8chm0MR!gtN_3m9--1h}rsYOz}y5rvZ~7 zB(|R6&D7z=ig!sqOQ*xp)uc9(=g}`c!e3<voUuB!Wii(#|1669{3RM3|EU};WJksF zoPSfZGiOk?>VWL=paGjB<&k+%=I#OivrAH-_V}LKT7Id86^zr<PJBQOxdX3>f-54^ z_s5;xLq5JmPTjfJGk2p|u>0C&W+B`8zDehJ&>BaDbx4AIl{J&hO!sj%9oL1TP9Yv+ zF+M!o&42MJb?MmpS&N<sQ8cYu^t(M8FV^RM@pw3+lEW<*7AP<l;QPA9^&|4$+4mh9 zac2vbGUs#{@g2H=9F10|i&5u?!Tl}|@7S{;0z9(EnOE$4p_%(t2%s+9Jo51_BfJ?3 zdTjTS4&q(mo_PKMAZH(k?nnRCVu4xUV$^HNUlG~4VKr8*zp_V}BlTefX(_vumQ7Ky zJ=XpJG@li-S6(^Q8^^O+vv3`20d%jtRzA;3)upLovy)C%?_tw$#B=CQ-sIEbH0|W& zEacbuESf!>bX9cj+$-l`D^O>U_8=1`qzn1vik)TGgheltxQViPgq9<U8ui)u6njN# zvP#9XJXR~NAXa18W)e&ZK|36_QQh+bfA$Dc^}64Vqt!DUA9Fsi4W)6_Gbqqj6Jzpu z+Ivht*$%~Q5AdVySJMGKF_LdNNof9(WBESuA%X{Efa}DU1TZ$6*W?n839qE^d&R-* z4=%o5)&yVL@Vyw8Rg;QZpPcirrD9V&U~b|(Bo{9Xzx#?7O}_He*NF?VkK+f=?puy> zK;Ii&F=Djc_bpOp>a%4?e#jFe=lSFr>71Lc$^_O3xfb;JS2#EaP6hAT4PmrhKT%mB ztaM)-KeGVY$*XN^z({!&<uaG8;g|P+y~eR-GSa+dx1taK(Q9D;ck<l-ll$PzU~Kj? zuKwXD<!X34Z?+?U>*pKc&Z?-8E~*f?W0!YgZ#LYp9yaNY&&Zz84=DjC3k!kJfo!YN z{hqHu_JkS6sK&}94BQ)L2{CwICKZ1#&!<F_l3yEkFgsImLpr>)2}_ucj$C3%B@^}* zC(it!=N=zvmegY~cka^3^$9jEO0#(e70<vO5#tUXVU1=_*LsB>JiH+Eap}7k89q5U zUQQL+K>cm#!-wt?bDR4beAltaB3B?9`!)AjhsFhr-U+q2`^$S#55;ru%$+)veAqdV zavt|oS+VdAuGn&%k}Hn{;N;}^h<j`9gIL<7LPGpgB-18J4Pj;+6tKiyc}{WCq-Ina zfqbUWjSEce2vA0TjN@qu<REC1?d(zV(nA5b5+ZH@bZ8BOn0xftR1)ERvl$>vO^bvM z-`Cf31V6K&-z5RrPFlBU^qvzTX2W@V=d2Z{w84KToOBWpQ0qW-B+zoO=tsN_@J`XU zSW55k^%BAQV$#<ke-lZ-S=ItwiFOiHb_J0z!CSX)zK#BYYp-`Yb&7<TRwT)K>5m2} zgOi%RZ#+we0)*{~we{)jZV!$xQ@mW6@bY(bem)RHGNn4EZL?5BF{GWn!p+g9LNy63 zOAgkZ9yaMG93Q#3aCLr)K<LES)y+_#wzm@uL2u>6*o&LHr&AcWci`^o$j=A|K$Esq zBR+d$Iia;CoQ=d}hG237-sG`VVk^<Hr;@$H24u1Oeu9Ln+mFvP18GV!G;tH#?+(28 zxS%ZGZVNb1q7pZW$)3n7eX$~0FNZdPmB<dH1LN|sO2n}-dBtBbLsKdd%aw2eZS*|A z5qj_t^ZR?QtY<^pM}W(2kGmpg4z5s{LZ*o<Iq6l`JxWF>C2Yzgo3J&d9;xl$1k!w0 zE(e@cOkOZFeo)(Lwyu_yl$S3z+f5&G@?H5q9>Q>I1e%Whm`rINjNt|e4B9wv`~~_i z&bI)QdE<wZZEGHfL&%-47xHtL7%hBvD0Cd#K{U{{hTuu`-myi%=b%WKj=B<~cy2K? zF&&t&ibh6lawGA$a~SwZd!Cqz?^lCzvVHA7^q(Rt)-$#ZxP&9M)CwYRne_#{I(c0H z_=$9Ras%E$PBiVz8lPDrf>&IUkx-wpnG_l82~kjBAzpJJE(Lb_o+lAqs?Zs=T1JIX zeaiWgxdt_+bhUO1xeAl8<J)Dmvmi{zAJe&>lzUi+iLyvc!h_{2SL$$XTpR%{si075 za^iK=+e^|;k;=k&J3<e)ViUD8v$MlZNNcW>X@|MG<ExJD_;72-GyJ-SLS4f~9VJR; zOxQ3xI}1i5oNYE2!8Qhdvs7YEiL&+%*Zo*=UeU8p=k8K&ukq>7R7}dxZqn9q4$bat z>bz`UUR6qcBU*fCLLZq_S=_e)fONEob-k!21?HBe3`!$3i-{skp4QUugvrC;MoY7K zP{SGn_TXx$>~<#1tzpLk&BW)PFJWr_=Op-IwE&BGmJx?8V6IP0a;mGe0!v&nHmzul zifZ2)!F1_1VU<^D%o<5#i*#>3e(`xqi&d4F8O8=-!{Kz@<O&nBQ=IBQ+UE&Vj{z#K zKXDYtY?U}e8|ssAv!=qCzIw$jSRkiQkV6k8c-GF^k5+cMuoNKi;udIzs`h<r3ZzrS z?MFUp)Y()61#Q`#Prf5v+0|BRVF{SbOan7;H(%KJ0$&^-&H>MM5tfa=CbY^evwR&C zU;k2gJj;Tu8>*7-*EK)u=sc{%YK6y_Ps25kq6{R<5i{iZhNB8s>-1tl58v=gY9d_~ z?mU>*BuW2{x9eP0p|{n_qRK-{YejznwfU-FJZ4EG3Tl@dS26~T*c`-b8%0aaR@9!D z0v#flsjIb|#12u!lGV2G+Y8rQw`!XuCeOaGAZyjCDQ#a^+q&I)Oyy!TQ(>jk90sg` zwxVSm8uB%$Y7%@wok$Nw*EbYA$r9@I_-@)4jZv%+svjFos2rN>dkXe+5X<G#h{mpt zl~88-?(Bs1_Pq6mUSO4mF4?f~UWi(EMeL|)wlSZLAHk#3XcTEC8_1g%8)fv-WnG=G z!LqkdHnu1Ivzgi%W^+Qc#p6kOej9pZ%31zQK=Ua61l8t~l{{2@+Ppmre(|0YwI?LR z7v1J}>FR+<rwN*+%Y_1@YL1GH{yBagS^47y&_=zmHnu&Wce3Y!^kF|{w&<vkS758S ze!+amiyD81iq5Hzb3O?l254wU&T*xAOiHD+l|W3X@CcyjrJETy<tr5D1Qa(P-^i=9 z#yFzMFFP6P>*VjZezP6h^O4!{c_^SR<#gx<?9pc~a3#Hb;;5~HmyfeiMXH80i%g&k znVcw$jz3NLL37{iH?(hC*$hm!Rn^Ps>T@qPzTD$J;tdqIVUj33<ZjAZyr%)-cctiL z6k@Vhli~CloTV6QH-<9?6~lC|U}_q9uK^kmm3Ri}4lPQNuUP5uUIadsqc>cZu-@y4 zynMn}K5tJt^fstuYoxu(+|NGR8U|-};HOQN*O|<QBk7dP;<Lg97M`Pent}%qyR_dx zMYv>cif$%?aONQw%o<p$a^cwBvV*($MAD_&%@{jd-5|D4j5S7GecdkYUN$|?hF|P| zz55(Jv^j?NEvm(XPdA_8yoZL<AtnA!Wn2<ZaD5umXed&@$ip8D*+#SdbP7&1g_VUZ zKJ55w^;Q5P{hKWx<0)Bc6b`3eIIixAm00Lmu&R|kB+_Nq3Xg{vwyn_}>Ruaq^6d#0 z6WW*9W>~Ml#iiyG?TKhP-66V*iUk+C&9}XIM0f*ui_%ZNob(*KT~kmGrYhD=AG+1B zTgYMLOPARy_xd;K00IpD`&q(3`gWYL_p%|5>M;7~CjIHt;<V?--N*URV>{W~fE$l+ z+u&mE(@?|;p%-0c7OsfmkxSHkK)5uynVDUn^{Qmg0s@of_<=f~w-8&>zU_CbpHIGB z&$%_6tM%^T$)Hx_?mYk8>|NXE))&21n%7FA86B&<=eOnpJL%E%CUP<S&{LSzB=t?B z`Pm}ExpLwAe<M-;N1a3{O?cx80t6KEqs{)5N<hYDHkL*V|6iT-pK`2&XRNZJ{RSh_ z=S-c4bzce_k_DS3PCf_?oszUBRAmCSDY;|BvVnM<aC#(RU(-<7itPgJdfd$p-)@)l z%<ije>1S*Lf4X-{?0D*BPVsYZxJapxoj@VG=1p;n%gng(*nWUMX_+9+)r#l3^I_xT ztBL3{$@O5oKVd|?qwN}Su>B!4LOG?@mEEc3fckei<g9%isq-aI`KGbEhjB}cT(Ig~ zr3DM=sq>}Tr9%NjT`8BA_8qD!yOxb}aI_?*dhmX|_$1rtARx>46lzqQC^xGb3D21v zy?2RLR>iV?G$dxBxq=cCU8<%v>*`m2<_TWv#1ze<Pl(vEL`KNT?}`|V><tGfP;zB` zOX>Pz0@K)*Wo9y`Wal}uE*NU(@Xc44HXWyF7}|4LVwA1ukjbb`2eCG7<J5m>*`uN| zwg{8P2pQBQW@40FAecw1YtFj!*y?Hf9@B}7!3*sMqh_^&UeK$hF1Tn@IYRIL>i#I1 zLK0)yRY_pS!xAX^qKXDXit4;ou(L`?Sn^G0*N*7K8FhDPA%=|cE2JQc%H#~Y|I(x` zr7C@3l1ejK;Y;nX3G4>P@k7B5*FR~sw1F2jS^G5UnS9}p4Uj|TZ5lffg=p3G4;(!g zA=9?Xj;&s9U`R<DbBn0Uwip#ve53W1m1(4EBodqW%1_93E~%Kr{B_np%nxD6+T=(B z<yG+nO%f(NJeGrYq7?mGm%{Qp&kf0wd&3chg_vHI6!z1@Zijzhym#`jrOn|Dm2d;P z;~)kOY<LJ>LqAytLsr-iJm%)+xwBep2t3<QdL-V3a!RKxX}6WOCBAdEsN2ceA@fDC zU;k~6@E`xHqL<VBFE}6|T?!x|-2d%=HFh%e^8CLOf_{qo9vo}u&Cxp^{}Hk*ssXGb zpm8a@&IdSAC1?t-dVuNbp@#wzr&5Jr03RNp!SUPM{U(q?a6D6v$r#zat*h;3Q~Twt zE1A`hVv>lva2|C1`o$NoCGO81;@EKXCy~~(#Dw~oy+fHR7|n~%r&QxuAmrB|1AQ+y z#w<;T8%R@$F(<y$K?>mkC2!<Ys)jtK@IBjDP~S`R_r1UoA%$1yhu$_qSuSb=r5`?1 z#T1DsF{l(#X+qAx!A;!DDHJD&eHozGtn_xsqsw^UEf3Xrjkr9`mT)Ma#R=IVzT>;h z#Gw$#uvt44n2f^?ExE6>_GUy|4jX&WWSDH}fM4QI+KBau9aMKMRw*D-{bSzrfo^?- z>TWB7@f;G`e1Q2l1uUmM(I15cP!Eh-<HngT#*cLRoYGI89WqSA^m2R>_aQ|31Dupu zG{y2bqQ13AQ4n!AbkC8w{w<%z6X+PpJB5yT#0)V=k9crKR|s6qa{o&c#MmhcZHYaq zOwvdUE}ir=CZHQ=71+%k;Nls#vCZI1Um_nQG1n8{Ml{E#0ESE$%m|Q{S_r9Km=i$( zlHr%Z=-b($`?GgK`pTFw4Z#r|Zx4*6gRS-#G_@pX8iVx)6)Cy{c^CLXV&97w_X~zH zIC^~9<PI6UJ%`qA^dDD8cWxqZCW2Y?`0ce7Bk5w-`hy$)H41b2pR_r{rm%6C2wS7M zBKZ#75J}8^fgnXx1G<Otp7&n^?F8@y0Zf=Ac3s|u`-7ZXu-L$ys|VUB)e>mV$-F;( zQs|g#GKrU+YO)MTopq8kZo$@>G*nc+a{wex`T)$CewgEwj1w{iUVrEWM2JRtt1bSf zd75of*K5J%+t>Szw);QW0~Vw(=y^wLWXP$<;EV`W1D+BT95@sfxj~PfFy7*D$AyJD z%SM|PyfN8<B)FnJ`HfIc>q8~1s8{(bpZup&HCRg!RA1TduCfoQDeO4Z4%~CjT#Sey zT3cNOJn$PCt)X=T)(+Pld9eU1zIB1kQ!l&96TcuxCUGI8dW~k76)MzDFy$|rQfPSt zeEg%lf3`PAM@%m$F6mKsc0%&~8s8-Z@?LtQE{G={mm`G=IfUMSA(BE0HnQR|<4i#C zAI*Houo^B02Mt)W3df>Cl^YmwXd&u5u_nixKpq~RhCIm2^)Vx-N+MP~EuAPS{B7XF z`nV3W2S!o>mf9dT9^Rn-M3>}ICsb32f%4NeN9Rj+y71R_VSU_~ZEew2n*$Po`g*Ne zIagkEGNT>)T?E6j(lU1LjBaVQ&!J-cdt1ZEsdF^9Y4lmi4+9(|J83G^DQIRKAxlZL zbTVG&EvbR(&k8_i99}DDM_X$^jRsV<^Az!Ro^{<$f5VVUYtrP^hc&?yZ(bgNjX0RN zQBZma{moO#X{CtniNT#?eD+6Kkm+H<J*bTLVD}Mn=|K7dRSFL_qB*qxq*aTgD8?b* zb(FdSUMEyZdErp2)toUsSwX(}B(R%$U3`+kzEVc~&hL6%ypy3ciB8^HGZn2pQWoCG zM%=u}SofMQ?Aj`{^{LZ?4xF$U1wmlWq-ml8nS(Gu$rX`0)X3>e(5O|AbW7*-VqNDF zbuO&%3j~hG3*r<<l%l8$WV7d*BlQAf0Y7lfnhXcX58%@~Ar8q1(#BxW^W>#HGG|6S z`$O>wvB85^0FnU@96eJI@68|(YkB0!k18SVlpdg6IMZLwZi(i>T>Klgj5yw$-(5vA zgi(qUuQ5^se>!K;`J(MF?;*6=r8QG43ltZBYGnrZ>Qnaoh-+9NYPr+k3aY@w-ESOi zCl7L}h&|^Z%Dp&a0IN>sgpThNq0`=TO^|dEPFRdkq0j*txkYu8L=ZR@bs14BrwPlA zlthx9scqofpR@fkUG$zf_Zy+xu#pGVU`OBlc>otw@QTTwB9IBxoyvYB`qXU(>4p(; z;)g0tDbBL*4lo85eC%k#ddFNGXV3~yW}sp|uta0}Mu?L3Ajt8drtRNnFmB*_08Fw0 zxKu4c=Bdt9)*{D!3vfQn&$)UYR|&=t!lF5xI)oycEq=|=hRN6`LbaQ}0^0&MFPqmv zEH(y><o=^$3;)EGnr?OyIZk>*`}PvOJlDrxY07)e?79??#l?zsDnj;QUFSkwkZj12 zbBJhGi^EzV8!Mw?;4RCZojR16)uHd|hR^d<?|U6mS}DI(J0en*foAj{l2rTI4-oDN zD7&o)cMe=VVKsr=fcb*%XDu+Ju3av=8d>euE*`6j%n1gl;JMKy6+#6HqPk&A0+446 z!%Hs5&mysYBZO5hWlA~bau-O!k6M~en-WxfuGyu$>-N!m$gz!9gSzJeMd>-RUpCN# zR8|{ftt`G!Gzt3=ox&#wSy07JwaTJpn&+_9zRoy}5l`mivIlzT<Kc8nCg6~4{PVdE zbtGBVlmI^dAR?o?5V?@`^5t_x7Y>?F=!BjQF8T+@>0pBwWz@qpEIl-XC7UI;4%)a^ zmk-ITo)#bQy&Kr{{gu4_`)v9COtpBzl1JT<%vix0Zl8?d)lW^IQq(Hq=FQub?qXH4 zAjO$Lgb(tDcN+)1G^@m|W}=-n(p0FYd5rI3Le;(|>5{vo<kHGT!Ob>O=PBxp7~m@l zbu6%(t`u!<uXlL0PTt{e`V-ROTc2Q$id+TO1%D-%NGSW;3Wn|5T(*$DaS%kUw$n`d zh`xGfB8`&5FxkSM-y&w}IGc|N^!G#^X0I;rdMMxNy{9;>NVy*!4bkj+8E-R!6n%UP zM1#Ja=)8f#yD4)DDOem7I{ws;ZH)0lR@bzfGq#;_P_>M5Tk#7oK6qWhMsLw^|1z{s zwbeHq68B2hQd!}&`kmFqox$ic0#0e}18#1Mavdxu2B}RQsD6)l>?jyE+M!tL^q5V% zE?0Y*jc4fnchIV;yx~NccyM1USd9@^NRKdOC;=%d-|+yvvW=159aMDvk67%V9LBpg z_=;3V9djVd7SV3lKm7@|%3YtVD@6w}7FFvM_V1EBL%3(?X`a8md{W>Ti4>_~T-SA( z1fDQb(D1^3Yt+ljII%8j>WfbLF&hRwUbsPr-uGy$%{<#^a|Yl>2Xh`e)u!BnlajgW zu0+p8IZ1Zf8ynm$_}Z6PAz>d+JJXZRStSn11GZfBAi?2$4*u>5eCBljeBl_c1Ieo~ z8559cwA*8nSvx*Ii(Oe%%N?8P7Kn-jK$8_J)!_?qiIL^hGe9B1I8b>Cd%(M9@Up_G z`|DLW*(GoLxbd~6FpD{}CvWR3wOr6KxhS&h9BK&Y3p46cQ;`OnFG8-{u9j5uVa8sb zq%i`R70%3f*|lrUm!QZ%^4Sb=ehqK(O)R<kjni=R8JcqJXOhK_#B!kUbeHtgs-Cd5 zhr#qhtgf*Sp059)Z}~SF#i_wR*fi@Uby|;D0tBgj$*}X@aTOI0w@#?9?hKS=LNFR{ z!fnGUcEX-C&isu<3Oovhw`6^Lu7kg)=T^R-r5=-IFk5q<4FZ&(4k;*E#ES&tT&Ek= z0EEeBLl~W8BARJ+HX)PeoUyvnMpc(8QuIzi3|@X7Tuzx%pWkD2SEk_`ooyP~5E?Yh zG7nEOCEo}gj=iXRV6Hc;?tS(qxhwH_2qPxK<8yI6xb~<RngttL-P%9fFkh>Z{{y?J zgvhe0O+T@!SvloF%S^6l9b|^@^XX@356k_FKEqlua&A|kQBgEoae=E~zJ>+z?r?Ex zm<oFbzYg?nYfQQR7M1EZil{bN@ctG3YGj)CbXX<E;`gs3TR#RnS~GLHrpn$^s>6t4 zj+Q<9BG=xw?L#?Akw+$Bkm7=6=cKw*4lK0x<H5*6VSb=xM0d-opVB9XsyLTGWHH~K zb)w7t$Q86=p&_8zJ73>m_a5V|R+$G8Tmx3XMV?srU?B0H2#!<7bm7m?oYc|j^xJ$P zOWPZk-2`qBG}FZ*#b2R`_h+B%rC7@uA#n<PP+h}2M{c*Bczdz7CXl~l&k|h>?wmgC zymAiTy$3~SUP%;?U>@B?^I5yFh`Y~%O3sj6K_mOFjr{#M3kr<_v-)$x+T#9VwYf>N z6<laZtTbBduVil+-#izwsrHXW!tEwm!W;g`KOoE$4{sY4<m!19w%;iedj0bA72z_^ z`u{ah_zx3ogQ7Cz2s99o0?L0kF#T7f?BHo^Xl!AsumArJ7yhS#$ya^a4ObGqcX|8G ze!Vf5(-=iU*gy^}CKql9?g)<MwIMennUl*AMIMYrwyF!zwsoymsU2C9=#0e+%NY(1 zi-79^Ob~#c;|YvmqwyF9j{5;MMZTrIOgBD2q+R+}r@h;=+tY?|@pyhcDv(Fd0Q`Yk z#*hA?H)ih>6AC#um=stp*k3Sm-w8oSS9dYDFfg<LG#fxKM+0O&M+3qzfXqI*hhCrx zTnAM{jc0QNYwbjAX9}`fpbl9F)`b(XdyHyUzyaF>(TvlNJC_|yS}?AMt@W=Se+I~S zs!HL|^3NV=9gH44{}>mn!zPO)j*Wq5h<Oe$B4S43koiD1cpdRYw9A5;vz<r7o5w}j zG4wYVrWyr`TH{cS_8>Na3rIeLIyB-M-iqB@WOUC~ry~p9);Vw7=2s%{p8hU`L<^&5 z^Yw`a1~acca-RQa5v&7L0?-2>2?{~_c2FSjb62=Xcs4*U@JKQW><6>4kIVx`Pjz@4 zyBv?XmoNauQPD49dwU5Xbf?_WEd_*cRqu}|hEwg=4H3?L*@sAqS7rE4jfcZHC@jMr zSl~yM?aEDU4f0rkvMVf@-xG3WPHba*s@BBnqtSBvFM$FSc{I%!+%HE%Q9STr?(XBy z{fqPNal<h}$etkzo`xM-*p_U&Ia%Tl<?-n)I0Uw1{dQ}ca^rERR)kl(Cnmr7(p%o+ zOq8VNWd{`56O_X;mB;UFT@DG4MTCW}1>YT$g3Wxv2+6ferzDKft*CiT0BiWF>UW%} zReR#zZ$arrl=C&e#)e92#CoN4<tv-==Cg<Q`!>D^V}kNh8S+4C2tgQI3?<!LfN5UF zn3?ogrlq3nJ86XT+Vk=A2B^TT+6DnhGv3R-!FSCkVYhYP`wYyDo4O8b#Zy#cGnTf; zm(w><&E~z^dY}Lx`xQnrQE};9E73Q1c^!LtxN*Sj?xvbNp^K57or{gao)8uxsXjqb z)e(MLYJKT63t*EdA<j#QRFfd1GB(4MItL+Jgs?m*LR5mVOd~>MFSk+^CHzll$T<8) zGu~K*g9^>HhXcxYRq}(fS?^_hCPY;TC+0{8%?;Gf7DlPEN`AXEFWEd%k|QL{BA#YJ zTtRe_hT9QD+<lVBjfe?=@4}fu3PD7gw)A#&%Znum>{dn8xe$KDBh4XnDWp5gG9t8b zSy#aAos>Aty{u*gSQtPiT`r*>c-t>g47xZAj9VgRgR(zGl|@mwVoKr<^w~4<x0#(= zF3F}mjW(m;DcsVYzQ5%LnaB;%R_qE_Y08;vGFpW$g((Ai;!(>`Ub;7?A$WK{+vtXS z6)%!Fuk!Ue-uT+TFIR8ir8l0vqiK8-t2~@&ZV&E)>{e|8rI5SC9F+H{s>GoTp|EAH zslMv!mY2d*J@}(Dg^J53ICg^&!Wz~*2TejD8BKYZm)uNkyQ-a<R7zF^F3UtxVpJ7q zZ7<7UJKY|5cw-xKCc+&zsqN}oN@1nBC=r_hiQgbWfoU;?3Ol^xe0Ttl(rB~!vpm__ zBZ~24+sIWjctp5RJ?O$7ZjwE~k4j~3<Q=Fxchaz9Foga0HT@r*PMRj&XI95D$@AWx z(#ehYf|$3LSufw;>v)&74TQQvE|3ntn9Q?Co-9_`Y?*&8Ey<x0oahgKIIOb|c&UEV zTDh<oC%gz&ZHUetiWIn`V?srD_Kk$zfMo~wuwxFU5Eb}VLkHTmz70b|=&WSR=x~EG zwiIrWlw72e$-25l(lr<g12bnjfuPWZAE74PF_8Y<%-oLV;R0qY60!U2v<ZoJn)_pp z{Th&-Oi_iE5ZJIoE766jUuw+(hS-k!uVJ7Bd|<u;K>2-G3C<B=^c4iK`@@qUSa2$8 zTyf~Gq1=|*B-eL_9T3w{BxnaFe6E&0%);JBTR7I&+UP_UT1MV09PXzcdG8Nkj+hs3 zc4lf?Lcvu_#bQ0O%0zq6o+^DwDEZ~nCs+`F-!1&<4ipCib+h0fYx$Znth}2NC-@do zmNrxD$0Wm-K7f5OUclfuT9vR>lSPx%n=8VucmF6oB_+U!{k{CcUmdZ9lQ(_s?6eYD z6)PMBSk0v}?&NJCj)II)5cg}iC5gF;G|Cs-$qFm=768e$4L45=WPZg#l~1e!;9p{{ zVC-P9<nfzAPYl3ZJHhQS=NZ;5BhTmARJ51r)J{3x&lcN|zYPrEF$EW?gys;Ah?V2R zqjd1|kRr=r-Mq4T7-5RT9B@HPItTDCk@n?DC(_Nt{aU>afn4ca+GWx-sfxk;EAE$3 z0&$g?hT<Q8IG;UzfM!a4C0O4j+sj8MfywY0<>4$fO{V4NpU_=<kkyPpHfAp&Z+1c^ z(^{fSvdWcC<H>73MHKak=>-0b58Es}<&L;gzT|TplBLQYY&B|$wL%f4CJdhX#e%nu zAdszgzZ+m!HWilNKcG4RKlf<#6fEiRvDvMe%5}#;%xX%lSJwXyyK$!7uBdr^pKg;5 zVk7W)<PDw8!1fYReVS5>EPA<d@^)ull6Voaflj?sW)>M0Vsv}(vTbMx!zEYv>EGw| zIPuMf@na@zohYdZ$MR7Y4%=&})%vHYW$o;AffdLHSBLwYI+Wj$Xy9OBOkbPRTZ^U* z7_keXI;^X5BX4?@vGxz(6&Afu@|(5BT-U7jm0fIs$Y$vN4L?h%o3FE0t#}Ea%V)P~ zx!n59*nwDKxAD{j41vj})M(4#WUK9y3}}}D2e-V#K&MgZ79NS0<DP72XU6tT@ODT> zZ+ZP^Ho`hxq{%GXmXL|}x#E=ko*5<A-oOm-$$7jlaVpu0;+HHGH_?KCWiU6i<n;!i zT5Bm}(Q+=h9?MT=Ti%7jwZ3#Ad->>B?tZ7s5hTsEDXKGE-`8hfmV}-<nGKXjYU)T| z*pYx}cSayoszH2i6qh5eTvAwPS3MJ!son#Tz+8{$>IkbPrGfdg?`0rXBXeG;=<tEJ zn9_cUXsEDE_YPpR{F8agN5Gl=_5KAtht!Zwnpz}H9rrM9tOnf17OTacn?N&;emo8% zVkb?azRvr_HSUodrOjmza4<^EI;=W|?zg1|5MC=Z6ox?|-W{UC-U3tI`E8$^+DurK z1#e>-mxt}qHhQWpq-C^=^W>v)02UrFMyhF+i!}a1#BN~&c-li*t$q59N`rWIQ|r|3 zfOEzFreqWvsWoQhg+92ToAmt_thS(2Fc-7((KuLa@)b=f5tz}c!GX?^RV1Q4wn>mm zDasSeX#VImI)Ds`mx+k}W2MY;_oz8<)<A3Z$N3}I^j`*vdV}iXv@`5h^~e9>_Y7Nt zJ#YU}pcj5VrvFWe*4O{9g7815DF3r2L_It{o_OjeTpt?jzs&%KW&~*fMZ$Cjjzoh9 zqa+&tgH%1PVmf`Sl%koYrBa=creC6vlvtUNoS9yekg1-em6Dc`qXma1O{*v&H>E5g zrAkRBC#xt?sp5bD13h<mzi84uLO__Gl#fT)msA)5ZNZ-LVw$Fsm6=?WpOU1hQv}Ic z*DTaFI7quQB_hDarz^lkN5LW~0B%&{=i_6hXC~>>ttWU)hmgJXk+P7Z!lRj>Er<XK z^grw3tsA9#c*LJ$AOr$p`9B`Re-r2b=Ru5UPTS*2qWga`@e$@Vj1f8>__(=g8lbI6 zx;1qfYO*)*&D0WOYZFlHu+qwUciOgXUpG{F8+p5t00#<yB(#$P0JTuW2v9$kb_;07 zJ)mBPaM<qWPVX{4M^0j<wB7E?+REDJNAEhTGMdzd>jnKhzc=uJKA{uk;qUhs!mU&w z8z9i%V6AX@U|}iu%veqnGzOFgq^bjIhOpts{fP$RpcIG<^_oCDkYdO-@G&TBo{VDs z^Z|+xT~K1+mnc}p2Jrz*5N_Bp)NAOBqXPus#vqqWjN}8gK}_Id(to9A@1z}Z7x(_u zI}=<wuB8fo5aT-lyO|lBlKkuxbU^W>?}5)5c!R`D)?dd50VJOQY<X`eK1T9^z6ibX z#<l(8>~TEu@Ffhl`05Q8AkgBv)b6^V-Vm43yuy(0C~N7NeR2%;E4426DFhs+uG;Oh zc!l<@p#*k3Z$b5)V}p&`tuykQUumaPX>t;GvDbgPaa$ciif5<AO9wQbx8MT2J)j(d z*aJ~BBZNfAl1Ph?f1}Jt>QLO<0}?O8tr4|;yE;dPV*VKv5N`y(#Ulbkg6Di=3bEi& zDNnLMu8F!YdYp5yXhSlEZ29^N;7u=ptWOTk6CqDSxGs?E8((BwcyPv!BM_7idn=E= z)d?&{EGX}nBiL-)?||V$cY{H~ST}>*q7~#!Vh{A1OWqmk!N===3k1JdTdzj%tRlk~ zsFGVl_AAitJcTIS*@;o@ny75aHMg6DeozyK8bj<c?pc2FEl1~WC1_nos(IS+qi_LZ zz(Ch|k38J89mtA{s_h}!a4Sb|T!<YkyVxu{_6$lPIOeEcp+~4oCAIx-N443CLn}$# zu!5yfvUE_{hcshmUa0=`{n|ML3q-|wHHkJ#!Jwt9o>@*$o2HO<WlFo!(5zf_N+ii) zOtNt#AjF2LMY6nm$Pa1{^8N1Yns?-TKM9Mi%y`u4bAC9P-*%sNzu9tWZMAD<=W{<a zyNno^R@<#IdyX%T8ZRR2^86*|7`P>}Y$Dr9uUbOY5z|Z^yT8k&sWW8mt6vnKQZ#~@ z$k`7C49$*pDH;O9EI3I1WPPMKorRMsvlATo=1F9cC`Lz!F0<J7gts_6c0z#DPugpf z1&Kc?okz(@N`2Xeh_5K#a-_g<z^P<Q)2xAw?UV{7I>ccS3=S}rJQTR*BMZ-(xT|YA zPS8XMJ?al2;;N^Z<paN_VjfN9R4|D`2W!8XjBybK;T#NOHpBzLyF(x31mipqhdxBw ziy$N=5>6l?a6}5Uk9u_sq8KJSpnyt8N{Gmx+M82>2zR(eudic{w+M46Wr;^cF48k5 zAii>~7a041yXw~T7Dj4!*<B=r#G(b$#-j4Z-?h~&+<bZz=GgLMOZsag6^9~-gAT?K zo0deG*-Jz9@}YGw9HeObgiU2?GKhZU4oj3bc*hw6QwVb~4o5QE>5r~5T(pf6ArCbs z{KPa|cq7S_^?YFJgw!}T&)g>k1j`gbgvUe!%!oH85%MGqCj}9kz<mvm<JtZlwEJsl za?d{nq58Jh1OA+<f5yVi*CsxZMgey>QKk|>t%zVIxT~TT7R77gxun@Sgy%+LpYu{C z;jpAi?mptT-#Z=`Dw~a;k({~OpTHL~L~i-(w3+r_*D35~9xo$)?<lVZ8|^YX8SJ$Q z?60CI+><WP{BMEAp>aDqYl1$@bh|6TX~#{cCLe>_OP^@zt{ij0Ghe-@Md56ns~EJq z_Tk*X$b+7vb?3b9vD?3S?$>Lc<MU?y+;IOwk2F%E68mp@WefOsujcA*j*cYf(BuTi z(J;cBq;0v3>=csWeU8_xx7pi#o`pZWqRRPfT%QfNbsesIneUQEGAec(9pvI(ZXwEj ziShg?_oJ7}alTVd7J+}&itC#pX{nmmNXngBVW;lDgTPO-J!}oG$Z}(B-_OJHD?T_- zoLn!rh(TMbz$$NMB;agU+T3+%;|>yLTX4|bbS~N|TWuYb5Kg|-EL7aGSa)R?Nhy!{ zCA`dTMo}DPO>2_QD5jlvd`<WIaxPnSjFq|;B%frNwYsz6B$6UN{ZiY9u4;kVtexD7 zdwfxKq8+c6H4k+|pQzj*LQ_fpE@}k5e?Y=Zj@}~y5AiCY&1AoPN+{~-7pF|aWSosV zR){K6yk&Eh6=!ejAtxKT)PKi5VyYw^$8Ljo3^u`1dlQyn3l(wA!irAzF=SFMahP#C zYI;zmgzas859XvQ<8Pc4_KjW|MH-cXM3aLP=|%zB%bZ=ilf*2kB<Fa8)xIUwe?^DD z2R%Fn9lVSQ5|zS=^#~A%GiSpuEkm@CFk~@XN*OPWNn`dj%3|xdD^N2?M{bi4RNeQ8 zL+A9xRTdMCjml;{f=FaQ_Ds%EL;1&GzDBuvzY+M4G|4url&rMS$fSgsDph5(#tdy3 zRm-Ue|7}I-syi3}af2VA3qEXHN%fmb86lzxL=A<(siN5LsUS-GZ*Lh#ZbGs$UQ^_d zBEX*0D;z~j$*O`@lhqJHBPDaT{Xv-j^0G;-=<eho3p?EamT;C0CmPY3d6M8bSu}hy zhJo}I8@ixD!gwKODR(9!2Rfh$+<w#!Ieqa652glBDtLHB`tetMnkMcgtYO@wi<+Dm z9dl`+8Qp3Re@Pl(l-bG<?xL4(?fTsu4zaZXs0{n&49}x8{5I!IIT~&DZp3C+m!Je8 zP4!r(r?+#>=1DcPnzwoaG2tUfMak#~9CqBaoGJ6Y`#ygm3?se&EF<pquelu^rH#Lh zJ)F6YuB-^-4T>Ld;Vt3Eb;OPtc6538cRfi@5-%K>G(|o-O`-%*a`=x|7^jq2QbXXr zTG}e6y0WGduct;r9my-aZTK^#dwE#Mo}@YK?dv!BFC$#Cmg%crfHSQAYRAhMOv_=o zjw8U)ztZSR+v<-*q<k%X#544!(ccWhv@3$7-32+-9iA);qcwEVDu(Q&)GJ4UO2ras z$|3L=Q(oNX7Yo_t?bAp}ulgd<m_BK^r<{9rf_xmd@XEOvmC!4Xl{*?$N1^cScJ5Q} zkOmEw#Dll}swHLda)Yi(kL#2{!&`>(aZZ=#oZaL<Drth2QbkP|pYF4LCDk4e>pKp< ze{gLedOcNisrgEoN*(WWRbr}Fqgn##NT<yUaM(|My;j_p(+_L(wQ_m}yqOv!R>Ru3 z)`|q2-!kDCZ2b*Fl?BzwmKkU{5~gZu>EVmynzV>jTZ9{Zz{m67UjjFJY26v%%X4K? zAN`SjhwNC=v!9$0KJ6<+OSc#ro)Gm$O~J6R*yQ*Xx>t54DJfElyxIhXBK&lPMWr@& z+JPOO77LcgB{%RBRQA(xe+i8&ovq$FZ2=YFoqKN(zw5s&lkM9$uO3u3CS<(alG=p{ zTpZ?53HFH5<So&QG}e%d=hkGQXAUPI(KT+U8lnWqfe8{dsMGOsepR@PGMnXJX9?YL zc~z2mLed!aK1DUZSe6)0TzVJ+z!Nb-)Yh;O5NYcawODdr5R)3S)<7?eK8mXf9A915 zOv;;=M3i5T^4T7F0z~LE+F?+`q}91h(K=0IX2(4|C_d6936Crc2?huEGIMvt4p~%; zQ3)5Pi($lNxo5|ek=bYa3atMiYR>kXf9QPw;u*9qhQC$Ci6Btq<wPxB;A{<qf#hoj zPE)=-w;~OjeW%J=p+3;QRqDuz{0RsGQA@O>TaR(lusj&I+1e6HpGnKt@YUug_`TLj zj?8Y(FWF<kgnaNyZgT@0ooA=eb_DYdhZzr_iIzJcFb<`@o}iMitjkY)JfEUct}n9K zs9Bmmokc$vj=*gHjZu!Vd%$bn{>z;2D+ZB+nb3{^VTRSwQwoz*>ck;ght`=v?rB$^ zqQWP*Y;GD_mgXKyVIi}_#q8r(n!|mkKZ44`|JB)<fHiS#0XQI~$Wlc?ab*i2s6{Ol z5d?)Qf)*8R^;raB7!e6cNP>VMIx5Oq!MzGpVJz~nh*}kwr_YLewFULLv}k2f>xST3 zQQLFD%;ZjH#(wYm<qP^b|2g-ZbI&<5%-qQ?^1W&HX8EIxhC_BoR{S<}X>wq|i!ArD z@;yeMyqtXER_@w;*44Hzw%*@(;%!xdEUEnF>=mh(j)g`)iA!J73coUY+<2(SRP4At zy<D?6FL-l{cSCZMS<hQP^siYE+I+P_k^MYk-|MEh?nkzV`p2D_uynz>XI<)_HC`M| zq{NlhXWd`gG{FAV^r|~`$EQ`yJZ$Oap3t=G%0Ah_vf!kGNud#>XGyc|eUpDTJ$`hv zpg3(qxJ7NZT*I?J-2Be1!K^7IC8VV~>*c5U?uK1G<4V6-7L!og_^{H<OOtE3tKw@S z=s@7T%;}`X@MDAh<rmydYkQ>;=W6Y4h$=Vd|MF`?+vm+D!`sB?RW2T?>UJmpfy36$ z9kjzOEG&5`yus1*WX%tn;3Lknk9S!V`khI6$emV2_@?#e+J3oK+HK$7oTc}yClyYJ zh^hVjqJ00Pi-YRwPx<UWa-`1VZr`TorR$u(Tp+H^{`2m0c)@w;#?+i@Usa2PqaT$q zsH(<6To&TjZTJOs!THPEXRf63Z<#LnB*uK~N0vud4UDPJoYudm+(;9C-1PI?KCK%Y zUes(j+emyLUbA>_VPM4A&_Frmd-<%B&6t~xuEuHo8f^0)ncrJh^fdEwV}O0vZf~8+ zgA6J{-uAxO7&mIu?$VPz+m>~8w{og<H_e;ilQt)1z=uaSr2XpMqrKc^yfkfmK=;vU zcVB*WYr)#olaA_-Ep{|tZ7B&EY*l=wwkpeIW7p84xXCkmop;H}d(}37x<gFw_?D?v z8ETsYPc%7qjkb;yUmozRNIs#==$RMw^r!5FhnJ+QgB#xNS$A6;l6q%t-4yAQ(HCM9 z?%gBO7w1@C`Dy;pJ~yP*RG*Av=9j_?E3++HyFMH)uCuS3QJ6gb{E>NCB}TKS?ppZS zhSM>vj+Hx8%bY*kbn4Z>FIVO?eZ6*|@st4<dpP&=^=@5rJ<cJjzV4a*?0#n-+U*;E z#^d|Y>bw;muB(Uq9Qa*kaGQOk$H`;kgHp#H4a@4|U~Bnj--4B&_02CdtT8Q6^cbEg zoBBA<zcBT;nJ=#vMn*)WR{PF~4EHoGijuBRKhX2eJTtd97osPH#k4in@3<q6da{1| zh#$p6rOQ=GBg9|!tG{q^m{XbGv9@CCjH$Plz5KAUTX{~4-5=G{$5+)3^IYX>lRdx3 z>TCXewweaz2KO`xb26&5+?FOE;s0m5s?~qWL<2*sE>>_RZ6ZQ9yulA5xIeRFz>}r) zph)zihEQwV>FW#16!y_=i|vNYhu1Pznu<jI>0?DAibPx1b{w6kiIu6{(T|Z*iA**J z9!*ul-E(XbI#{bmFN|~v_&OvWZP4$~;Ptx$X2Jj70KZ4`z!;`*`zgj?uAZ<o!!I4^ zYKbJMk2dXz1M&*^plt@UgCh6Aqq#g1XpM#0Zi@YH2mmgD&mb)rz9}*u9yID;|AVVO zx*8+@I%c%bHv^k^8;eAa7}W->)In7zDwPVA#$BRLkxK*L`3QXzs`oewUZ+S8ij0Q) zCNUsAaopX=kb_EKw-)gCNpOr0%|Mea)Tc1c;!;uAst3ci+r)!_O!%Of)DDUy;HnZ! zT}BYCIzJs*ckXeUc5~Re=sK{(S~Pr9q#Z1#4tmFBDY)yI=v)IGHb%FRqJQErZ%*$e z{iDEF>2SBSJw}vU^Ajg2Vq!SGb>Xm;T`?%Q2wa6PPz(4gr-DfmRXm4cNEht_?Taba z40^IiwE6TsKPJX}b#IuU(?=qaFUGNT;NUPWK_Vh?^YJ?e#n|nhPGg#3SssFXf~SLg zSYLV?vn6%dL0H1-ezKYbSe!>;?^<tcE~g;Y-YWr?+dIbzi>a#d_fh~p8$RgW)7n9i zt3axN7}^c|d=$m$hhI%Eg&g4n8*rhUp0$G_Lr2kkjq+U*r#BeDeakK;5Uuo}NH;%S z5Um%EKu%lvdUy4FI4}b~Lumk7QIRYJ<1ZS=KTU*=|8L`ge3<55NPOs0vUX6Ul|QZ> zgYF1AzC9Imb1f1uM*jS|B~T$5!1J8UpvY$dBGI^@prOH`<0reTh=jyg6`}rEldNGQ zwmWXBMhLhIM1+????4@dMxl(95eo<z7h{d_l@Tya5xg>4gjm`^k?FdOg|W(^YRO!J zt%C011GLA&H$_(I9v)3733)Ujm!?F@V&zcNIcAgVV>cuo)ChtMgjx>mpvXtMsA-eG z2n!rHjf-GxpSNcs5CS0e;B(0vr(=&P6FY6II~Np?6)t`g&Vnswz#_#J_%KK$k}1{b zX%v}4sgTH}^Aud=&Z@^0iy=U`22(&z(GH620=?5a0v&+*@f>if>Qe<AKLAqR5beS6 z4e=bRb37AqI@$<_^K(0=hOJ<la4?M<Mz#s#B-2{*bCJ!qtvi-$24&d;Y=)cMV7m4J z9vX#D7#)6kc5{~mnDB7Oym)`$GgEtbXHO{94vsG05v75Nk)Q}9S9(xn!&f+kM-{Xl zv)1R2+zAk4@Eu<Jb0XLf#sQ34{B}b0gYB<tD?qUm@NuUVM4ru*@Y88^h2anXpyot? z>WMIaR}8*nju!rZbc4B;Tk3aMz^l}ujNqBxiO^!_C=?o*LK01=+@+o09NmDyo7{kJ zK(}w8WZ+4{RLucGOihXsa-M#`?EQEbc^Gt>?Zs|UZX|J_XanLT<Ppyiu7kIMQVSr# zdtyerl)*`2oX#jH?3a6cc2?WKswj41*N~r}I(I(Zrei=|7io<tETDeX)v@7FKq~Cm zO^avYdj!yy;g^6G=vSli9!8-xHG^GZ8X=rJr@%C=GDQrB&x%f%t*5|e{%{h6FY=`0 z`V6H+CE;o*J^E){tb|l?5K;x+QckVar$`lYwL-?#Gg~`1Mn3_+H^Zp|n2jD3>2+D3 zgSU`)6e0T<JlfgtHE1;rv~r+XXkE{{u1{0SB$~MjRlJ%|Er^wJY3F9*kaPvKa{+td zOXbrW`aGl^Z#N%x&^~kxs6~MLaI;Tn<UsLs@`0hd$x%>_!r>GJPXd<r^(h*KwBycG zjwm>@iQMT6mP!K{dbm?NC~|qLK8Q%xC>2}@puw@>N!<q`(F4#2KSz1-R39T%#K%jZ z@!%@fisSAl7lAUZuz=ux0eV2OZr3Nt6p-p;7fLj-3OUE@OiHZww}8W(ve@h7KL!SR z>m;7wity9>#XlE99gT(X#@o5yZS@&oY7RZDY&He&1=GmjYzcQ))gXNaodoc}M(MG> z?XR4}P*bi#FhXBX4~i`I<^nO<ksajx2?og#ha`4af*1Y=wZV&)f)>zjUtu|zM}&n$ zEpr&<3X`da_#2K1NeUDe@-7aA@#jJkO4JaO2Vo9)DQOuejMrJf!Xh^R(xpZYW_k`M z!XDTR_Cm+Y&cj$Gp_hQLgxBXwhRR?PB`}GRn1sYIVF`GS6qfS+zt$K%go+yi842&Q zyk@>f%0D>8UN?8-=%e6gLzo9NE%cyB)f{2Ewq6KpKWkLaDGty+*Tu50=#hjlAFX&{ z_VhOsiyuI<AaiD0re&2dyR%{n)4#9~pSlZn?+&M$P=@J2k*+1ebd+a=*^SetPTm6C z{&1d*pDNGZA<U-pkFbDZa@gua5d02MvT*^SKMD(=>yfa4anT9>zeBpb7QnX7tTVy_ zP{+g1Mje7^=Rw;Wkaw!|`j!>V3>z+(KvNJak##=A!I9ZlZ+aCq3OE5^2)vvZ{(*6b zWGSIUWs0kO8vOXQ=oHi`zs>9_Z2l0VL=$roV|bO3EHvKs7{bXD3Mc9gwSyu}%?#;u z1e0Rk#Dtd^WSK#KeY>~@%8M~%9DGLZ))++RwRQTGjd!-6B4NFM3&DY_;@TIZB+^^L z>qDr5^^4-cuwpoC$00XuF$i;YM<23F@@$_R0Ba_&ZA&_1kd93Ocx~HFHmkS^%+d~K z!P@|5Zwy1P9$XbvRlR=mDKl~riQYuA3!a}Ji@_9bU6=F6G{PUKaJe)XVsW`%o-H7F z@mPEd^UY6K6EERv#axhqR|)f2UcOG;3)5GK#l0jDa1WqX<J~}594}qhXTo^)yBL|Z zVYr+ZuM^_JboLw282Y_TUOKZ1h2iX%D=_c}Yx&{yx)O%7cim>-!{8A{Z3_cAL$`aO zV_cZc-tU%S_t?VAX4W!49OWtY_I(U|OPLm~efCbfnIHSwB718ahH<)z&7kLuuWO_V zd&dz5le~wG(YeJL2cZ?reu9tzwL$~c=?v|hbp6peKYn{5Hv49DhHZFOh)vI17|*`R go56QICxq9r2V1}gkorZUDEM=Gphy&R9a>1y-{H3dYXATM diff --git a/dfall_ws/src/dfall_pkg/crazyradio/docs/_data/menu.yml b/dfall_ws/src/dfall_pkg/crazyradio/docs/_data/menu.yml new file mode 100644 index 00000000..28e1aff2 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/docs/_data/menu.yml @@ -0,0 +1,16 @@ +- page_id: home +- title: Install Instructions + subs: + - {page_id: install_from_source} + - {page_id: usd_permissions} +- title: User guides + subs: + - {page_id: python_api} +- title: Explanation Functionalities + subs: + - {page_id: crazyradio_lib} +- title: Development + subs: + - {page_id: testing} + - {page_id: matlab} + - {page_id: eeprom} diff --git a/dfall_ws/src/dfall_pkg/crazyradio/docs/crazyradio_lib.md b/dfall_ws/src/dfall_pkg/crazyradio/docs/crazyradio_lib.md new file mode 100644 index 00000000..25c1b747 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/docs/crazyradio_lib.md @@ -0,0 +1,161 @@ +--- +title: Python Crazyradio Library +page_id: crazyradio_lib +--- + +The python crazyradio lib can be found in the Crazyflie python library git repos +<https://github.com/bitcraze/crazyflie-lib-python/blob/master/cflib/drivers/crazyradio.py>. +It is a single file that implements the low level Crazyradio dongle +functionalities. + +Theory of operation +------------------- + +The Crazyradio is configured in PTX mode which means that it will start +all comunication. If a device in PRX mode is on the same address, +channel and datarate, the device will send back an ack packet that may +contains data. + + Crazyradio Device + _ _ + | | + | Packet | + |------------>| + | Ack | + |<------------| + | | + +This is an example on how to use the lib: + +``` {.python} +import crazyradio + +cr = crazyradio.Crazyradio() +cr.set_channel(90) +cr.set_data_rate(cr.DR_2MPS) + +res = cr.send_packet([0xff, ]) +print res.ack # At true if an ack has been received +print res.data # The ack payload data +``` + +API +--- + +### Crazyradio + +#### Fields + +None + +#### Methods + +##### [init]{.underline}(self. device=None, devid=0) + +| Name | `_ _init_ _` (Constructor)| +| -------------| ------------------------------------------------| +| Parameters | (USBDevice) device, (int) devid| +| Returns | None| +| Description | Initialize the Crazyradio object. If device is not specified, a list of available Crazyradio is made and devId selects the Crazyradio used (by default the first one)| + +##### close(self) + +| Name | `close`| +| -------------| --------------------------------------------------------------------| +| Parameters | None| +| Returns | None| +| Description | Close the USB device. Should be called before closing the program.| + +##### set\_channel(self, channel) + + | Name | `set_channel` | + | -------------| ---------------------------------------------------------------------| + | Parameters | (int) channel | + | Returns | None | + | Description | Set the Crazyradio channel. Channel must be between 0 and 125. Channels are spaced by 1MHz starting at 2400MHz and ending at 2525MHz. | + +##### set\_address(self, address) + +| Name | `set_address`| +| -------------| ---------------------------| +| Parameters | (list of int) address| +| Returns | None| +| Description | Set the Crazyradio address. The *address* is 5 bytes long. It should be a list of 5 bytes values.| + +##### set\_data\_rate(self, datarate) + + | Name |`set_datarate`| + | ------------- |------------------| + | Parameters |(int) datarate| + | Returns |None| + | Description |Set the Crazyradio datarate. *Datarate* is one of `DR_250KPS`, `DR_1MPS` or `DR_2MPS`| + +##### set\_power(self, power) + +| Name |`set_power`| +| ------------- |----------------------------------------------------------------------------------| +| Parameters |(int) power| +| Returns |None| +| Description |Set the Crazyradio transmit power. *Power* is one of `P_M18DBM`, `P_M12DBM`, `P_M6DBM` or `P_0DBM` respectively for -18dBm, -12dBm, -6dBm and 0dBm.| + +##### set\_arc(self, arc) + + | Name | `set_arc`| + | -------------| ----------------------------------------------------------------------------------| + | Parameters | (int) arc| + | Returns | None| + | Description | Set the number of retry. 0\<*arc*\<15. See nRF24L01 documentation for more info.| + +##### set\_ard\_time(self, us) + +| Name | `set_ard_time`| +| -------------| ---------------------------------------------------------------------------------| +| Parameters | (int) us| +| Returns | None| +| Description | Set the time to wait for an Ack in micro seconds. 250\<*us*\<4000. The wait time for an Ack packet corresponds to the time to receive the biggest expected Ack. See nRF24L01 documentation for more info.| + +##### set\_ard\_bytes(self, nbytes) + +| Name | `set_ard_bytes`| +| -------------| ---------------------------------------------------------------| +| Parameters | (int) nbytes| +| Returns | None| +| Description | Set the time to wait for an Ack in number of ack payload bytes. The Crazyradio will calculate the correct time with the currently selected datarate.| + +##### set\_cont\_carrier(self, active) + +| Name | `set_cont_carrier`| +| -------------| --------------------------------------------------------| +| Parameters | (bool) active| +| Returns | None| +| Description | Enable or disable the continious carrier mode. In continious carrier the Crazyradio transmit a constant sinus at the currently set frequency (channel) and power. This is a test mode that can affect other 2.4GHz devices (ex. wifi) it should only be used in a lab for test purposes.| + +##### scan\_channels(self, start, stop, packet) + +| Name | `scan_channels`| +| -------------| ----------------------------------| +| Parameters | (int) start, (int) stop, (int) packet| +| Returns | (list) List of channels that Acked the packet| +| Description | Sends \\packet\\ to all channels from start to stop. Returns a list of the channels for which an ACK was received.| + +##### send\_packet(self, dataOut) + +| Name | `send_packet`| +| -------------| --------------------------------------------------------| +| Parameters | (list or tuple) dataOut| +| Returns | ([\_radio\_ack](#_radio_ack)) Ack status| +| Description | Sends the packet *dataOut* on the configured channel and datarate. Waits for an ack and returns a \_radio\_ack object that contains the ack status and optional ack payload data.| + +### \_radio\_ack + +#### Fields + +| (bool) ack | At `True` if an Ack packet has been receive (ie. if the packet was received by the device)| + | ----------------- |------------------------------------------| + | (bool) powerDet | Indicate the nRF24LU1 power detector status. See nRF24LU1 documentation for more information.| +| (int) retry | Number of retry before an ack was received| +| (tuple) data | Data payload received in the Ack packet| + +#### Methods + +None diff --git a/dfall_ws/src/dfall_pkg/crazyradio/docs/eeprom.md b/dfall_ws/src/dfall_pkg/crazyradio/docs/eeprom.md new file mode 100644 index 00000000..74a77c39 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/docs/eeprom.md @@ -0,0 +1,23 @@ +--- +title: Reset EEPROM +page_id: eeprom +--- + + + +The EEPROM stores configuration data, which persists even after a +firmware update. You might want to reset this information. For example, +if you forget the address of your Crazyflie, you won\'t be able to +connect wirelessly anymore. In order to reset the EEPROM, follow the +following steps: + +1. Unplug your Crazyradio +2. Connect the Crazyflie to the PC using a USB-cable +3. Execute the following from the examples + +<!-- --> + + python3 write-eeprom.py + +This will find your first Crazyflie (which is the one you connected over +USB) and write the default values to the EEPROM. diff --git a/dfall_ws/src/dfall_pkg/crazyradio/docs/index.md b/dfall_ws/src/dfall_pkg/crazyradio/docs/index.md new file mode 100644 index 00000000..bfefafcd --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/docs/index.md @@ -0,0 +1,12 @@ +--- +title: Home +page_id: home +--- + +cflib is an API written in Python that is used to communicate with the Crazyflie +and Crazyflie 2.0 quadcopters. It is intended to be used by client software to +communicate with and control a Crazyflie quadcopter. For instance the [Crazyflie PC client](https://github.com/bitcraze/crazyflie-clients-python) uses the cflib. + +## Contribute + +Everyone is encouraged to contribute to the CrazyFlie library by forking the Github repository and making a pull request or opening an issue. diff --git a/dfall_ws/src/dfall_pkg/crazyradio/docs/install_from_source.md b/dfall_ws/src/dfall_pkg/crazyradio/docs/install_from_source.md new file mode 100644 index 00000000..8c3cacf0 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/docs/install_from_source.md @@ -0,0 +1,37 @@ +--- +title: Installing from source +page_id: install_from_source +--- +### Developing for the cfclient +* [Fork the cflib](https://help.github.com/articles/fork-a-repo/) +* [Clone the cflib](https://help.github.com/articles/cloning-a-repository/), `git clone git@github.com:YOUR-USERNAME/crazyflie-lib-python.git` +* [Install the cflib in editable mode](http://pip-python3.readthedocs.org/en/latest/reference/pip_install.html?highlight=editable#editable-installs), `pip install -e path/to/cflib` + + +* [Uninstall the cflib if you don't want it any more](http://pip-python3.readthedocs.org/en/latest/reference/pip_uninstall.html), `pip uninstall cflib` + +Note: If you are developing for the [cfclient][cfclient] you must use python3. On Ubuntu (16.04, 18.08) use `pip3` instead of `pip`. + +### Linux, OSX, Windows + +The following should be executed in the root of the crazyflie-lib-python file tree. + +#### Virtualenv +This section contains a very short description of how to use [virtualenv (local python environment)](https://virtualenv.pypa.io/en/latest/) +with package dependencies. If you don't want to use virualenv and don't mind installing cflib dependencies system-wide +you can skip this section. + +* Install virtualenv: `pip install virtualenv` +* create an environment: `virtualenv venv` +* Activate the environment: `source venv/bin/activate` + + +* To deactivate the virtualenv when you are done using it `deactivate` + +Note: For systems that support [make](https://www.gnu.org/software/make/manual/html_node/Simple-Makefile.html), you can use `make venv` to +create an environment, activate it and install dependencies. + +#### Install cflib dependencies +Install dependencies required by the lib: `pip install -r requirements.txt` + +To verify the installation, connect the crazyflie and run an example: `python examples/basiclog` diff --git a/dfall_ws/src/dfall_pkg/crazyradio/docs/matlab.md b/dfall_ws/src/dfall_pkg/crazyradio/docs/matlab.md new file mode 100644 index 00000000..15a94cb5 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/docs/matlab.md @@ -0,0 +1,107 @@ +--- +title: Using Matlab with the Crazyflie API +page_id: matlab +--- + + +Using Matlab with the Crazyflie API is easy -- you just need to install +the python 'matlab engine' and then can access all matlab commands +directly from python. + +Prerequisites +------------- + +1. MATLAB 2014b or later +2. 64 bit python 2.7, 3.3 or 3.4 +3. The Crazyflie API + +Installing the Matlab python engine +----------------------------------- + +1. Find the path to the MATLAB folder. To do this, start MATLAB and + type matlabroot in the command window. Copy the path returned by + matlabroot +2. To install the engine open a command window and on Windows type cd + \"matlabroot\\extern\\engines\\python\". On Mac or Linux systems + type cd \"matlabroot/extern/engines/python\". +3. Finally type python setup.py install + +Step 3 sometimes fails if you do not have write permission to the +default build directory. If this happens: + +3a. Create a new directory to store the build directory where you have +write permission.\ +3b. Then set up the python engine with: +`python setup.py build --build-base builddir install --user `{.bash} + +Here builddir is the path of the directory created in step 3b. Note the +double dashes (no space) before 'build-base' and 'user'. + +### More information (from Mathworks MATLAB documentation) + +System reqirements: +<http://www.mathworks.com/help/matlab/matlab_external/system-requirements-for-matlab-engine-for-python.html> + +Installation: +<http://www.mathworks.com/help/matlab/matlab_external/install-the-matlab-engine-for-python.html> + +Installation in non-default locations +<http://www.mathworks.com/help/matlab/matlab_external/install-matlab-engine-api-for-python-in-nondefault-locations.html> + +Using the Matlab Python engine +------------------------------ + +Once you have installed the matlab engine, you can use any matlab +commands (or your own matlab scripts) from within the Crazyflie API. To +do this: + +1. Import the matlab engine with: `import matlab.engine`{.python} +2. Create a matlab engine object (which starts matlab -- the initial + startup will be slow) with + (eg)`self.eng = matlab.engine.start_matlab()`{.python} +3. ***Optional*** You might want to add a directory with your matlab + scripts to the matlab + path:`self.eng.addpath("directory name",nargout=0)`{.python} +4. ***Optional*** MATLAB errors and console output will usually appear + in the console window of IDEs such as pycharm or Eclipse. To divert + them to a file you can create StringIO objects. To do this you must + first import StringIO, then create the StringIO objects, + eg`self.matlabout = StringIO.StringIO() + self.matlaberr = StringIO.StringIO()`{.python} +5. You can then run a matlab script or function + with:`output = self.eng.function_name([argument list],[stdout=self.matlabout],[stderr=self.matlaberr],[nargout=n])`{.python} + Here 'output' is the output from the matlab function (if multiple + arguments are returned by the function then output is an array - see + the matlab python engine documentation for more information), + \[argument list\] is the input arguments to the matlab function, + self.matlabout and self.matlaberr are StringIO objects to capture + Matlab errors and console output (optional) and n is the number of + output arguments from the MATLAB script (the default is 1). + +### More information + +Matlab engine API documentation from Mathworks: +<http://www.mathworks.com/help/matlab/matlab-engine-for-python.html> + +Call MATLAB functions from python +<http://www.mathworks.com/help/matlab/matlab_external/call-matlab-functions-from-python.html> + +Limitations +----------- + +Not all data structures in matlab and python have direct equivalents. +You can pass most primitive data types between them, as well as arrays. +You can also usually pass matlab data types from one matlab function to +another (eg you can save an output variable from a matlab function such +as a file handle or plot handle in a python variable, and then pass it +to another matlab function). + +For speed it is best to minimize communications between python and +matlab - i.e. try to do all matlab computations through a single script, +instead of calling many matlab functions from inside python. + +More information +---------------- + +Pass data to matlab from python +<http://www.mathworks.com/help/matlab/matlab_external/pass-data-to-matlab-from-python.html> diff --git a/dfall_ws/src/dfall_pkg/crazyradio/docs/python_api.md b/dfall_ws/src/dfall_pkg/crazyradio/docs/python_api.md new file mode 100644 index 00000000..0c9e3c4a --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/docs/python_api.md @@ -0,0 +1,414 @@ +--- +title: The Crazyflie Python API +page_id: python_api +--- + +In order to easily use and control the Crazyflie there\'s an library +made in Python that gives high-level functions and hides the details. +This page contains generic information about how to use this library and +the API that it implements. + +If you are interested in more details look in the PyDoc in the code or: + +- Communication protocol for + [logging](https://www.bitcraze.io/docs/crazyflie-firmware/master/ctrp_log/) or + [parameters](https://www.bitcraze.io/docs/crazyflie-firmware/master/ctrp_parameters/) + +Structure of the library +======================== + +The library is asynchronous and based on callbacks for events. Functions +like `open_link` will return immediately, and the callback `connected` +will be called when the link is opened. The library doesn\'t contain any +threads or locks that will keep the application running, it\'s up to the +application that is using the library to do this. + +Uniform Resource Identifier (URI) +--------------------------------- + +All communication links are identified using an URI build up of the +following: InterfaceType://InterfaceId/InterfaceChannel/InterfaceSpeed + +Currently only *radio* and *debug* interfaces are used but there\'s +ideas for more like *udp*, *serial*, *usb*, etc\...Here are some +examples: + +- \%%Radio interface, USB dongle number 0, radio channel 10 and radio + speed 250 Kbit/s: radio://0/10/250K %% +- Debug interface, id 0, channel 1: debug://0/1 + +Variables and logging +--------------------- + +The library supports setting up logging configurations that are used for +logging variables from the firmware. Each log configuration contains a +number of variables that should be logged as well as a time period (in +ms) of how often the data should be sent back to the host. Once the log +configuration is added to the firmware the firmware will automatically +send back the data at every period. These configurations are used in the +following way: + +- Connect to the Crazyflie (log configurations needs a TOC to work) +- Create a log configuration that contains a number of variables to + log and a period at which they should be logged +- Add the log configuration. This will also validate that the log + configuration is sane (i.e uses a supported period and all variables + are in the TOC) +- After checking that the configuration is valid, set up callbacks for + the data in your application and start the log configuration +- Each time the firmware sends data back to the host the callback will + the called with a time-stamp and the data + +There\'s a few limitations that needs to be taken into account: + +- Each packet is limited to 32bytes, which means that the data that is + logged and the packet that is sent to set it up cannot be larger + than this. It limits the logging to about 14 variables, but this is + dependent on what types they are +- The minimum period of a for a log configuration is multiples of 10ms + +Parameters +---------- + +The library supports reading and writing parameters at run-time to the +firmware. This is intended to be used for data that is not continuously +being changed by the firmware, like setting regulation parameters and +reading out if the power-on self-tests passed. Parameters should only +change in the firmware when being set from the host or during start-up. +The library doesn\'t continuously update the parameter values, this +should only be done once after connecting. After each write to a +parameter the firmware will send back the updated value and this will be +forwarded to callbacks registered for reading this parameter. The +parameters should be used in the following way: + +- Register parameter updated callbacks at any time in your application +- Connect to your Crazyflie (this will download the parameter TOC) +- Request updates for all the parameters +- The library will call all the callbacks registered +- The host can now write parameters that will be forwarded to the + firmware +- For each write all the callbacks registered for this parameter will + be called back + +Variable and parameter names +---------------------------- + +All names of parameters and log variables use the same structure: +`group.name` + +The group should be used to bundle together logical groups, like +everything that has to do with the stabilizer should be in the group +`stabilizer`. + +There\'s a limit of 28 chars in total and here are some examples: + +- stabilizer.roll +- stabilizer.pitch +- pm.vbat +- imu\_tests.MPU6050 +- pid\_attitide.pitch\_kd + +Utilities +========= + +Callbacks +--------- + +All callbacks are handled using the `Caller` class that contains the +following methods: + +``` {.python} + add_callback(cb) + """ Register cb as a new callback. Will not register duplicates. """ + + remove_callback(cb) + """ Un-register cb from the callbacks """ + + call(*args) + """ Call the callbacks registered with the arguments args """ +``` + +Debug driver +------------ + +The library contains a special link driver, named `DebugDriver`. This +driver will emulate a Crazyflie and is used for testing of the UI and +library. Normally this will be hidden from the user except if explicitly +enabled in the configuration file. The driver supports the following: + +- Connecting a download param and log TOCs +- Setting up log configurations and sending back fake data +- Setting and reading parameters +- Bootloading + +There are a number of different URIs that will be returned from the +driver. These will have different functions, like always returning a +random TOC CRC to always trigger TOC downloading or failing during +connect. The driver also has support for sending back data with random +delays to trigger random re-sending by the library. + +Initiating the link drivers +=========================== + +Before the library can be used the link drivers have to he initialized. +This will search for available drivers and instantiate them. + +``` {.python} + init_drivers(enable_debug_driver=False) + """ Search for and initialize link drivers. If enable_debug_driver is True then the DebugDriver will also be used.""" +``` + +Connection- and link-callbacks +============================== + +Operations on the link and connection will return directly and will call +the following callbacks when events occur: + +``` {.python} + # Called on disconnect, no matter the reason + disconnected = Caller() + # Called on unintentional disconnect only + connection_lost = Caller() + # Called when the first packet in a new link is received + link_established = Caller() + # Called when the user requests a connection + connection_requested = Caller() + # Called when the link is established and the TOCs (that are not cached) + # have been downloaded + connected = Caller() + # Called if establishing of the link fails (i.e times out) + connection_failed = Caller() + # Called for every packet received + packet_received = Caller() + # Called for every packet sent + packet_sent = Caller() + # Called when the link driver updates the link quality measurement + link_quality_updated = Caller() +``` + +To register for callbacks the following is used: + +``` {.python} + crazyflie = Crazyflie() + crazyflie.connected.add_callback(crazyflie_connected) +``` + +Finding a Crazyflie and connecting +================================== + +The first thing to do is to find a Crazyflie quadcopter that we can +connect to. This is done by queuing the library that will scan all the +available interfaces (currently the debug and radio interface). + +``` {.python} + cflib.crtp.init_drivers() + available = cflib.crtp.scan_interfaces() + for i in available: + print "Interface with URI [%s] found and name/comment [%s]" % (i[0], i[1]) +``` + +Opening and closing a communication link is doing by using the Crazyflie +object: + +``` {.python} + crazyflie = Crazyflie() + crazyflie.connected.add_callback(crazyflie_connected) + crazyflie.open_link("radio://0/10/250K") +``` + +Then you can use the following to close the link again: + +``` {.python} + crazyflie.close_link() +``` + +Sending control commands +======================== + +The control commands are not implemented as parameters, instead they +have a special API. + +``` {.python} + send_setpoint(roll, pitch, yaw, thrust): + """ + Send a new control set-point for roll/pitch/yaw/thust to the copter + + The arguments roll/pitch/yaw/trust is the new set-points that should + be sent to the copter + """ +``` + +To send a new control set-point use the following: + +``` {.python} + roll = 0.0 + pitch = 0.0 + yawrate = 0 + thrust = 0 + crazyflie.commander.send_setpoint(roll, pitch, yawrate, thrust) +``` + +Thrust is an integer value ranging from 10001 (next to no power) to +60000 (full power). Sending a command makes it apply for 500 ms, after +which the firmware will cut out the power. With this in mind, you need +to try and maintain a thrust level, with a tick being sent at least once +every 2 seconds. Ideally you should be sending one tick every 10 ms, for +100 commands a second. This has a nice added benefit of allowing for +very precise control. + +Parameters +========== + +The parameter framework is used to read and set parameters. This +functionality should be used when: + +- The parameter is not changed by the Crazyflie but by the client +- The parameter is not read periodically + +If this is not the case then the logging framework should be used +instead. + +To set a parameter you have to the connected to the Crazyflie. A +parameter is set using: + +``` {.python} + param_name = "group.name" + param_value = 3 + crazyflie.param.set_value(param_name, param_value) +``` + +The parameter reading is done using callbacks. When a parameter is +updated from the host (using the code above) the parameter will be read +back by the library and this will trigger the callbacks. Parameter +callbacks can be added at any time (you don\'t have to be connected to a +Crazyflie). + +``` {.python} + add_update_callback(group, name=None, cb=None) + """ + Add a callback for a specific parameter name or group. If not name is specified then + all parameters in the group will trigger the callback. This callback will be executed + when a new value is read from the Crazyflie. + """ + + request_param_update(complete_name) + """ Request an update of the value for the supplied parameter. """ + + set_value(complete_name, value) + """ Set the value for the supplied parameter. """ +``` + +Here\'s an example of how to use the calls. + +``` {.python} + crazyflie.param.add_update_callback(group="group", name="name", param_updated_callback) + + def param_updated_callback(name, value): + print "%s has value %d" % (name, value) +``` + +Logging +======= + +The logging framework is used to enable the \"automatic\" sending of +variable values at specified intervals to the client. This functionality +should be used when: + +- The variable is changed by the Crazyflie and not by the client +- The variable is updated at high rate and you want to read the value + periodically + +If this is not the case then the parameter framework should be used +instead. + +The API to create and get information from LogConfig: + +``` {.python} + # Called when new logging data arrives + data_received_cb = Caller() + # Called when there's an error + error_cb = Caller() + # Called when the log configuration is confirmed to be started + started_cb = Caller() + # Called when the log configuration is confirmed to be added + added_cb = Caller() + + add_variable(name, fetch_as=None) + """Add a new variable to the configuration. + + name - Complete name of the variable in the form group.name + fetch_as - String representation of the type the variable should be + fetched as (i.e uint8_t, float, FP16, etc) + + If no fetch_as type is supplied, then the stored as type will be used + (i.e the type of the fetched variable is the same as it's stored in the + Crazyflie).""" + + start() + """Start the logging for this entry""" + + stop() + """Stop the logging for this entry""" + + delete() + """Delete this entry in the Crazyflie""" +``` + +The API for the log in the Crazyflie: + +``` {.python} + add_config(logconf) + """Add a log configuration to the logging framework. + + When doing this the contents of the log configuration will be validated + and listeners for new log configurations will be notified. When + validating the configuration the variables are checked against the TOC + to see that they actually exist. If they don't then the configuration + cannot be used. Since a valid TOC is required, a Crazyflie has to be + connected when calling this method, otherwise it will fail.""" +``` + +To create a logging configuration the following can be used: + +``` {.python} + logconf = LogConfig(name="Logging", period_in_ms=100) + logconf.add_variable("group1.name1", "float") + logconf.add_variable("group1.name2", "uint8_t") + logconf.add_variable("group2.name1", "int16_t") +``` + +The datatype is the transferred datatype, it will be converted from +internal type to transferred type before transfers: + +- float +- uint8\_t and int8\_t +- uint16\_t and int16\_t +- uint32\_t and int32\_t +- FP16: 16bit version of floating point, allows to pack more variable + in one packet at the expense of precision. + +The logging cannot be started until your are connected to a Crazyflie: + +``` {.python} + # Callback called when the connection is established to the Crazyflie + def connected(link_uri): + crazyflie.log.add_config(logconf) + + if logconf.valid: + logconf.data_received_cb.add_callback(data_received_callback) + logconf.error_cb.add_callback(logging_error) + logconf.start() + else: + print "One or more of the variables in the configuration was not found in log TOC. No logging will be possible." + + def data_received_callback(timestamp, data, logconf): + print "[%d][%s]: %s" % (timestamp, logconf.name, data) + + def logging_error(logconf, msg): + print "Error when logging %s" % logconf.name +``` + +Examples +======== + +The examples are now placed in the repository in the examples folder. diff --git a/dfall_ws/src/dfall_pkg/crazyradio/docs/testing.md b/dfall_ws/src/dfall_pkg/crazyradio/docs/testing.md new file mode 100644 index 00000000..cd05d12b --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/docs/testing.md @@ -0,0 +1,26 @@ +--- +title: Testing +page_id: testing +--- + +## Testing +### With docker and the toolbelt + +For information and installation of the +[toolbelt.](https://wiki.bitcraze.io/projects:dockerbuilderimage:index) + +* Check to see if you pass tests: `tb test` +* Check to see if you pass style guidelines: `tb verify` + +Note: Docker and the toolbelt is an optional way of running tests and reduces the +work needed to maintain your python environmet. + +### Native python on Linux, OSX, Windows + [Tox](http://tox.readthedocs.org/en/latest/) is used for native testing: `pip install tox` +* If test fails after installing tox with `pip install tox`, installing with `sudo apt-get install tox`result a successful test run + +* Test package in python2.7 `TOXENV=py27 tox` +* Test package in python3.4 `TOXENV=py34 tox` +* Test package in python3.6 `TOXENV=py36 tox` + +Note: You must have the specific python versions on your machine or tests will fail. (ie. without specifying the TOXENV, `tox` runs tests for python2.7, 3.3, 3.4 and would require all python versions to be installed on the machine.) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/docs/usb_permissions.md b/dfall_ws/src/dfall_pkg/crazyradio/docs/usb_permissions.md new file mode 100644 index 00000000..e88959e7 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/docs/usb_permissions.md @@ -0,0 +1,35 @@ +--- +title: USB permissions +page_id: usd_permissions +--- + +### Linux + +The following steps make it possible to use the USB Radio without being root. + +``` +sudo groupadd plugdev +sudo usermod -a -G plugdev $USER +``` + +You will need to log out and log in again in order to be a member of the plugdev group. + +Create a file named ```/etc/udev/rules.d/99-crazyradio.rules``` and add the +following: +``` +# Crazyradio (normal operation) +SUBSYSTEM=="usb", ATTRS{idVendor}=="1915", ATTRS{idProduct}=="7777", MODE="0664", GROUP="plugdev" +# Bootloader +SUBSYSTEM=="usb", ATTRS{idVendor}=="1915", ATTRS{idProduct}=="0101", MODE="0664", GROUP="plugdev" +``` + +To connect Crazyflie 2.0 via usb, create a file name ```/etc/udev/rules.d/99-crazyflie.rules``` and add the following: +``` +SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5740", MODE="0664", GROUP="plugdev" +``` + +You can reload the udev-rules using the following: +``` +sudo udevadm control --reload-rules +sudo udevadm trigger +``` diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/autonomousSequence.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/autonomousSequence.py index a0e4ec77..f4d37fac 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/autonomousSequence.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/autonomousSequence.py @@ -35,6 +35,7 @@ and how to send setpoints. import time import cflib.crtp +from cflib.crazyflie import Crazyflie from cflib.crazyflie.log import LogConfig from cflib.crazyflie.syncCrazyflie import SyncCrazyflie from cflib.crazyflie.syncLogger import SyncLogger @@ -126,17 +127,16 @@ def start_position_printing(scf): def run_sequence(scf, sequence): cf = scf.cf - cf.param.set_value('flightmode.posSet', '1') - for position in sequence: print('Setting position {}'.format(position)) for i in range(50): - cf.commander.send_setpoint(position[1], position[0], - position[3], - int(position[2] * 1000)) + cf.commander.send_position_setpoint(position[0], + position[1], + position[2], + position[3]) time.sleep(0.1) - cf.commander.send_setpoint(0, 0, 0, 0) + cf.commander.send_stop_setpoint() # Make sure that the last packet leaves before the link is closed # since the message queue is not flushed before closing time.sleep(0.1) @@ -145,7 +145,7 @@ def run_sequence(scf, sequence): if __name__ == '__main__': cflib.crtp.init_drivers(enable_debug_driver=False) - with SyncCrazyflie(uri) as scf: + with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf: reset_estimator(scf) # start_position_printing(scf) run_sequence(scf, sequence) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/autonomous_sequence_high_level.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/autonomous_sequence_high_level.py new file mode 100644 index 00000000..9132a791 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/autonomous_sequence_high_level.py @@ -0,0 +1,182 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2018 Bitcraze AB +# +# 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. +""" +Simple example that connects to one crazyflie (check the address at the top +and update it to your crazyflie address) and uses the high level commander +to send setpoints and trajectory to fly a figure 8. + +This example is intended to work with any positioning system (including LPS). +It aims at documenting how to set the Crazyflie in position control mode +and how to send setpoints using the high level commander. +""" +import time + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.mem import MemoryElement +from cflib.crazyflie.mem import Poly4D +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from cflib.crazyflie.syncLogger import SyncLogger + +# URI to the Crazyflie to connect to +uri = 'radio://0/80/2M' + +# The trajectory to fly +# See https://github.com/whoenig/uav_trajectories for a tool to generate +# trajectories + +# Duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7 +figure8 = [ + [1.050000, 0.000000, -0.000000, 0.000000, -0.000000, 0.830443, -0.276140, -0.384219, 0.180493, -0.000000, 0.000000, -0.000000, 0.000000, -1.356107, 0.688430, 0.587426, -0.329106, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.710000, 0.396058, 0.918033, 0.128965, -0.773546, 0.339704, 0.034310, -0.026417, -0.030049, -0.445604, -0.684403, 0.888433, 1.493630, -1.361618, -0.139316, 0.158875, 0.095799, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.620000, 0.922409, 0.405715, -0.582968, -0.092188, -0.114670, 0.101046, 0.075834, -0.037926, -0.291165, 0.967514, 0.421451, -1.086348, 0.545211, 0.030109, -0.050046, -0.068177, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.700000, 0.923174, -0.431533, -0.682975, 0.177173, 0.319468, -0.043852, -0.111269, 0.023166, 0.289869, 0.724722, -0.512011, -0.209623, -0.218710, 0.108797, 0.128756, -0.055461, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.560000, 0.405364, -0.834716, 0.158939, 0.288175, -0.373738, -0.054995, 0.036090, 0.078627, 0.450742, -0.385534, -0.954089, 0.128288, 0.442620, 0.055630, -0.060142, -0.076163, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.560000, 0.001062, -0.646270, -0.012560, -0.324065, 0.125327, 0.119738, 0.034567, -0.063130, 0.001593, -1.031457, 0.015159, 0.820816, -0.152665, -0.130729, -0.045679, 0.080444, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.700000, -0.402804, -0.820508, -0.132914, 0.236278, 0.235164, -0.053551, -0.088687, 0.031253, -0.449354, -0.411507, 0.902946, 0.185335, -0.239125, -0.041696, 0.016857, 0.016709, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.620000, -0.921641, -0.464596, 0.661875, 0.286582, -0.228921, -0.051987, 0.004669, 0.038463, -0.292459, 0.777682, 0.565788, -0.432472, -0.060568, -0.082048, -0.009439, 0.041158, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.710000, -0.923935, 0.447832, 0.627381, -0.259808, -0.042325, -0.032258, 0.001420, 0.005294, 0.288570, 0.873350, -0.515586, -0.730207, -0.026023, 0.288755, 0.215678, -0.148061, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [1.053185, -0.398611, 0.850510, -0.144007, -0.485368, -0.079781, 0.176330, 0.234482, -0.153567, 0.447039, -0.532729, -0.855023, 0.878509, 0.775168, -0.391051, -0.713519, 0.391628, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa +] + + +class Uploader: + def __init__(self): + self._is_done = False + + def upload(self, trajectory_mem): + print('Uploading data') + trajectory_mem.write_data(self._upload_done) + + while not self._is_done: + time.sleep(0.2) + + def _upload_done(self, mem, addr): + print('Data uploaded') + self._is_done = True + + +def wait_for_position_estimator(scf): + print('Waiting for estimator to find position...') + + log_config = LogConfig(name='Kalman Variance', period_in_ms=500) + log_config.add_variable('kalman.varPX', 'float') + log_config.add_variable('kalman.varPY', 'float') + log_config.add_variable('kalman.varPZ', 'float') + + var_y_history = [1000] * 10 + var_x_history = [1000] * 10 + var_z_history = [1000] * 10 + + threshold = 0.001 + + with SyncLogger(scf, log_config) as logger: + for log_entry in logger: + data = log_entry[1] + + var_x_history.append(data['kalman.varPX']) + var_x_history.pop(0) + var_y_history.append(data['kalman.varPY']) + var_y_history.pop(0) + var_z_history.append(data['kalman.varPZ']) + var_z_history.pop(0) + + min_x = min(var_x_history) + max_x = max(var_x_history) + min_y = min(var_y_history) + max_y = max(var_y_history) + min_z = min(var_z_history) + max_z = max(var_z_history) + + # print("{} {} {}". + # format(max_x - min_x, max_y - min_y, max_z - min_z)) + + if (max_x - min_x) < threshold and ( + max_y - min_y) < threshold and ( + max_z - min_z) < threshold: + break + + +def reset_estimator(cf): + cf.param.set_value('kalman.resetEstimation', '1') + time.sleep(0.1) + cf.param.set_value('kalman.resetEstimation', '0') + + wait_for_position_estimator(cf) + + +def activate_high_level_commander(cf): + cf.param.set_value('commander.enHighLevel', '1') + + +def activate_mellinger_controller(cf): + cf.param.set_value('stabilizer.controller', '2') + + +def upload_trajectory(cf, trajectory_id, trajectory): + trajectory_mem = cf.mem.get_mems(MemoryElement.TYPE_TRAJ)[0] + + total_duration = 0 + for row in trajectory: + duration = row[0] + x = Poly4D.Poly(row[1:9]) + y = Poly4D.Poly(row[9:17]) + z = Poly4D.Poly(row[17:25]) + yaw = Poly4D.Poly(row[25:33]) + trajectory_mem.poly4Ds.append(Poly4D(duration, x, y, z, yaw)) + total_duration += duration + + Uploader().upload(trajectory_mem) + cf.high_level_commander.define_trajectory(trajectory_id, 0, + len(trajectory_mem.poly4Ds)) + return total_duration + + +def run_sequence(cf, trajectory_id, duration): + commander = cf.high_level_commander + + commander.takeoff(1.0, 2.0) + time.sleep(3.0) + relative = True + commander.start_trajectory(trajectory_id, 1.0, relative) + time.sleep(duration) + commander.land(0.0, 2.0) + time.sleep(2) + commander.stop() + + +if __name__ == '__main__': + cflib.crtp.init_drivers(enable_debug_driver=False) + + with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf: + cf = scf.cf + trajectory_id = 1 + + activate_high_level_commander(cf) + # activate_mellinger_controller(cf) + duration = upload_trajectory(cf, trajectory_id, figure8) + print('The sequence is {:.1f} seconds long'.format(duration)) + reset_estimator(cf) + run_sequence(cf, trajectory_id, duration) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/basicLedmemSync.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/basicLedmemSync.py new file mode 100644 index 00000000..e8155331 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/basicLedmemSync.py @@ -0,0 +1,66 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# Crazyflie Nano Quadcopter Client +# +# 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. +""" +Simple example that connects to the crazyflie at `URI` and writes to +the LED memory so that individual leds in the LED-ring can be set, +it has been tested with (and designed for) the LED-ring deck. + +Change the URI variable to your Crazyflie configuration. +""" +import logging +import time + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.mem import MemoryElement +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie + +URI = 'radio://0/80/250K' + +# Only output errors from the logging framework +logging.basicConfig(level=logging.ERROR) + + +if __name__ == '__main__': + # Initialize the low-level drivers (don't list the debug drivers) + cflib.crtp.init_drivers(enable_debug_driver=False) + + with SyncCrazyflie(URI, cf=Crazyflie(rw_cache='./cache')) as scf: + cf = scf.cf + + # Set virtual mem effect effect + cf.param.set_value('ring.effect', '13') + + # Get LED memory and write to it + mem = cf.mem.get_mems(MemoryElement.TYPE_DRIVER_LED) + if len(mem) > 0: + mem[0].leds[0].set(r=0, g=100, b=0) + mem[0].leds[3].set(r=0, g=0, b=100) + mem[0].leds[6].set(r=100, g=0, b=0) + mem[0].leds[9].set(r=100, g=100, b=100) + mem[0].write_data(None) + + time.sleep(2) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/basicLedparamSync.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/basicLedparamSync.py new file mode 100644 index 00000000..654d88fb --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/basicLedparamSync.py @@ -0,0 +1,74 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# Crazyflie Nano Quadcopter Client +# +# 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. +""" +Simple example that connects to the crazyflie at `URI` and writes to +parameters that control the LED-ring, +it has been tested with (and designed for) the LED-ring deck. + +Change the URI variable to your Crazyflie configuration. +""" +import logging +import time + +import cflib.crtp +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie + +URI = 'radio://0/80/250K' + +# Only output errors from the logging framework +logging.basicConfig(level=logging.ERROR) + + +if __name__ == '__main__': + # Initialize the low-level drivers (don't list the debug drivers) + cflib.crtp.init_drivers(enable_debug_driver=False) + + with SyncCrazyflie(URI) as scf: + cf = scf.cf + + # Set solid color effect + cf.param.set_value('ring.effect', '7') + # Set the RGB values + cf.param.set_value('ring.solidRed', '100') + cf.param.set_value('ring.solidGreen', '0') + cf.param.set_value('ring.solidBlue', '0') + time.sleep(2) + + # Set black color effect + cf.param.set_value('ring.effect', '0') + time.sleep(1) + + # Set fade to color effect + cf.param.set_value('ring.effect', '14') + # Set fade time i seconds + cf.param.set_value('ring.fadeTime', '1.0') + # Set the RGB values in one uint32 0xRRGGBB + cf.param.set_value('ring.fadeColor', '0x0000A0') + time.sleep(1) + cf.param.set_value('ring.fadeColor', '0x00A000') + time.sleep(1) + cf.param.set_value('ring.fadeColor', '0xA00000') + time.sleep(1) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/basiclog.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/basiclog.py index 26c59c5b..e8c118c8 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/basiclog.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/basiclog.py @@ -48,8 +48,7 @@ class LoggingExample: def __init__(self, link_uri): """ Initialize and run the example with the specified link_uri """ - # Create a Crazyflie object without specifying any cache dirs - self._cf = Crazyflie() + self._cf = Crazyflie(rw_cache='./cache') # Connect some callbacks from the Crazyflie API self._cf.connected.add_callback(self._connected) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/basiclogSync.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/basiclogSync.py index 8cca3c17..e24765ef 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/basiclogSync.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/basiclogSync.py @@ -33,6 +33,7 @@ import logging import time import cflib.crtp +from cflib.crazyflie import Crazyflie from cflib.crazyflie.log import LogConfig from cflib.crazyflie.syncCrazyflie import SyncCrazyflie from cflib.crazyflie.syncLogger import SyncLogger @@ -59,7 +60,11 @@ if __name__ == '__main__': lg_stab.add_variable('stabilizer.pitch', 'float') lg_stab.add_variable('stabilizer.yaw', 'float') - with SyncCrazyflie(available[0][0]) as scf: + cf = Crazyflie(rw_cache='./cache') + with SyncCrazyflie(available[0][0], cf=cf) as scf: + # Note: it is possible to add more than one log config using an + # array. + # with SyncLogger(scf, [lg_stab, other_conf]) as logger: with SyncLogger(scf, lg_stab) as logger: endTime = time.time() + 10 diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/basicparam.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/basicparam.py index 7ee2747b..d2b76bf6 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/basicparam.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/basicparam.py @@ -48,8 +48,7 @@ class ParamExample: def __init__(self, link_uri): """ Initialize and run the example with the specified link_uri """ - # Create a Crazyflie object without specifying any cache dirs - self._cf = Crazyflie() + self._cf = Crazyflie(rw_cache='./cache') # Connect some callbacks from the Crazyflie API self._cf.connected.add_callback(self._connected) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/cache/.gitkeep b/dfall_ws/src/dfall_pkg/crazyradio/examples/cache/.gitkeep new file mode 100644 index 00000000..05c2cbe2 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/cache/.gitkeep @@ -0,0 +1 @@ +I'm here to prevent git from removing the directory diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/cache/AB949641.json b/dfall_ws/src/dfall_pkg/crazyradio/examples/cache/AB949641.json new file mode 100644 index 00000000..f82651d4 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/cache/AB949641.json @@ -0,0 +1,1738 @@ +{ + "imu_sensors": { + "BMP388": { + "__class__": "ParamTocElement", + "ident": 6, + "group": "imu_sensors", + "name": "BMP388", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "HMC5883L": { + "__class__": "ParamTocElement", + "ident": 1, + "group": "imu_sensors", + "name": "HMC5883L", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "MS5611": { + "__class__": "ParamTocElement", + "ident": 2, + "group": "imu_sensors", + "name": "MS5611", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + } + }, + "imu_tests": { + "MPU6500": { + "__class__": "ParamTocElement", + "ident": 3, + "group": "imu_tests", + "name": "MPU6500", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "HMC5883L": { + "__class__": "ParamTocElement", + "ident": 4, + "group": "imu_tests", + "name": "HMC5883L", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "MS5611": { + "__class__": "ParamTocElement", + "ident": 5, + "group": "imu_tests", + "name": "MS5611", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + } + }, + "cpu": { + "flash": { + "__class__": "ParamTocElement", + "ident": 7, + "group": "cpu", + "name": "flash", + "ctype": "uint16_t", + "pytype": "<H", + "access": 1 + }, + "id0": { + "__class__": "ParamTocElement", + "ident": 8, + "group": "cpu", + "name": "id0", + "ctype": "uint32_t", + "pytype": "<L", + "access": 1 + }, + "id1": { + "__class__": "ParamTocElement", + "ident": 9, + "group": "cpu", + "name": "id1", + "ctype": "uint32_t", + "pytype": "<L", + "access": 1 + }, + "id2": { + "__class__": "ParamTocElement", + "ident": 10, + "group": "cpu", + "name": "id2", + "ctype": "uint32_t", + "pytype": "<L", + "access": 1 + } + }, + "system": { + "selftestPassed": { + "__class__": "ParamTocElement", + "ident": 11, + "group": "system", + "name": "selftestPassed", + "ctype": "int8_t", + "pytype": "<b", + "access": 0 + }, + "taskDump": { + "__class__": "ParamTocElement", + "ident": 16, + "group": "system", + "name": "taskDump", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "sound": { + "effect": { + "__class__": "ParamTocElement", + "ident": 12, + "group": "sound", + "name": "effect", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "neffect": { + "__class__": "ParamTocElement", + "ident": 13, + "group": "sound", + "name": "neffect", + "ctype": "uint32_t", + "pytype": "<L", + "access": 1 + }, + "freq": { + "__class__": "ParamTocElement", + "ident": 14, + "group": "sound", + "name": "freq", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "ratio": { + "__class__": "ParamTocElement", + "ident": 15, + "group": "sound", + "name": "ratio", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "memTst": { + "resetW": { + "__class__": "ParamTocElement", + "ident": 17, + "group": "memTst", + "name": "resetW", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "commander": { + "enHighLevel": { + "__class__": "ParamTocElement", + "ident": 18, + "group": "commander", + "name": "enHighLevel", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "flightmode": { + "althold": { + "__class__": "ParamTocElement", + "ident": 19, + "group": "flightmode", + "name": "althold", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "poshold": { + "__class__": "ParamTocElement", + "ident": 20, + "group": "flightmode", + "name": "poshold", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "posSet": { + "__class__": "ParamTocElement", + "ident": 21, + "group": "flightmode", + "name": "posSet", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "yawMode": { + "__class__": "ParamTocElement", + "ident": 22, + "group": "flightmode", + "name": "yawMode", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "yawRst": { + "__class__": "ParamTocElement", + "ident": 23, + "group": "flightmode", + "name": "yawRst", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "stabModeRoll": { + "__class__": "ParamTocElement", + "ident": 24, + "group": "flightmode", + "name": "stabModeRoll", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "stabModePitch": { + "__class__": "ParamTocElement", + "ident": 25, + "group": "flightmode", + "name": "stabModePitch", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "stabModeYaw": { + "__class__": "ParamTocElement", + "ident": 26, + "group": "flightmode", + "name": "stabModeYaw", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "cmdrCPPM": { + "rateRoll": { + "__class__": "ParamTocElement", + "ident": 27, + "group": "cmdrCPPM", + "name": "rateRoll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ratePitch": { + "__class__": "ParamTocElement", + "ident": 28, + "group": "cmdrCPPM", + "name": "ratePitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rateYaw": { + "__class__": "ParamTocElement", + "ident": 29, + "group": "cmdrCPPM", + "name": "rateYaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "angRoll": { + "__class__": "ParamTocElement", + "ident": 30, + "group": "cmdrCPPM", + "name": "angRoll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "angPitch": { + "__class__": "ParamTocElement", + "ident": 31, + "group": "cmdrCPPM", + "name": "angPitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "locSrv": { + "enRangeStreamFP32": { + "__class__": "ParamTocElement", + "ident": 32, + "group": "locSrv", + "name": "enRangeStreamFP32", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "extPosStdDev": { + "__class__": "ParamTocElement", + "ident": 33, + "group": "locSrv", + "name": "extPosStdDev", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "extQuatStdDev": { + "__class__": "ParamTocElement", + "ident": 34, + "group": "locSrv", + "name": "extQuatStdDev", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "pid_attitude": { + "roll_kp": { + "__class__": "ParamTocElement", + "ident": 35, + "group": "pid_attitude", + "name": "roll_kp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll_ki": { + "__class__": "ParamTocElement", + "ident": 36, + "group": "pid_attitude", + "name": "roll_ki", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll_kd": { + "__class__": "ParamTocElement", + "ident": 37, + "group": "pid_attitude", + "name": "roll_kd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_kp": { + "__class__": "ParamTocElement", + "ident": 38, + "group": "pid_attitude", + "name": "pitch_kp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_ki": { + "__class__": "ParamTocElement", + "ident": 39, + "group": "pid_attitude", + "name": "pitch_ki", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_kd": { + "__class__": "ParamTocElement", + "ident": 40, + "group": "pid_attitude", + "name": "pitch_kd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_kp": { + "__class__": "ParamTocElement", + "ident": 41, + "group": "pid_attitude", + "name": "yaw_kp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_ki": { + "__class__": "ParamTocElement", + "ident": 42, + "group": "pid_attitude", + "name": "yaw_ki", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_kd": { + "__class__": "ParamTocElement", + "ident": 43, + "group": "pid_attitude", + "name": "yaw_kd", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "pid_rate": { + "roll_kp": { + "__class__": "ParamTocElement", + "ident": 44, + "group": "pid_rate", + "name": "roll_kp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll_ki": { + "__class__": "ParamTocElement", + "ident": 45, + "group": "pid_rate", + "name": "roll_ki", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll_kd": { + "__class__": "ParamTocElement", + "ident": 46, + "group": "pid_rate", + "name": "roll_kd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_kp": { + "__class__": "ParamTocElement", + "ident": 47, + "group": "pid_rate", + "name": "pitch_kp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_ki": { + "__class__": "ParamTocElement", + "ident": 48, + "group": "pid_rate", + "name": "pitch_ki", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_kd": { + "__class__": "ParamTocElement", + "ident": 49, + "group": "pid_rate", + "name": "pitch_kd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_kp": { + "__class__": "ParamTocElement", + "ident": 50, + "group": "pid_rate", + "name": "yaw_kp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_ki": { + "__class__": "ParamTocElement", + "ident": 51, + "group": "pid_rate", + "name": "yaw_ki", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_kd": { + "__class__": "ParamTocElement", + "ident": 52, + "group": "pid_rate", + "name": "yaw_kd", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "sensfusion6": { + "kp": { + "__class__": "ParamTocElement", + "ident": 53, + "group": "sensfusion6", + "name": "kp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ki": { + "__class__": "ParamTocElement", + "ident": 54, + "group": "sensfusion6", + "name": "ki", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "baseZacc": { + "__class__": "ParamTocElement", + "ident": 55, + "group": "sensfusion6", + "name": "baseZacc", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "health": { + "startPropTest": { + "__class__": "ParamTocElement", + "ident": 56, + "group": "health", + "name": "startPropTest", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "stabilizer": { + "estimator": { + "__class__": "ParamTocElement", + "ident": 57, + "group": "stabilizer", + "name": "estimator", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "controller": { + "__class__": "ParamTocElement", + "ident": 58, + "group": "stabilizer", + "name": "controller", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "stop": { + "__class__": "ParamTocElement", + "ident": 59, + "group": "stabilizer", + "name": "stop", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "posEstAlt": { + "estAlphaAsl": { + "__class__": "ParamTocElement", + "ident": 60, + "group": "posEstAlt", + "name": "estAlphaAsl", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "estAlphaZr": { + "__class__": "ParamTocElement", + "ident": 61, + "group": "posEstAlt", + "name": "estAlphaZr", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "velFactor": { + "__class__": "ParamTocElement", + "ident": 62, + "group": "posEstAlt", + "name": "velFactor", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "velZAlpha": { + "__class__": "ParamTocElement", + "ident": 63, + "group": "posEstAlt", + "name": "velZAlpha", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vAccDeadband": { + "__class__": "ParamTocElement", + "ident": 64, + "group": "posEstAlt", + "name": "vAccDeadband", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "posCtlPid": { + "xKp": { + "__class__": "ParamTocElement", + "ident": 65, + "group": "posCtlPid", + "name": "xKp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "xKi": { + "__class__": "ParamTocElement", + "ident": 66, + "group": "posCtlPid", + "name": "xKi", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "xKd": { + "__class__": "ParamTocElement", + "ident": 67, + "group": "posCtlPid", + "name": "xKd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yKp": { + "__class__": "ParamTocElement", + "ident": 68, + "group": "posCtlPid", + "name": "yKp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yKi": { + "__class__": "ParamTocElement", + "ident": 69, + "group": "posCtlPid", + "name": "yKi", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yKd": { + "__class__": "ParamTocElement", + "ident": 70, + "group": "posCtlPid", + "name": "yKd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "zKp": { + "__class__": "ParamTocElement", + "ident": 71, + "group": "posCtlPid", + "name": "zKp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "zKi": { + "__class__": "ParamTocElement", + "ident": 72, + "group": "posCtlPid", + "name": "zKi", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "zKd": { + "__class__": "ParamTocElement", + "ident": 73, + "group": "posCtlPid", + "name": "zKd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "thrustBase": { + "__class__": "ParamTocElement", + "ident": 74, + "group": "posCtlPid", + "name": "thrustBase", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "thrustMin": { + "__class__": "ParamTocElement", + "ident": 75, + "group": "posCtlPid", + "name": "thrustMin", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "rpLimit": { + "__class__": "ParamTocElement", + "ident": 76, + "group": "posCtlPid", + "name": "rpLimit", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "xyVelMax": { + "__class__": "ParamTocElement", + "ident": 77, + "group": "posCtlPid", + "name": "xyVelMax", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "zVelMax": { + "__class__": "ParamTocElement", + "ident": 78, + "group": "posCtlPid", + "name": "zVelMax", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "velCtlPid": { + "vxKp": { + "__class__": "ParamTocElement", + "ident": 79, + "group": "velCtlPid", + "name": "vxKp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vxKi": { + "__class__": "ParamTocElement", + "ident": 80, + "group": "velCtlPid", + "name": "vxKi", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vxKd": { + "__class__": "ParamTocElement", + "ident": 81, + "group": "velCtlPid", + "name": "vxKd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vyKp": { + "__class__": "ParamTocElement", + "ident": 82, + "group": "velCtlPid", + "name": "vyKp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vyKi": { + "__class__": "ParamTocElement", + "ident": 83, + "group": "velCtlPid", + "name": "vyKi", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vyKd": { + "__class__": "ParamTocElement", + "ident": 84, + "group": "velCtlPid", + "name": "vyKd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vzKp": { + "__class__": "ParamTocElement", + "ident": 85, + "group": "velCtlPid", + "name": "vzKp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vzKi": { + "__class__": "ParamTocElement", + "ident": 86, + "group": "velCtlPid", + "name": "vzKi", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vzKd": { + "__class__": "ParamTocElement", + "ident": 87, + "group": "velCtlPid", + "name": "vzKd", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "controller": { + "tiltComp": { + "__class__": "ParamTocElement", + "ident": 88, + "group": "controller", + "name": "tiltComp", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "ctrlMel": { + "kp_xy": { + "__class__": "ParamTocElement", + "ident": 89, + "group": "ctrlMel", + "name": "kp_xy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "kd_xy": { + "__class__": "ParamTocElement", + "ident": 90, + "group": "ctrlMel", + "name": "kd_xy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ki_xy": { + "__class__": "ParamTocElement", + "ident": 91, + "group": "ctrlMel", + "name": "ki_xy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "i_range_xy": { + "__class__": "ParamTocElement", + "ident": 92, + "group": "ctrlMel", + "name": "i_range_xy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "kp_z": { + "__class__": "ParamTocElement", + "ident": 93, + "group": "ctrlMel", + "name": "kp_z", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "kd_z": { + "__class__": "ParamTocElement", + "ident": 94, + "group": "ctrlMel", + "name": "kd_z", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ki_z": { + "__class__": "ParamTocElement", + "ident": 95, + "group": "ctrlMel", + "name": "ki_z", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "i_range_z": { + "__class__": "ParamTocElement", + "ident": 96, + "group": "ctrlMel", + "name": "i_range_z", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "mass": { + "__class__": "ParamTocElement", + "ident": 97, + "group": "ctrlMel", + "name": "mass", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "massThrust": { + "__class__": "ParamTocElement", + "ident": 98, + "group": "ctrlMel", + "name": "massThrust", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "kR_xy": { + "__class__": "ParamTocElement", + "ident": 99, + "group": "ctrlMel", + "name": "kR_xy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "kR_z": { + "__class__": "ParamTocElement", + "ident": 100, + "group": "ctrlMel", + "name": "kR_z", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "kw_xy": { + "__class__": "ParamTocElement", + "ident": 101, + "group": "ctrlMel", + "name": "kw_xy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "kw_z": { + "__class__": "ParamTocElement", + "ident": 102, + "group": "ctrlMel", + "name": "kw_z", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ki_m_xy": { + "__class__": "ParamTocElement", + "ident": 103, + "group": "ctrlMel", + "name": "ki_m_xy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ki_m_z": { + "__class__": "ParamTocElement", + "ident": 104, + "group": "ctrlMel", + "name": "ki_m_z", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "kd_omega_rp": { + "__class__": "ParamTocElement", + "ident": 105, + "group": "ctrlMel", + "name": "kd_omega_rp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "i_range_m_xy": { + "__class__": "ParamTocElement", + "ident": 106, + "group": "ctrlMel", + "name": "i_range_m_xy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "i_range_m_z": { + "__class__": "ParamTocElement", + "ident": 107, + "group": "ctrlMel", + "name": "i_range_m_z", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "ctrlINDI": { + "thrust_threshold": { + "__class__": "ParamTocElement", + "ident": 108, + "group": "ctrlINDI", + "name": "thrust_threshold", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "bound_ctrl_input": { + "__class__": "ParamTocElement", + "ident": 109, + "group": "ctrlINDI", + "name": "bound_ctrl_input", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll_kp": { + "__class__": "ParamTocElement", + "ident": 110, + "group": "ctrlINDI", + "name": "roll_kp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_kp": { + "__class__": "ParamTocElement", + "ident": 111, + "group": "ctrlINDI", + "name": "pitch_kp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_kp": { + "__class__": "ParamTocElement", + "ident": 112, + "group": "ctrlINDI", + "name": "yaw_kp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "g1_p": { + "__class__": "ParamTocElement", + "ident": 113, + "group": "ctrlINDI", + "name": "g1_p", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "g1_q": { + "__class__": "ParamTocElement", + "ident": 114, + "group": "ctrlINDI", + "name": "g1_q", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "g1_r": { + "__class__": "ParamTocElement", + "ident": 115, + "group": "ctrlINDI", + "name": "g1_r", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "g2": { + "__class__": "ParamTocElement", + "ident": 116, + "group": "ctrlINDI", + "name": "g2", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ref_err_p": { + "__class__": "ParamTocElement", + "ident": 117, + "group": "ctrlINDI", + "name": "ref_err_p", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ref_err_q": { + "__class__": "ParamTocElement", + "ident": 118, + "group": "ctrlINDI", + "name": "ref_err_q", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ref_err_r": { + "__class__": "ParamTocElement", + "ident": 119, + "group": "ctrlINDI", + "name": "ref_err_r", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ref_rate_p": { + "__class__": "ParamTocElement", + "ident": 120, + "group": "ctrlINDI", + "name": "ref_rate_p", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ref_rate_q": { + "__class__": "ParamTocElement", + "ident": 121, + "group": "ctrlINDI", + "name": "ref_rate_q", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ref_rate_r": { + "__class__": "ParamTocElement", + "ident": 122, + "group": "ctrlINDI", + "name": "ref_rate_r", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "act_dyn_p": { + "__class__": "ParamTocElement", + "ident": 123, + "group": "ctrlINDI", + "name": "act_dyn_p", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "act_dyn_q": { + "__class__": "ParamTocElement", + "ident": 124, + "group": "ctrlINDI", + "name": "act_dyn_q", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "act_dyn_r": { + "__class__": "ParamTocElement", + "ident": 125, + "group": "ctrlINDI", + "name": "act_dyn_r", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "filt_cutoff": { + "__class__": "ParamTocElement", + "ident": 126, + "group": "ctrlINDI", + "name": "filt_cutoff", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "filt_cutoff_r": { + "__class__": "ParamTocElement", + "ident": 127, + "group": "ctrlINDI", + "name": "filt_cutoff_r", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "motorPowerSet": { + "enable": { + "__class__": "ParamTocElement", + "ident": 128, + "group": "motorPowerSet", + "name": "enable", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "m1": { + "__class__": "ParamTocElement", + "ident": 129, + "group": "motorPowerSet", + "name": "m1", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "m2": { + "__class__": "ParamTocElement", + "ident": 130, + "group": "motorPowerSet", + "name": "m2", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "m3": { + "__class__": "ParamTocElement", + "ident": 131, + "group": "motorPowerSet", + "name": "m3", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "m4": { + "__class__": "ParamTocElement", + "ident": 132, + "group": "motorPowerSet", + "name": "m4", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + } + }, + "kalman": { + "resetEstimation": { + "__class__": "ParamTocElement", + "ident": 133, + "group": "kalman", + "name": "resetEstimation", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "quadIsFlying": { + "__class__": "ParamTocElement", + "ident": 134, + "group": "kalman", + "name": "quadIsFlying", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "pNAcc_xy": { + "__class__": "ParamTocElement", + "ident": 135, + "group": "kalman", + "name": "pNAcc_xy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pNAcc_z": { + "__class__": "ParamTocElement", + "ident": 136, + "group": "kalman", + "name": "pNAcc_z", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pNVel": { + "__class__": "ParamTocElement", + "ident": 137, + "group": "kalman", + "name": "pNVel", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pNPos": { + "__class__": "ParamTocElement", + "ident": 138, + "group": "kalman", + "name": "pNPos", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pNAtt": { + "__class__": "ParamTocElement", + "ident": 139, + "group": "kalman", + "name": "pNAtt", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "mNBaro": { + "__class__": "ParamTocElement", + "ident": 140, + "group": "kalman", + "name": "mNBaro", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "mNGyro_rollpitch": { + "__class__": "ParamTocElement", + "ident": 141, + "group": "kalman", + "name": "mNGyro_rollpitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "mNGyro_yaw": { + "__class__": "ParamTocElement", + "ident": 142, + "group": "kalman", + "name": "mNGyro_yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "initialX": { + "__class__": "ParamTocElement", + "ident": 143, + "group": "kalman", + "name": "initialX", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "initialY": { + "__class__": "ParamTocElement", + "ident": 144, + "group": "kalman", + "name": "initialY", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "initialZ": { + "__class__": "ParamTocElement", + "ident": 145, + "group": "kalman", + "name": "initialZ", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "initialYaw": { + "__class__": "ParamTocElement", + "ident": 146, + "group": "kalman", + "name": "initialYaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "maxPos": { + "__class__": "ParamTocElement", + "ident": 147, + "group": "kalman", + "name": "maxPos", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "maxVel": { + "__class__": "ParamTocElement", + "ident": 148, + "group": "kalman", + "name": "maxVel", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "deck": { + "bcLedRing": { + "__class__": "ParamTocElement", + "ident": 149, + "group": "deck", + "name": "bcLedRing", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bcBuzzer": { + "__class__": "ParamTocElement", + "ident": 161, + "group": "deck", + "name": "bcBuzzer", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bcGTGPS": { + "__class__": "ParamTocElement", + "ident": 162, + "group": "deck", + "name": "bcGTGPS", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bcCPPM": { + "__class__": "ParamTocElement", + "ident": 163, + "group": "deck", + "name": "bcCPPM", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bcUSD": { + "__class__": "ParamTocElement", + "ident": 164, + "group": "deck", + "name": "bcUSD", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bcZRanger": { + "__class__": "ParamTocElement", + "ident": 166, + "group": "deck", + "name": "bcZRanger", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bcZRanger2": { + "__class__": "ParamTocElement", + "ident": 167, + "group": "deck", + "name": "bcZRanger2", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bcDWM1000": { + "__class__": "ParamTocElement", + "ident": 168, + "group": "deck", + "name": "bcDWM1000", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bcFlow": { + "__class__": "ParamTocElement", + "ident": 172, + "group": "deck", + "name": "bcFlow", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bcFlow2": { + "__class__": "ParamTocElement", + "ident": 173, + "group": "deck", + "name": "bcFlow2", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bcOA": { + "__class__": "ParamTocElement", + "ident": 175, + "group": "deck", + "name": "bcOA", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bcMultiranger": { + "__class__": "ParamTocElement", + "ident": 176, + "group": "deck", + "name": "bcMultiranger", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + }, + "bdLighthouse4": { + "__class__": "ParamTocElement", + "ident": 177, + "group": "deck", + "name": "bdLighthouse4", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + } + }, + "ring": { + "effect": { + "__class__": "ParamTocElement", + "ident": 150, + "group": "ring", + "name": "effect", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "neffect": { + "__class__": "ParamTocElement", + "ident": 151, + "group": "ring", + "name": "neffect", + "ctype": "uint32_t", + "pytype": "<L", + "access": 1 + }, + "solidRed": { + "__class__": "ParamTocElement", + "ident": 152, + "group": "ring", + "name": "solidRed", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "solidGreen": { + "__class__": "ParamTocElement", + "ident": 153, + "group": "ring", + "name": "solidGreen", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "solidBlue": { + "__class__": "ParamTocElement", + "ident": 154, + "group": "ring", + "name": "solidBlue", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "headlightEnable": { + "__class__": "ParamTocElement", + "ident": 155, + "group": "ring", + "name": "headlightEnable", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "glowstep": { + "__class__": "ParamTocElement", + "ident": 156, + "group": "ring", + "name": "glowstep", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "emptyCharge": { + "__class__": "ParamTocElement", + "ident": 157, + "group": "ring", + "name": "emptyCharge", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "fullCharge": { + "__class__": "ParamTocElement", + "ident": 158, + "group": "ring", + "name": "fullCharge", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "fadeColor": { + "__class__": "ParamTocElement", + "ident": 159, + "group": "ring", + "name": "fadeColor", + "ctype": "uint32_t", + "pytype": "<L", + "access": 0 + }, + "fadeTime": { + "__class__": "ParamTocElement", + "ident": 160, + "group": "ring", + "name": "fadeTime", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "usd": { + "logging": { + "__class__": "ParamTocElement", + "ident": 165, + "group": "usd", + "name": "logging", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "loco": { + "mode": { + "__class__": "ParamTocElement", + "ident": 169, + "group": "loco", + "name": "mode", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "tdoa3": { + "logId": { + "__class__": "ParamTocElement", + "ident": 170, + "group": "tdoa3", + "name": "logId", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "logOthrId": { + "__class__": "ParamTocElement", + "ident": 171, + "group": "tdoa3", + "name": "logOthrId", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "motion": { + "disable": { + "__class__": "ParamTocElement", + "ident": 174, + "group": "motion", + "name": "disable", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "activeMarker": { + "front": { + "__class__": "ParamTocElement", + "ident": 178, + "group": "activeMarker", + "name": "front", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "back": { + "__class__": "ParamTocElement", + "ident": 179, + "group": "activeMarker", + "name": "back", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "left": { + "__class__": "ParamTocElement", + "ident": 180, + "group": "activeMarker", + "name": "left", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "right": { + "__class__": "ParamTocElement", + "ident": 181, + "group": "activeMarker", + "name": "right", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "mode": { + "__class__": "ParamTocElement", + "ident": 182, + "group": "activeMarker", + "name": "mode", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "poll": { + "__class__": "ParamTocElement", + "ident": 183, + "group": "activeMarker", + "name": "poll", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "firmware": { + "revision0": { + "__class__": "ParamTocElement", + "ident": 184, + "group": "firmware", + "name": "revision0", + "ctype": "uint32_t", + "pytype": "<L", + "access": 1 + }, + "revision1": { + "__class__": "ParamTocElement", + "ident": 185, + "group": "firmware", + "name": "revision1", + "ctype": "uint16_t", + "pytype": "<H", + "access": 1 + }, + "modified": { + "__class__": "ParamTocElement", + "ident": 186, + "group": "firmware", + "name": "modified", + "ctype": "uint8_t", + "pytype": "<B", + "access": 1 + } + } +} \ No newline at end of file diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/cache/CA011AD2.json b/dfall_ws/src/dfall_pkg/crazyradio/examples/cache/CA011AD2.json new file mode 100644 index 00000000..33c07952 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/cache/CA011AD2.json @@ -0,0 +1,3393 @@ +{ + "gyro": { + "xRaw": { + "__class__": "LogTocElement", + "ident": 0, + "group": "gyro", + "name": "xRaw", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "yRaw": { + "__class__": "LogTocElement", + "ident": 1, + "group": "gyro", + "name": "yRaw", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "zRaw": { + "__class__": "LogTocElement", + "ident": 2, + "group": "gyro", + "name": "zRaw", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "xVariance": { + "__class__": "LogTocElement", + "ident": 3, + "group": "gyro", + "name": "xVariance", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yVariance": { + "__class__": "LogTocElement", + "ident": 4, + "group": "gyro", + "name": "yVariance", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "zVariance": { + "__class__": "LogTocElement", + "ident": 5, + "group": "gyro", + "name": "zVariance", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "x": { + "__class__": "LogTocElement", + "ident": 101, + "group": "gyro", + "name": "x", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "y": { + "__class__": "LogTocElement", + "ident": 102, + "group": "gyro", + "name": "y", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "z": { + "__class__": "LogTocElement", + "ident": 103, + "group": "gyro", + "name": "z", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "pwm": { + "m1_pwm": { + "__class__": "LogTocElement", + "ident": 6, + "group": "pwm", + "name": "m1_pwm", + "ctype": "uint32_t", + "pytype": "<L", + "access": 0 + }, + "m2_pwm": { + "__class__": "LogTocElement", + "ident": 7, + "group": "pwm", + "name": "m2_pwm", + "ctype": "uint32_t", + "pytype": "<L", + "access": 0 + }, + "m3_pwm": { + "__class__": "LogTocElement", + "ident": 8, + "group": "pwm", + "name": "m3_pwm", + "ctype": "uint32_t", + "pytype": "<L", + "access": 0 + }, + "m4_pwm": { + "__class__": "LogTocElement", + "ident": 9, + "group": "pwm", + "name": "m4_pwm", + "ctype": "uint32_t", + "pytype": "<L", + "access": 0 + } + }, + "crtp": { + "rxRate": { + "__class__": "LogTocElement", + "ident": 10, + "group": "crtp", + "name": "rxRate", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "txRate": { + "__class__": "LogTocElement", + "ident": 11, + "group": "crtp", + "name": "txRate", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + } + }, + "pm": { + "vbat": { + "__class__": "LogTocElement", + "ident": 12, + "group": "pm", + "name": "vbat", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vbatMV": { + "__class__": "LogTocElement", + "ident": 13, + "group": "pm", + "name": "vbatMV", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "extVbat": { + "__class__": "LogTocElement", + "ident": 14, + "group": "pm", + "name": "extVbat", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "extVbatMV": { + "__class__": "LogTocElement", + "ident": 15, + "group": "pm", + "name": "extVbatMV", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "extCurr": { + "__class__": "LogTocElement", + "ident": 16, + "group": "pm", + "name": "extCurr", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "chargeCurrent": { + "__class__": "LogTocElement", + "ident": 17, + "group": "pm", + "name": "chargeCurrent", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "state": { + "__class__": "LogTocElement", + "ident": 18, + "group": "pm", + "name": "state", + "ctype": "int8_t", + "pytype": "<b", + "access": 0 + }, + "batteryLevel": { + "__class__": "LogTocElement", + "ident": 19, + "group": "pm", + "name": "batteryLevel", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "radio": { + "rssi": { + "__class__": "LogTocElement", + "ident": 20, + "group": "radio", + "name": "rssi", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "isConnected": { + "__class__": "LogTocElement", + "ident": 21, + "group": "radio", + "name": "isConnected", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "sys": { + "canfly": { + "__class__": "LogTocElement", + "ident": 22, + "group": "sys", + "name": "canfly", + "ctype": "int8_t", + "pytype": "<b", + "access": 0 + } + }, + "sitAw": { + "FFAccWZDetected": { + "__class__": "LogTocElement", + "ident": 23, + "group": "sitAw", + "name": "FFAccWZDetected", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "ARDetected": { + "__class__": "LogTocElement", + "ident": 24, + "group": "sitAw", + "name": "ARDetected", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "TuDetected": { + "__class__": "LogTocElement", + "ident": 25, + "group": "sitAw", + "name": "TuDetected", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "extrx": { + "ch0": { + "__class__": "LogTocElement", + "ident": 26, + "group": "extrx", + "name": "ch0", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "ch1": { + "__class__": "LogTocElement", + "ident": 27, + "group": "extrx", + "name": "ch1", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "ch2": { + "__class__": "LogTocElement", + "ident": 28, + "group": "extrx", + "name": "ch2", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "ch3": { + "__class__": "LogTocElement", + "ident": 29, + "group": "extrx", + "name": "ch3", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "thrust": { + "__class__": "LogTocElement", + "ident": 30, + "group": "extrx", + "name": "thrust", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "roll": { + "__class__": "LogTocElement", + "ident": 31, + "group": "extrx", + "name": "roll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch": { + "__class__": "LogTocElement", + "ident": 32, + "group": "extrx", + "name": "pitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw": { + "__class__": "LogTocElement", + "ident": 33, + "group": "extrx", + "name": "yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "memTst": { + "errCntW": { + "__class__": "LogTocElement", + "ident": 34, + "group": "memTst", + "name": "errCntW", + "ctype": "uint32_t", + "pytype": "<L", + "access": 0 + } + }, + "range": { + "front": { + "__class__": "LogTocElement", + "ident": 35, + "group": "range", + "name": "front", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "back": { + "__class__": "LogTocElement", + "ident": 36, + "group": "range", + "name": "back", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "up": { + "__class__": "LogTocElement", + "ident": 37, + "group": "range", + "name": "up", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "left": { + "__class__": "LogTocElement", + "ident": 38, + "group": "range", + "name": "left", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "right": { + "__class__": "LogTocElement", + "ident": 39, + "group": "range", + "name": "right", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "zrange": { + "__class__": "LogTocElement", + "ident": 40, + "group": "range", + "name": "zrange", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + } + }, + "ext_pos": { + "X": { + "__class__": "LogTocElement", + "ident": 41, + "group": "ext_pos", + "name": "X", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "Y": { + "__class__": "LogTocElement", + "ident": 42, + "group": "ext_pos", + "name": "Y", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "Z": { + "__class__": "LogTocElement", + "ident": 43, + "group": "ext_pos", + "name": "Z", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "locSrvZ": { + "tick": { + "__class__": "LogTocElement", + "ident": 44, + "group": "locSrvZ", + "name": "tick", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + } + }, + "pid_attitude": { + "roll_outP": { + "__class__": "LogTocElement", + "ident": 45, + "group": "pid_attitude", + "name": "roll_outP", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll_outI": { + "__class__": "LogTocElement", + "ident": 46, + "group": "pid_attitude", + "name": "roll_outI", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll_outD": { + "__class__": "LogTocElement", + "ident": 47, + "group": "pid_attitude", + "name": "roll_outD", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_outP": { + "__class__": "LogTocElement", + "ident": 48, + "group": "pid_attitude", + "name": "pitch_outP", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_outI": { + "__class__": "LogTocElement", + "ident": 49, + "group": "pid_attitude", + "name": "pitch_outI", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_outD": { + "__class__": "LogTocElement", + "ident": 50, + "group": "pid_attitude", + "name": "pitch_outD", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_outP": { + "__class__": "LogTocElement", + "ident": 51, + "group": "pid_attitude", + "name": "yaw_outP", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_outI": { + "__class__": "LogTocElement", + "ident": 52, + "group": "pid_attitude", + "name": "yaw_outI", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_outD": { + "__class__": "LogTocElement", + "ident": 53, + "group": "pid_attitude", + "name": "yaw_outD", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "pid_rate": { + "roll_outP": { + "__class__": "LogTocElement", + "ident": 54, + "group": "pid_rate", + "name": "roll_outP", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll_outI": { + "__class__": "LogTocElement", + "ident": 55, + "group": "pid_rate", + "name": "roll_outI", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll_outD": { + "__class__": "LogTocElement", + "ident": 56, + "group": "pid_rate", + "name": "roll_outD", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_outP": { + "__class__": "LogTocElement", + "ident": 57, + "group": "pid_rate", + "name": "pitch_outP", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_outI": { + "__class__": "LogTocElement", + "ident": 58, + "group": "pid_rate", + "name": "pitch_outI", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch_outD": { + "__class__": "LogTocElement", + "ident": 59, + "group": "pid_rate", + "name": "pitch_outD", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_outP": { + "__class__": "LogTocElement", + "ident": 60, + "group": "pid_rate", + "name": "yaw_outP", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_outI": { + "__class__": "LogTocElement", + "ident": 61, + "group": "pid_rate", + "name": "yaw_outI", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw_outD": { + "__class__": "LogTocElement", + "ident": 62, + "group": "pid_rate", + "name": "yaw_outD", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "sensfusion6": { + "qw": { + "__class__": "LogTocElement", + "ident": 63, + "group": "sensfusion6", + "name": "qw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "qx": { + "__class__": "LogTocElement", + "ident": 64, + "group": "sensfusion6", + "name": "qx", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "qy": { + "__class__": "LogTocElement", + "ident": 65, + "group": "sensfusion6", + "name": "qy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "qz": { + "__class__": "LogTocElement", + "ident": 66, + "group": "sensfusion6", + "name": "qz", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "gravityX": { + "__class__": "LogTocElement", + "ident": 67, + "group": "sensfusion6", + "name": "gravityX", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "gravityY": { + "__class__": "LogTocElement", + "ident": 68, + "group": "sensfusion6", + "name": "gravityY", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "gravityZ": { + "__class__": "LogTocElement", + "ident": 69, + "group": "sensfusion6", + "name": "gravityZ", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "accZbase": { + "__class__": "LogTocElement", + "ident": 70, + "group": "sensfusion6", + "name": "accZbase", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "isInit": { + "__class__": "LogTocElement", + "ident": 71, + "group": "sensfusion6", + "name": "isInit", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "isCalibrated": { + "__class__": "LogTocElement", + "ident": 72, + "group": "sensfusion6", + "name": "isCalibrated", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "acc": { + "x": { + "__class__": "LogTocElement", + "ident": 73, + "group": "acc", + "name": "x", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "y": { + "__class__": "LogTocElement", + "ident": 74, + "group": "acc", + "name": "y", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "z": { + "__class__": "LogTocElement", + "ident": 75, + "group": "acc", + "name": "z", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "baro": { + "asl": { + "__class__": "LogTocElement", + "ident": 76, + "group": "baro", + "name": "asl", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "temp": { + "__class__": "LogTocElement", + "ident": 77, + "group": "baro", + "name": "temp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pressure": { + "__class__": "LogTocElement", + "ident": 78, + "group": "baro", + "name": "pressure", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "controller": { + "ctr_yaw": { + "__class__": "LogTocElement", + "ident": 79, + "group": "controller", + "name": "ctr_yaw", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "cmd_thrust": { + "__class__": "LogTocElement", + "ident": 179, + "group": "controller", + "name": "cmd_thrust", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cmd_roll": { + "__class__": "LogTocElement", + "ident": 180, + "group": "controller", + "name": "cmd_roll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cmd_pitch": { + "__class__": "LogTocElement", + "ident": 181, + "group": "controller", + "name": "cmd_pitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cmd_yaw": { + "__class__": "LogTocElement", + "ident": 182, + "group": "controller", + "name": "cmd_yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "r_roll": { + "__class__": "LogTocElement", + "ident": 183, + "group": "controller", + "name": "r_roll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "r_pitch": { + "__class__": "LogTocElement", + "ident": 184, + "group": "controller", + "name": "r_pitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "r_yaw": { + "__class__": "LogTocElement", + "ident": 185, + "group": "controller", + "name": "r_yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "accelz": { + "__class__": "LogTocElement", + "ident": 186, + "group": "controller", + "name": "accelz", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "actuatorThrust": { + "__class__": "LogTocElement", + "ident": 187, + "group": "controller", + "name": "actuatorThrust", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll": { + "__class__": "LogTocElement", + "ident": 188, + "group": "controller", + "name": "roll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch": { + "__class__": "LogTocElement", + "ident": 189, + "group": "controller", + "name": "pitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw": { + "__class__": "LogTocElement", + "ident": 190, + "group": "controller", + "name": "yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rollRate": { + "__class__": "LogTocElement", + "ident": 191, + "group": "controller", + "name": "rollRate", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitchRate": { + "__class__": "LogTocElement", + "ident": 192, + "group": "controller", + "name": "pitchRate", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yawRate": { + "__class__": "LogTocElement", + "ident": 193, + "group": "controller", + "name": "yawRate", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "ctrltarget": { + "x": { + "__class__": "LogTocElement", + "ident": 80, + "group": "ctrltarget", + "name": "x", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "y": { + "__class__": "LogTocElement", + "ident": 81, + "group": "ctrltarget", + "name": "y", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "z": { + "__class__": "LogTocElement", + "ident": 82, + "group": "ctrltarget", + "name": "z", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vx": { + "__class__": "LogTocElement", + "ident": 83, + "group": "ctrltarget", + "name": "vx", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vy": { + "__class__": "LogTocElement", + "ident": 84, + "group": "ctrltarget", + "name": "vy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vz": { + "__class__": "LogTocElement", + "ident": 85, + "group": "ctrltarget", + "name": "vz", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ax": { + "__class__": "LogTocElement", + "ident": 86, + "group": "ctrltarget", + "name": "ax", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ay": { + "__class__": "LogTocElement", + "ident": 87, + "group": "ctrltarget", + "name": "ay", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "az": { + "__class__": "LogTocElement", + "ident": 88, + "group": "ctrltarget", + "name": "az", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll": { + "__class__": "LogTocElement", + "ident": 89, + "group": "ctrltarget", + "name": "roll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch": { + "__class__": "LogTocElement", + "ident": 90, + "group": "ctrltarget", + "name": "pitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw": { + "__class__": "LogTocElement", + "ident": 91, + "group": "ctrltarget", + "name": "yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "ctrltargetZ": { + "x": { + "__class__": "LogTocElement", + "ident": 92, + "group": "ctrltargetZ", + "name": "x", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "y": { + "__class__": "LogTocElement", + "ident": 93, + "group": "ctrltargetZ", + "name": "y", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "z": { + "__class__": "LogTocElement", + "ident": 94, + "group": "ctrltargetZ", + "name": "z", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "vx": { + "__class__": "LogTocElement", + "ident": 95, + "group": "ctrltargetZ", + "name": "vx", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "vy": { + "__class__": "LogTocElement", + "ident": 96, + "group": "ctrltargetZ", + "name": "vy", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "vz": { + "__class__": "LogTocElement", + "ident": 97, + "group": "ctrltargetZ", + "name": "vz", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "ax": { + "__class__": "LogTocElement", + "ident": 98, + "group": "ctrltargetZ", + "name": "ax", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "ay": { + "__class__": "LogTocElement", + "ident": 99, + "group": "ctrltargetZ", + "name": "ay", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "az": { + "__class__": "LogTocElement", + "ident": 100, + "group": "ctrltargetZ", + "name": "az", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + } + }, + "health": { + "motorVarXM1": { + "__class__": "LogTocElement", + "ident": 104, + "group": "health", + "name": "motorVarXM1", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "motorVarYM1": { + "__class__": "LogTocElement", + "ident": 105, + "group": "health", + "name": "motorVarYM1", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "motorVarXM2": { + "__class__": "LogTocElement", + "ident": 106, + "group": "health", + "name": "motorVarXM2", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "motorVarYM2": { + "__class__": "LogTocElement", + "ident": 107, + "group": "health", + "name": "motorVarYM2", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "motorVarXM3": { + "__class__": "LogTocElement", + "ident": 108, + "group": "health", + "name": "motorVarXM3", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "motorVarYM3": { + "__class__": "LogTocElement", + "ident": 109, + "group": "health", + "name": "motorVarYM3", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "motorVarXM4": { + "__class__": "LogTocElement", + "ident": 110, + "group": "health", + "name": "motorVarXM4", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "motorVarYM4": { + "__class__": "LogTocElement", + "ident": 111, + "group": "health", + "name": "motorVarYM4", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "motorPass": { + "__class__": "LogTocElement", + "ident": 112, + "group": "health", + "name": "motorPass", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "motorTestCount": { + "__class__": "LogTocElement", + "ident": 113, + "group": "health", + "name": "motorTestCount", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + } + }, + "mag": { + "x": { + "__class__": "LogTocElement", + "ident": 114, + "group": "mag", + "name": "x", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "y": { + "__class__": "LogTocElement", + "ident": 115, + "group": "mag", + "name": "y", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "z": { + "__class__": "LogTocElement", + "ident": 116, + "group": "mag", + "name": "z", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "stabilizer": { + "roll": { + "__class__": "LogTocElement", + "ident": 117, + "group": "stabilizer", + "name": "roll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch": { + "__class__": "LogTocElement", + "ident": 118, + "group": "stabilizer", + "name": "pitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw": { + "__class__": "LogTocElement", + "ident": 119, + "group": "stabilizer", + "name": "yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "thrust": { + "__class__": "LogTocElement", + "ident": 120, + "group": "stabilizer", + "name": "thrust", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rtStab": { + "__class__": "LogTocElement", + "ident": 121, + "group": "stabilizer", + "name": "rtStab", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "intToOut": { + "__class__": "LogTocElement", + "ident": 122, + "group": "stabilizer", + "name": "intToOut", + "ctype": "uint32_t", + "pytype": "<L", + "access": 0 + } + }, + "stateEstimate": { + "x": { + "__class__": "LogTocElement", + "ident": 123, + "group": "stateEstimate", + "name": "x", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "y": { + "__class__": "LogTocElement", + "ident": 124, + "group": "stateEstimate", + "name": "y", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "z": { + "__class__": "LogTocElement", + "ident": 125, + "group": "stateEstimate", + "name": "z", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vx": { + "__class__": "LogTocElement", + "ident": 126, + "group": "stateEstimate", + "name": "vx", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vy": { + "__class__": "LogTocElement", + "ident": 127, + "group": "stateEstimate", + "name": "vy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vz": { + "__class__": "LogTocElement", + "ident": 128, + "group": "stateEstimate", + "name": "vz", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ax": { + "__class__": "LogTocElement", + "ident": 129, + "group": "stateEstimate", + "name": "ax", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ay": { + "__class__": "LogTocElement", + "ident": 130, + "group": "stateEstimate", + "name": "ay", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "az": { + "__class__": "LogTocElement", + "ident": 131, + "group": "stateEstimate", + "name": "az", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "roll": { + "__class__": "LogTocElement", + "ident": 132, + "group": "stateEstimate", + "name": "roll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pitch": { + "__class__": "LogTocElement", + "ident": 133, + "group": "stateEstimate", + "name": "pitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "yaw": { + "__class__": "LogTocElement", + "ident": 134, + "group": "stateEstimate", + "name": "yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "qx": { + "__class__": "LogTocElement", + "ident": 135, + "group": "stateEstimate", + "name": "qx", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "qy": { + "__class__": "LogTocElement", + "ident": 136, + "group": "stateEstimate", + "name": "qy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "qz": { + "__class__": "LogTocElement", + "ident": 137, + "group": "stateEstimate", + "name": "qz", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "qw": { + "__class__": "LogTocElement", + "ident": 138, + "group": "stateEstimate", + "name": "qw", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "stateEstimateZ": { + "x": { + "__class__": "LogTocElement", + "ident": 139, + "group": "stateEstimateZ", + "name": "x", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "y": { + "__class__": "LogTocElement", + "ident": 140, + "group": "stateEstimateZ", + "name": "y", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "z": { + "__class__": "LogTocElement", + "ident": 141, + "group": "stateEstimateZ", + "name": "z", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "vx": { + "__class__": "LogTocElement", + "ident": 142, + "group": "stateEstimateZ", + "name": "vx", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "vy": { + "__class__": "LogTocElement", + "ident": 143, + "group": "stateEstimateZ", + "name": "vy", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "vz": { + "__class__": "LogTocElement", + "ident": 144, + "group": "stateEstimateZ", + "name": "vz", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "ax": { + "__class__": "LogTocElement", + "ident": 145, + "group": "stateEstimateZ", + "name": "ax", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "ay": { + "__class__": "LogTocElement", + "ident": 146, + "group": "stateEstimateZ", + "name": "ay", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "az": { + "__class__": "LogTocElement", + "ident": 147, + "group": "stateEstimateZ", + "name": "az", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "roll": { + "__class__": "LogTocElement", + "ident": 148, + "group": "stateEstimateZ", + "name": "roll", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "pitch": { + "__class__": "LogTocElement", + "ident": 149, + "group": "stateEstimateZ", + "name": "pitch", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "yaw": { + "__class__": "LogTocElement", + "ident": 150, + "group": "stateEstimateZ", + "name": "yaw", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "quat": { + "__class__": "LogTocElement", + "ident": 151, + "group": "stateEstimateZ", + "name": "quat", + "ctype": "uint32_t", + "pytype": "<L", + "access": 0 + }, + "rateRoll": { + "__class__": "LogTocElement", + "ident": 152, + "group": "stateEstimateZ", + "name": "rateRoll", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "ratePitch": { + "__class__": "LogTocElement", + "ident": 153, + "group": "stateEstimateZ", + "name": "ratePitch", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "rateYaw": { + "__class__": "LogTocElement", + "ident": 154, + "group": "stateEstimateZ", + "name": "rateYaw", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + } + }, + "posEstAlt": { + "estimatedZ": { + "__class__": "LogTocElement", + "ident": 155, + "group": "posEstAlt", + "name": "estimatedZ", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "estVZ": { + "__class__": "LogTocElement", + "ident": 156, + "group": "posEstAlt", + "name": "estVZ", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "velocityZ": { + "__class__": "LogTocElement", + "ident": 157, + "group": "posEstAlt", + "name": "velocityZ", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "posCtl": { + "targetVX": { + "__class__": "LogTocElement", + "ident": 158, + "group": "posCtl", + "name": "targetVX", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "targetVY": { + "__class__": "LogTocElement", + "ident": 159, + "group": "posCtl", + "name": "targetVY", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "targetVZ": { + "__class__": "LogTocElement", + "ident": 160, + "group": "posCtl", + "name": "targetVZ", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "targetX": { + "__class__": "LogTocElement", + "ident": 161, + "group": "posCtl", + "name": "targetX", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "targetY": { + "__class__": "LogTocElement", + "ident": 162, + "group": "posCtl", + "name": "targetY", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "targetZ": { + "__class__": "LogTocElement", + "ident": 163, + "group": "posCtl", + "name": "targetZ", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "Xp": { + "__class__": "LogTocElement", + "ident": 164, + "group": "posCtl", + "name": "Xp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "Xi": { + "__class__": "LogTocElement", + "ident": 165, + "group": "posCtl", + "name": "Xi", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "Xd": { + "__class__": "LogTocElement", + "ident": 166, + "group": "posCtl", + "name": "Xd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "Yp": { + "__class__": "LogTocElement", + "ident": 167, + "group": "posCtl", + "name": "Yp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "Yi": { + "__class__": "LogTocElement", + "ident": 168, + "group": "posCtl", + "name": "Yi", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "Yd": { + "__class__": "LogTocElement", + "ident": 169, + "group": "posCtl", + "name": "Yd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "Zp": { + "__class__": "LogTocElement", + "ident": 170, + "group": "posCtl", + "name": "Zp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "Zi": { + "__class__": "LogTocElement", + "ident": 171, + "group": "posCtl", + "name": "Zi", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "Zd": { + "__class__": "LogTocElement", + "ident": 172, + "group": "posCtl", + "name": "Zd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "VXp": { + "__class__": "LogTocElement", + "ident": 173, + "group": "posCtl", + "name": "VXp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "VXi": { + "__class__": "LogTocElement", + "ident": 174, + "group": "posCtl", + "name": "VXi", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "VXd": { + "__class__": "LogTocElement", + "ident": 175, + "group": "posCtl", + "name": "VXd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "VZp": { + "__class__": "LogTocElement", + "ident": 176, + "group": "posCtl", + "name": "VZp", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "VZi": { + "__class__": "LogTocElement", + "ident": 177, + "group": "posCtl", + "name": "VZi", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "VZd": { + "__class__": "LogTocElement", + "ident": 178, + "group": "posCtl", + "name": "VZd", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "ctrlMel": { + "cmd_thrust": { + "__class__": "LogTocElement", + "ident": 194, + "group": "ctrlMel", + "name": "cmd_thrust", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cmd_roll": { + "__class__": "LogTocElement", + "ident": 195, + "group": "ctrlMel", + "name": "cmd_roll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cmd_pitch": { + "__class__": "LogTocElement", + "ident": 196, + "group": "ctrlMel", + "name": "cmd_pitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cmd_yaw": { + "__class__": "LogTocElement", + "ident": 197, + "group": "ctrlMel", + "name": "cmd_yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "r_roll": { + "__class__": "LogTocElement", + "ident": 198, + "group": "ctrlMel", + "name": "r_roll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "r_pitch": { + "__class__": "LogTocElement", + "ident": 199, + "group": "ctrlMel", + "name": "r_pitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "r_yaw": { + "__class__": "LogTocElement", + "ident": 200, + "group": "ctrlMel", + "name": "r_yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "accelz": { + "__class__": "LogTocElement", + "ident": 201, + "group": "ctrlMel", + "name": "accelz", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "zdx": { + "__class__": "LogTocElement", + "ident": 202, + "group": "ctrlMel", + "name": "zdx", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "zdy": { + "__class__": "LogTocElement", + "ident": 203, + "group": "ctrlMel", + "name": "zdy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "zdz": { + "__class__": "LogTocElement", + "ident": 204, + "group": "ctrlMel", + "name": "zdz", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "i_err_x": { + "__class__": "LogTocElement", + "ident": 205, + "group": "ctrlMel", + "name": "i_err_x", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "i_err_y": { + "__class__": "LogTocElement", + "ident": 206, + "group": "ctrlMel", + "name": "i_err_y", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "i_err_z": { + "__class__": "LogTocElement", + "ident": 207, + "group": "ctrlMel", + "name": "i_err_z", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "ctrlINDI": { + "cmd_thrust": { + "__class__": "LogTocElement", + "ident": 208, + "group": "ctrlINDI", + "name": "cmd_thrust", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cmd_roll": { + "__class__": "LogTocElement", + "ident": 209, + "group": "ctrlINDI", + "name": "cmd_roll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cmd_pitch": { + "__class__": "LogTocElement", + "ident": 210, + "group": "ctrlINDI", + "name": "cmd_pitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cmd_yaw": { + "__class__": "LogTocElement", + "ident": 211, + "group": "ctrlINDI", + "name": "cmd_yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "r_roll": { + "__class__": "LogTocElement", + "ident": 212, + "group": "ctrlINDI", + "name": "r_roll", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "r_pitch": { + "__class__": "LogTocElement", + "ident": 213, + "group": "ctrlINDI", + "name": "r_pitch", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "r_yaw": { + "__class__": "LogTocElement", + "ident": 214, + "group": "ctrlINDI", + "name": "r_yaw", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "accelz": { + "__class__": "LogTocElement", + "ident": 215, + "group": "ctrlINDI", + "name": "accelz", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "u_act_dyn.p": { + "__class__": "LogTocElement", + "ident": 216, + "group": "ctrlINDI", + "name": "u_act_dyn.p", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "u_act_dyn.q": { + "__class__": "LogTocElement", + "ident": 217, + "group": "ctrlINDI", + "name": "u_act_dyn.q", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "u_act_dyn.r": { + "__class__": "LogTocElement", + "ident": 218, + "group": "ctrlINDI", + "name": "u_act_dyn.r", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "du.p": { + "__class__": "LogTocElement", + "ident": 219, + "group": "ctrlINDI", + "name": "du.p", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "du.q": { + "__class__": "LogTocElement", + "ident": 220, + "group": "ctrlINDI", + "name": "du.q", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "du.r": { + "__class__": "LogTocElement", + "ident": 221, + "group": "ctrlINDI", + "name": "du.r", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ang_accel_ref.p": { + "__class__": "LogTocElement", + "ident": 222, + "group": "ctrlINDI", + "name": "ang_accel_ref.p", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ang_accel_ref.q": { + "__class__": "LogTocElement", + "ident": 223, + "group": "ctrlINDI", + "name": "ang_accel_ref.q", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "ang_accel_ref.r": { + "__class__": "LogTocElement", + "ident": 224, + "group": "ctrlINDI", + "name": "ang_accel_ref.r", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rate_d[0]": { + "__class__": "LogTocElement", + "ident": 225, + "group": "ctrlINDI", + "name": "rate_d[0]", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rate_d[1]": { + "__class__": "LogTocElement", + "ident": 226, + "group": "ctrlINDI", + "name": "rate_d[1]", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rate_d[2]": { + "__class__": "LogTocElement", + "ident": 227, + "group": "ctrlINDI", + "name": "rate_d[2]", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "motor": { + "m1": { + "__class__": "LogTocElement", + "ident": 228, + "group": "motor", + "name": "m1", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "m2": { + "__class__": "LogTocElement", + "ident": 229, + "group": "motor", + "name": "m2", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "m3": { + "__class__": "LogTocElement", + "ident": 230, + "group": "motor", + "name": "m3", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "m4": { + "__class__": "LogTocElement", + "ident": 231, + "group": "motor", + "name": "m4", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + } + }, + "kalman": { + "inFlight": { + "__class__": "LogTocElement", + "ident": 232, + "group": "kalman", + "name": "inFlight", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "stateX": { + "__class__": "LogTocElement", + "ident": 233, + "group": "kalman", + "name": "stateX", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "stateY": { + "__class__": "LogTocElement", + "ident": 234, + "group": "kalman", + "name": "stateY", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "stateZ": { + "__class__": "LogTocElement", + "ident": 235, + "group": "kalman", + "name": "stateZ", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "statePX": { + "__class__": "LogTocElement", + "ident": 236, + "group": "kalman", + "name": "statePX", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "statePY": { + "__class__": "LogTocElement", + "ident": 237, + "group": "kalman", + "name": "statePY", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "statePZ": { + "__class__": "LogTocElement", + "ident": 238, + "group": "kalman", + "name": "statePZ", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "stateD0": { + "__class__": "LogTocElement", + "ident": 239, + "group": "kalman", + "name": "stateD0", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "stateD1": { + "__class__": "LogTocElement", + "ident": 240, + "group": "kalman", + "name": "stateD1", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "stateD2": { + "__class__": "LogTocElement", + "ident": 241, + "group": "kalman", + "name": "stateD2", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "varX": { + "__class__": "LogTocElement", + "ident": 242, + "group": "kalman", + "name": "varX", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "varY": { + "__class__": "LogTocElement", + "ident": 243, + "group": "kalman", + "name": "varY", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "varZ": { + "__class__": "LogTocElement", + "ident": 244, + "group": "kalman", + "name": "varZ", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "varPX": { + "__class__": "LogTocElement", + "ident": 245, + "group": "kalman", + "name": "varPX", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "varPY": { + "__class__": "LogTocElement", + "ident": 246, + "group": "kalman", + "name": "varPY", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "varPZ": { + "__class__": "LogTocElement", + "ident": 247, + "group": "kalman", + "name": "varPZ", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "varD0": { + "__class__": "LogTocElement", + "ident": 248, + "group": "kalman", + "name": "varD0", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "varD1": { + "__class__": "LogTocElement", + "ident": 249, + "group": "kalman", + "name": "varD1", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "varD2": { + "__class__": "LogTocElement", + "ident": 250, + "group": "kalman", + "name": "varD2", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "q0": { + "__class__": "LogTocElement", + "ident": 251, + "group": "kalman", + "name": "q0", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "q1": { + "__class__": "LogTocElement", + "ident": 252, + "group": "kalman", + "name": "q1", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "q2": { + "__class__": "LogTocElement", + "ident": 253, + "group": "kalman", + "name": "q2", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "q3": { + "__class__": "LogTocElement", + "ident": 254, + "group": "kalman", + "name": "q3", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rtUpdate": { + "__class__": "LogTocElement", + "ident": 255, + "group": "kalman", + "name": "rtUpdate", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rtPred": { + "__class__": "LogTocElement", + "ident": 256, + "group": "kalman", + "name": "rtPred", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rtBaro": { + "__class__": "LogTocElement", + "ident": 257, + "group": "kalman", + "name": "rtBaro", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rtFinal": { + "__class__": "LogTocElement", + "ident": 258, + "group": "kalman", + "name": "rtFinal", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rtApnd": { + "__class__": "LogTocElement", + "ident": 259, + "group": "kalman", + "name": "rtApnd", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "rtRej": { + "__class__": "LogTocElement", + "ident": 260, + "group": "kalman", + "name": "rtRej", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "kalman_states": { + "ox": { + "__class__": "LogTocElement", + "ident": 261, + "group": "kalman_states", + "name": "ox", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "oy": { + "__class__": "LogTocElement", + "ident": 262, + "group": "kalman_states", + "name": "oy", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vx": { + "__class__": "LogTocElement", + "ident": 263, + "group": "kalman_states", + "name": "vx", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "vy": { + "__class__": "LogTocElement", + "ident": 264, + "group": "kalman_states", + "name": "vy", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "kalman_pred": { + "predNX": { + "__class__": "LogTocElement", + "ident": 265, + "group": "kalman_pred", + "name": "predNX", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "predNY": { + "__class__": "LogTocElement", + "ident": 266, + "group": "kalman_pred", + "name": "predNY", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "measNX": { + "__class__": "LogTocElement", + "ident": 267, + "group": "kalman_pred", + "name": "measNX", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "measNY": { + "__class__": "LogTocElement", + "ident": 268, + "group": "kalman_pred", + "name": "measNY", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "outlierf": { + "lhWin": { + "__class__": "LogTocElement", + "ident": 269, + "group": "outlierf", + "name": "lhWin", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "bucket0": { + "__class__": "LogTocElement", + "ident": 345, + "group": "outlierf", + "name": "bucket0", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "bucket1": { + "__class__": "LogTocElement", + "ident": 346, + "group": "outlierf", + "name": "bucket1", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "bucket2": { + "__class__": "LogTocElement", + "ident": 347, + "group": "outlierf", + "name": "bucket2", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "bucket3": { + "__class__": "LogTocElement", + "ident": 348, + "group": "outlierf", + "name": "bucket3", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "bucket4": { + "__class__": "LogTocElement", + "ident": 349, + "group": "outlierf", + "name": "bucket4", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "accLev": { + "__class__": "LogTocElement", + "ident": 350, + "group": "outlierf", + "name": "accLev", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "errD": { + "__class__": "LogTocElement", + "ident": 351, + "group": "outlierf", + "name": "errD", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "ring": { + "fadeTime": { + "__class__": "LogTocElement", + "ident": 270, + "group": "ring", + "name": "fadeTime", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "gps": { + "lat": { + "__class__": "LogTocElement", + "ident": 271, + "group": "gps", + "name": "lat", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "lon": { + "__class__": "LogTocElement", + "ident": 272, + "group": "gps", + "name": "lon", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "hMSL": { + "__class__": "LogTocElement", + "ident": 273, + "group": "gps", + "name": "hMSL", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "hAcc": { + "__class__": "LogTocElement", + "ident": 274, + "group": "gps", + "name": "hAcc", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "nsat": { + "__class__": "LogTocElement", + "ident": 275, + "group": "gps", + "name": "nsat", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + }, + "fix": { + "__class__": "LogTocElement", + "ident": 276, + "group": "gps", + "name": "fix", + "ctype": "int32_t", + "pytype": "<i", + "access": 0 + } + }, + "loco": { + "mode": { + "__class__": "LogTocElement", + "ident": 277, + "group": "loco", + "name": "mode", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "ranging": { + "state": { + "__class__": "LogTocElement", + "ident": 278, + "group": "ranging", + "name": "state", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "distance0": { + "__class__": "LogTocElement", + "ident": 279, + "group": "ranging", + "name": "distance0", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "distance1": { + "__class__": "LogTocElement", + "ident": 280, + "group": "ranging", + "name": "distance1", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "distance2": { + "__class__": "LogTocElement", + "ident": 281, + "group": "ranging", + "name": "distance2", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "distance3": { + "__class__": "LogTocElement", + "ident": 282, + "group": "ranging", + "name": "distance3", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "distance4": { + "__class__": "LogTocElement", + "ident": 283, + "group": "ranging", + "name": "distance4", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "distance5": { + "__class__": "LogTocElement", + "ident": 284, + "group": "ranging", + "name": "distance5", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "distance6": { + "__class__": "LogTocElement", + "ident": 285, + "group": "ranging", + "name": "distance6", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "distance7": { + "__class__": "LogTocElement", + "ident": 286, + "group": "ranging", + "name": "distance7", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pressure0": { + "__class__": "LogTocElement", + "ident": 287, + "group": "ranging", + "name": "pressure0", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pressure1": { + "__class__": "LogTocElement", + "ident": 288, + "group": "ranging", + "name": "pressure1", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pressure2": { + "__class__": "LogTocElement", + "ident": 289, + "group": "ranging", + "name": "pressure2", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pressure3": { + "__class__": "LogTocElement", + "ident": 290, + "group": "ranging", + "name": "pressure3", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pressure4": { + "__class__": "LogTocElement", + "ident": 291, + "group": "ranging", + "name": "pressure4", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pressure5": { + "__class__": "LogTocElement", + "ident": 292, + "group": "ranging", + "name": "pressure5", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pressure6": { + "__class__": "LogTocElement", + "ident": 293, + "group": "ranging", + "name": "pressure6", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "pressure7": { + "__class__": "LogTocElement", + "ident": 294, + "group": "ranging", + "name": "pressure7", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "twr": { + "rangingSuccessRate0": { + "__class__": "LogTocElement", + "ident": 295, + "group": "twr", + "name": "rangingSuccessRate0", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "rangingPerSec0": { + "__class__": "LogTocElement", + "ident": 296, + "group": "twr", + "name": "rangingPerSec0", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "rangingSuccessRate1": { + "__class__": "LogTocElement", + "ident": 297, + "group": "twr", + "name": "rangingSuccessRate1", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "rangingPerSec1": { + "__class__": "LogTocElement", + "ident": 298, + "group": "twr", + "name": "rangingPerSec1", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "rangingSuccessRate2": { + "__class__": "LogTocElement", + "ident": 299, + "group": "twr", + "name": "rangingSuccessRate2", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "rangingPerSec2": { + "__class__": "LogTocElement", + "ident": 300, + "group": "twr", + "name": "rangingPerSec2", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "rangingSuccessRate3": { + "__class__": "LogTocElement", + "ident": 301, + "group": "twr", + "name": "rangingSuccessRate3", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "rangingPerSec3": { + "__class__": "LogTocElement", + "ident": 302, + "group": "twr", + "name": "rangingPerSec3", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "rangingSuccessRate4": { + "__class__": "LogTocElement", + "ident": 303, + "group": "twr", + "name": "rangingSuccessRate4", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "rangingPerSec4": { + "__class__": "LogTocElement", + "ident": 304, + "group": "twr", + "name": "rangingPerSec4", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "rangingSuccessRate5": { + "__class__": "LogTocElement", + "ident": 305, + "group": "twr", + "name": "rangingSuccessRate5", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "rangingPerSec5": { + "__class__": "LogTocElement", + "ident": 306, + "group": "twr", + "name": "rangingPerSec5", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "tdoa": { + "d7-0": { + "__class__": "LogTocElement", + "ident": 307, + "group": "tdoa", + "name": "d7-0", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "d0-1": { + "__class__": "LogTocElement", + "ident": 308, + "group": "tdoa", + "name": "d0-1", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "d1-2": { + "__class__": "LogTocElement", + "ident": 309, + "group": "tdoa", + "name": "d1-2", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "d2-3": { + "__class__": "LogTocElement", + "ident": 310, + "group": "tdoa", + "name": "d2-3", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "d3-4": { + "__class__": "LogTocElement", + "ident": 311, + "group": "tdoa", + "name": "d3-4", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "d4-5": { + "__class__": "LogTocElement", + "ident": 312, + "group": "tdoa", + "name": "d4-5", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "d5-6": { + "__class__": "LogTocElement", + "ident": 313, + "group": "tdoa", + "name": "d5-6", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "d6-7": { + "__class__": "LogTocElement", + "ident": 314, + "group": "tdoa", + "name": "d6-7", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cc0": { + "__class__": "LogTocElement", + "ident": 315, + "group": "tdoa", + "name": "cc0", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cc1": { + "__class__": "LogTocElement", + "ident": 316, + "group": "tdoa", + "name": "cc1", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cc2": { + "__class__": "LogTocElement", + "ident": 317, + "group": "tdoa", + "name": "cc2", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cc3": { + "__class__": "LogTocElement", + "ident": 318, + "group": "tdoa", + "name": "cc3", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cc4": { + "__class__": "LogTocElement", + "ident": 319, + "group": "tdoa", + "name": "cc4", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cc5": { + "__class__": "LogTocElement", + "ident": 320, + "group": "tdoa", + "name": "cc5", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cc6": { + "__class__": "LogTocElement", + "ident": 321, + "group": "tdoa", + "name": "cc6", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cc7": { + "__class__": "LogTocElement", + "ident": 322, + "group": "tdoa", + "name": "cc7", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "dist7-0": { + "__class__": "LogTocElement", + "ident": 323, + "group": "tdoa", + "name": "dist7-0", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "dist0-1": { + "__class__": "LogTocElement", + "ident": 324, + "group": "tdoa", + "name": "dist0-1", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "dist1-2": { + "__class__": "LogTocElement", + "ident": 325, + "group": "tdoa", + "name": "dist1-2", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "dist2-3": { + "__class__": "LogTocElement", + "ident": 326, + "group": "tdoa", + "name": "dist2-3", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "dist3-4": { + "__class__": "LogTocElement", + "ident": 327, + "group": "tdoa", + "name": "dist3-4", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "dist4-5": { + "__class__": "LogTocElement", + "ident": 328, + "group": "tdoa", + "name": "dist4-5", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "dist5-6": { + "__class__": "LogTocElement", + "ident": 329, + "group": "tdoa", + "name": "dist5-6", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "dist6-7": { + "__class__": "LogTocElement", + "ident": 330, + "group": "tdoa", + "name": "dist6-7", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "stRx": { + "__class__": "LogTocElement", + "ident": 331, + "group": "tdoa", + "name": "stRx", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "stSeq": { + "__class__": "LogTocElement", + "ident": 332, + "group": "tdoa", + "name": "stSeq", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "stData": { + "__class__": "LogTocElement", + "ident": 333, + "group": "tdoa", + "name": "stData", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "stEst": { + "__class__": "LogTocElement", + "ident": 334, + "group": "tdoa", + "name": "stEst", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + } + }, + "tdoa3": { + "stRx": { + "__class__": "LogTocElement", + "ident": 335, + "group": "tdoa3", + "name": "stRx", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "stEst": { + "__class__": "LogTocElement", + "ident": 336, + "group": "tdoa3", + "name": "stEst", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "stTime": { + "__class__": "LogTocElement", + "ident": 337, + "group": "tdoa3", + "name": "stTime", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "stFound": { + "__class__": "LogTocElement", + "ident": 338, + "group": "tdoa3", + "name": "stFound", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "stCc": { + "__class__": "LogTocElement", + "ident": 339, + "group": "tdoa3", + "name": "stCc", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "stHit": { + "__class__": "LogTocElement", + "ident": 340, + "group": "tdoa3", + "name": "stHit", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "stMiss": { + "__class__": "LogTocElement", + "ident": 341, + "group": "tdoa3", + "name": "stMiss", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "cc": { + "__class__": "LogTocElement", + "ident": 342, + "group": "tdoa3", + "name": "cc", + "ctype": "float", + "pytype": "<f", + "access": 0 + }, + "tof": { + "__class__": "LogTocElement", + "ident": 343, + "group": "tdoa3", + "name": "tof", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "tdoa": { + "__class__": "LogTocElement", + "ident": 344, + "group": "tdoa3", + "name": "tdoa", + "ctype": "float", + "pytype": "<f", + "access": 0 + } + }, + "motion": { + "motion": { + "__class__": "LogTocElement", + "ident": 352, + "group": "motion", + "name": "motion", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "deltaX": { + "__class__": "LogTocElement", + "ident": 353, + "group": "motion", + "name": "deltaX", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "deltaY": { + "__class__": "LogTocElement", + "ident": 354, + "group": "motion", + "name": "deltaY", + "ctype": "int16_t", + "pytype": "<h", + "access": 0 + }, + "shutter": { + "__class__": "LogTocElement", + "ident": 355, + "group": "motion", + "name": "shutter", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "maxRaw": { + "__class__": "LogTocElement", + "ident": 356, + "group": "motion", + "name": "maxRaw", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "minRaw": { + "__class__": "LogTocElement", + "ident": 357, + "group": "motion", + "name": "minRaw", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "Rawsum": { + "__class__": "LogTocElement", + "ident": 358, + "group": "motion", + "name": "Rawsum", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "outlierCount": { + "__class__": "LogTocElement", + "ident": 359, + "group": "motion", + "name": "outlierCount", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + }, + "oa": { + "front": { + "__class__": "LogTocElement", + "ident": 360, + "group": "oa", + "name": "front", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "back": { + "__class__": "LogTocElement", + "ident": 361, + "group": "oa", + "name": "back", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "up": { + "__class__": "LogTocElement", + "ident": 362, + "group": "oa", + "name": "up", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "left": { + "__class__": "LogTocElement", + "ident": 363, + "group": "oa", + "name": "left", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + }, + "right": { + "__class__": "LogTocElement", + "ident": 364, + "group": "oa", + "name": "right", + "ctype": "uint16_t", + "pytype": "<H", + "access": 0 + } + }, + "activeMarker": { + "btSns": { + "__class__": "LogTocElement", + "ident": 365, + "group": "activeMarker", + "name": "btSns", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + }, + "i2cOk": { + "__class__": "LogTocElement", + "ident": 366, + "group": "activeMarker", + "name": "i2cOk", + "ctype": "uint8_t", + "pytype": "<B", + "access": 0 + } + } +} \ No newline at end of file diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/cfbridge.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/cfbridge.py new file mode 100755 index 00000000..1d7677e6 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/cfbridge.py @@ -0,0 +1,147 @@ +#!/usr/bin/env python +""" +Bridge a Crazyflie connected to a Crazyradio to a local MAVLink port +Requires 'pip install cflib' + +As the ESB protocol works using PTX and PRX (Primary Transmitter/Reciever) +modes. Thus, data is only recieved as a response to a sent packet. +So, we need to constantly poll the receivers for bidirectional communication. + +@author: Dennis Shtatnov (densht@gmail.com) + +Based off example code from crazyflie-lib-python/examples/read-eeprom.py +""" +# import struct +import logging +import socket +import sys +import threading +import time + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crtp.crtpstack import CRTPPacket +# from cflib.crtp.crtpstack import CRTPPort + +CRTP_PORT_MAVLINK = 8 + + +# Only output errors from the logging framework +logging.basicConfig(level=logging.DEBUG) + + +class RadioBridge: + def __init__(self, link_uri): + """ Initialize and run the example with the specified link_uri """ + + # UDP socket for interfacing with GCS + self._sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) + self._sock.bind(('127.0.0.1', 14551)) + + # Create a Crazyflie object without specifying any cache dirs + self._cf = Crazyflie() + + # Connect some callbacks from the Crazyflie API + self._cf.connected.add_callback(self._connected) + self._cf.disconnected.add_callback(self._disconnected) + self._cf.connection_failed.add_callback(self._connection_failed) + self._cf.connection_lost.add_callback(self._connection_lost) + + print('Connecting to %s' % link_uri) + + # Try to connect to the Crazyflie + self._cf.open_link(link_uri) + + # Variable used to keep main loop occupied until disconnect + self.is_connected = True + + threading.Thread(target=self._server).start() + + def _connected(self, link_uri): + """ This callback is called form the Crazyflie API when a Crazyflie + has been connected and the TOCs have been downloaded.""" + print('Connected to %s' % link_uri) + + self._cf.packet_received.add_callback(self._got_packet) + + def _got_packet(self, pk): + if pk.port == CRTP_PORT_MAVLINK: + self._sock.sendto(pk.data, ('127.0.0.1', 14550)) + + def _forward(self, data): + pk = CRTPPacket() + pk.port = CRTP_PORT_MAVLINK # CRTPPort.COMMANDER + pk.data = data # struct.pack('<fffH', roll, -pitch, yaw, thrust) + self._cf.send_packet(pk) + + def _server(self): + while True: + print('\nwaiting to receive message') + + # Only receive what can be sent in one message + data, address = self._sock.recvfrom(256) + + print('received %s bytes from %s' % (len(data), address)) + + for i in range(0, len(data), 30): + self._forward(data[i:(i+30)]) + + def _stab_log_error(self, logconf, msg): + """Callback from the log API when an error occurs""" + print('Error when logging %s: %s' % (logconf.name, msg)) + + def _stab_log_data(self, timestamp, data, logconf): + """Callback froma the log API when data arrives""" + print('[%d][%s]: %s' % (timestamp, logconf.name, data)) + + def _connection_failed(self, link_uri, msg): + """Callback when connection initial connection fails (i.e no Crazyflie + at the speficied address)""" + print('Connection to %s failed: %s' % (link_uri, msg)) + self.is_connected = False + + def _connection_lost(self, link_uri, msg): + """Callback when disconnected after a connection has been made (i.e + Crazyflie moves out of range)""" + print('Connection to %s lost: %s' % (link_uri, msg)) + + def _disconnected(self, link_uri): + """Callback when the Crazyflie is disconnected (called in all cases)""" + print('Disconnected from %s' % link_uri) + self.is_connected = False + + +if __name__ == '__main__': + # Initialize the low-level drivers (don't list the debug drivers) + cflib.crtp.radiodriver.set_retries_before_disconnect(1500) + cflib.crtp.radiodriver.set_retries(3) + cflib.crtp.init_drivers(enable_debug_driver=False) + # Scan for Crazyflies and use the first one found + print('Scanning interfaces for Crazyflies...') + if len(sys.argv) > 2: + address = int(sys.argv[2], 16) # address=0xE7E7E7E7E7 + else: + address = None + + available = cflib.crtp.scan_interfaces(address) + print('Crazyflies found:') + for i in available: + print(i[0]) + + if len(available) > 0: + if len(sys.argv) > 1: + channel = str(sys.argv[1]) + else: + channel = 80 + + link_uri = 'radio://0/' + str(channel) + '/2M' + le = RadioBridge(link_uri) # (available[0][0]) + + # The Crazyflie lib doesn't contain anything to keep the application alive, + # so this is where your application should do something. In our case we + # are just waiting until we are disconnected. + try: + while le.is_connected: + time.sleep(1) + except KeyboardInterrupt: + sys.exit(1) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/flowsequenceSync.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/flowsequenceSync.py index f77a141b..fb88be85 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/flowsequenceSync.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/flowsequenceSync.py @@ -34,9 +34,10 @@ import logging import time import cflib.crtp +from cflib.crazyflie import Crazyflie from cflib.crazyflie.syncCrazyflie import SyncCrazyflie -URI = 'radio://0/80/250k' +URI = 'radio://0/80/250K' # Only output errors from the logging framework logging.basicConfig(level=logging.ERROR) @@ -46,7 +47,7 @@ if __name__ == '__main__': # Initialize the low-level drivers (don't list the debug drivers) cflib.crtp.init_drivers(enable_debug_driver=False) - with SyncCrazyflie(URI) as scf: + with SyncCrazyflie(URI, cf=Crazyflie(rw_cache='./cache')) as scf: cf = scf.cf cf.param.set_value('kalman.resetEstimation', '1') diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_grab.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_grab.py new file mode 100644 index 00000000..bbba813c --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_grab.py @@ -0,0 +1,176 @@ +#!/usr/bin/env python3 +# Demo that makes one Crazyflie take off 30cm above the first controller found +# Using the controller trigger it is then possible to 'grab' the Crazyflie +# and to make it move. +import sys +import time + +import openvr + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from cflib.crazyflie.syncLogger import SyncLogger + +# URI to the Crazyflie to connect to +uri = 'radio://0/80/2M' + +print('Opening') +vr = openvr.init(openvr.VRApplication_Other) +print('Opened') + +# Find first controller or tracker +controllerId = None +poses = vr.getDeviceToAbsoluteTrackingPose(openvr.TrackingUniverseStanding, 0, + openvr.k_unMaxTrackedDeviceCount) +for i in range(openvr.k_unMaxTrackedDeviceCount): + if poses[i].bPoseIsValid: + device_class = vr.getTrackedDeviceClass(i) + if device_class == openvr.TrackedDeviceClass_Controller or \ + device_class == openvr.TrackedDeviceClass_GenericTracker: + controllerId = i + break + +if controllerId is None: + print('Cannot find controller or tracker, exiting') + sys.exit(1) + + +def wait_for_position_estimator(scf): + print('Waiting for estimator to find position...') + + log_config = LogConfig(name='Kalman Variance', period_in_ms=500) + log_config.add_variable('kalman.varPX', 'float') + log_config.add_variable('kalman.varPY', 'float') + log_config.add_variable('kalman.varPZ', 'float') + + var_y_history = [1000] * 10 + var_x_history = [1000] * 10 + var_z_history = [1000] * 10 + + threshold = 0.001 + + with SyncLogger(scf, log_config) as logger: + for log_entry in logger: + data = log_entry[1] + + var_x_history.append(data['kalman.varPX']) + var_x_history.pop(0) + var_y_history.append(data['kalman.varPY']) + var_y_history.pop(0) + var_z_history.append(data['kalman.varPZ']) + var_z_history.pop(0) + + min_x = min(var_x_history) + max_x = max(var_x_history) + min_y = min(var_y_history) + max_y = max(var_y_history) + min_z = min(var_z_history) + max_z = max(var_z_history) + + # print("{} {} {}". + # format(max_x - min_x, max_y - min_y, max_z - min_z)) + + if (max_x - min_x) < threshold and ( + max_y - min_y) < threshold and ( + max_z - min_z) < threshold: + break + + +def reset_estimator(scf): + cf = scf.cf + cf.param.set_value('kalman.resetEstimation', '1') + time.sleep(0.1) + cf.param.set_value('kalman.resetEstimation', '0') + + wait_for_position_estimator(cf) + + +def position_callback(timestamp, data, logconf): + x = data['kalman.stateX'] + y = data['kalman.stateY'] + z = data['kalman.stateZ'] + print('pos: ({}, {}, {})'.format(x, y, z)) + + +def start_position_printing(scf): + log_conf = LogConfig(name='Position', period_in_ms=500) + log_conf.add_variable('kalman.stateX', 'float') + log_conf.add_variable('kalman.stateY', 'float') + log_conf.add_variable('kalman.stateZ', 'float') + + scf.cf.log.add_config(log_conf) + log_conf.data_received_cb.add_callback(position_callback) + log_conf.start() + + +def vector_substract(v0, v1): + return [v0[0] - v1[0], v0[1] - v1[1], v0[2] - v1[2]] + + +def vector_add(v0, v1): + return [v0[0] + v1[0], v0[1] + v1[1], v0[2] + v1[2]] + + +def run_sequence(scf): + cf = scf.cf + + poses = vr.getDeviceToAbsoluteTrackingPose( + openvr.TrackingUniverseStanding, 0, openvr.k_unMaxTrackedDeviceCount) + controller_pose = poses[controllerId] + pose = controller_pose.mDeviceToAbsoluteTracking + setpoint = [-1*pose[2][3], -1*pose[0][3], pose[1][3] + 0.3] + + grabbed = False + grab_controller_start = [0, 0, 0] + grab_setpoint_start = [0, 0, 0] + + while True: + poses = vr.getDeviceToAbsoluteTrackingPose( + openvr.TrackingUniverseStanding, 0, + openvr.k_unMaxTrackedDeviceCount) + controller_state = vr.getControllerState(controllerId)[1] + + trigger = ((controller_state.ulButtonPressed & 0x200000000) != 0) + + controller_pose = poses[controllerId] + pose = controller_pose.mDeviceToAbsoluteTracking + + if not grabbed and trigger: + print('Grab started') + grab_controller_start = [-1*pose[2][3], -1*pose[0][3], pose[1][3]] + grab_setpoint_start = setpoint + + if grabbed and not trigger: + print('Grab ended') + + grabbed = trigger + + if trigger: + curr = [-1*pose[2][3], -1*pose[0][3], pose[1][3]] + setpoint = vector_add(grab_setpoint_start, + vector_substract(curr, + grab_controller_start)) + + cf.commander.send_position_setpoint(setpoint[0], + setpoint[1], + setpoint[2], + 0) + time.sleep(0.02) + + cf.commander.send_setpoint + (0, 0, 0, 0) + # Make sure that the last packet leaves before the link is closed + # since the message queue is not flushed before closing + time.sleep(0.1) + + +if __name__ == '__main__': + cflib.crtp.init_drivers(enable_debug_driver=False) + + with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf: + reset_estimator(scf) + run_sequence(scf) + + openvr.shutdown() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_grab_color.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_grab_color.py new file mode 100644 index 00000000..9c5a4bfd --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_grab_color.py @@ -0,0 +1,208 @@ +#!/usr/bin/env python3 +# Demo that makes one Crazyflie take off 30cm above the first controller found +# Using the controller trigger it is then possible to 'grab' the Crazyflie +# and to make it move. +# If the Crazyflie has a ledring attached, the touchpad of the controller can +# be used to change the color of the led-ring LEDs +import colorsys +import math +import sys +import time + +import openvr + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from cflib.crazyflie.syncLogger import SyncLogger + +# URI to the Crazyflie to connect to +uri = 'radio://0/80/2M' + +print('Openning') +vr = openvr.init(openvr.VRApplication_Other) +print('Oppened') + +# Find first controller or tracker +controllerId = None +poses = vr.getDeviceToAbsoluteTrackingPose(openvr.TrackingUniverseStanding, 0, + openvr.k_unMaxTrackedDeviceCount) +for i in range(openvr.k_unMaxTrackedDeviceCount): + if poses[i].bPoseIsValid: + device_class = vr.getTrackedDeviceClass(i) + if device_class == openvr.TrackedDeviceClass_Controller or\ + device_class == openvr.TrackedDeviceClass_GenericTracker: + controllerId = i + break + +if controllerId is None: + print('Cannot find controller or tracker, exiting') + sys.exit(1) + + +def wait_for_position_estimator(scf): + print('Waiting for estimator to find position...') + + log_config = LogConfig(name='Kalman Variance', period_in_ms=500) + log_config.add_variable('kalman.varPX', 'float') + log_config.add_variable('kalman.varPY', 'float') + log_config.add_variable('kalman.varPZ', 'float') + + var_y_history = [1000] * 10 + var_x_history = [1000] * 10 + var_z_history = [1000] * 10 + + threshold = 0.001 + + with SyncLogger(scf, log_config) as logger: + for log_entry in logger: + data = log_entry[1] + + var_x_history.append(data['kalman.varPX']) + var_x_history.pop(0) + var_y_history.append(data['kalman.varPY']) + var_y_history.pop(0) + var_z_history.append(data['kalman.varPZ']) + var_z_history.pop(0) + + min_x = min(var_x_history) + max_x = max(var_x_history) + min_y = min(var_y_history) + max_y = max(var_y_history) + min_z = min(var_z_history) + max_z = max(var_z_history) + + # print('{} {} {}'. + # format(max_x - min_x, max_y - min_y, max_z - min_z)) + + if (max_x - min_x) < threshold and ( + max_y - min_y) < threshold and ( + max_z - min_z) < threshold: + break + + +def reset_estimator(scf): + cf = scf.cf + cf.param.set_value('kalman.resetEstimation', '1') + time.sleep(0.1) + cf.param.set_value('kalman.resetEstimation', '0') + + wait_for_position_estimator(cf) + + +def position_callback(timestamp, data, logconf): + x = data['kalman.stateX'] + y = data['kalman.stateY'] + z = data['kalman.stateZ'] + print('pos: ({}, {}, {})'.format(x, y, z)) + + +def start_position_printing(scf): + log_conf = LogConfig(name='Position', period_in_ms=500) + log_conf.add_variable('kalman.stateX', 'float') + log_conf.add_variable('kalman.stateY', 'float') + log_conf.add_variable('kalman.stateZ', 'float') + + scf.cf.log.add_config(log_conf) + log_conf.data_received_cb.add_callback(position_callback) + log_conf.start() + + +def vector_substract(v0, v1): + return [v0[0] - v1[0], v0[1] - v1[1], v0[2] - v1[2]] + + +def vector_add(v0, v1): + return [v0[0] + v1[0], v0[1] + v1[1], v0[2] + v1[2]] + + +def run_sequence(scf): + cf = scf.cf + + cf.param.set_value('ring.effect', '7') + + poses = vr.getDeviceToAbsoluteTrackingPose( + openvr.TrackingUniverseStanding, 0, openvr.k_unMaxTrackedDeviceCount) + + controller_pose = poses[controllerId] + pose = controller_pose.mDeviceToAbsoluteTracking + # setpoint = [-1*pose[2][3], -1*pose[0][3], pose[1][3] + 0.3] + setpoint = [0, 0, 0.5] + + grabbed = False + grab_controller_start = [0, 0, 0] + grab_setpoint_start = [0, 0, 0] + + while True: + poses = vr.getDeviceToAbsoluteTrackingPose( + openvr.TrackingUniverseStanding, 0, + openvr.k_unMaxTrackedDeviceCount) + controller_state = vr.getControllerState(controllerId)[1] + + trigger = ((controller_state.ulButtonPressed & 0x200000000) != 0) + trackpad_touched = ((controller_state.ulButtonTouched & 0x100000000) != 0) # noqa + + trackpad = (0, 0) + for i in range(openvr.k_unControllerStateAxisCount): + axis_type = vr.getInt32TrackedDeviceProperty( + controllerId, openvr.Prop_Axis0Type_Int32 + i)[0] + if axis_type == openvr.k_eControllerAxis_TrackPad: + trackpad = (controller_state.rAxis[i].x, + controller_state.rAxis[i].y) + + controller_pose = poses[controllerId] + pose = controller_pose.mDeviceToAbsoluteTracking + + if trackpad_touched: + angle = math.atan2(trackpad[1], trackpad[0]) + hue = (angle + math.pi) / (2*math.pi) + rgb = colorsys.hsv_to_rgb(hue, 1, 0.3) + + print(rgb) + + cf.param.set_value('ring.solidRed', + '{}'.format(int(rgb[0] * 255))) + cf.param.set_value('ring.solidGreen', + '{}'.format(int(rgb[1] * 255))) + cf.param.set_value('ring.solidBlue', + '{}'.format(int(rgb[2] * 255))) + + if not grabbed and trigger: + print('Grab started') + grab_controller_start = [-1*pose[2][3], -1*pose[0][3], pose[1][3]] + grab_setpoint_start = setpoint + + if grabbed and not trigger: + print('Grab ended') + + grabbed = trigger + + if trigger: + curr = [-1*pose[2][3], -1*pose[0][3], pose[1][3]] + setpoint = vector_add(grab_setpoint_start, + vector_substract(curr, grab_controller_start) + ) + + cf.commander.send_position_setpoint(setpoint[0], + setpoint[1], + setpoint[2], + 0) + time.sleep(0.02) + + cf.commander.send_setpoint + (0, 0, 0, 0) + # Make sure that the last packet leaves before the link is closed + # since the message queue is not flushed before closing + time.sleep(0.1) + + +if __name__ == '__main__': + cflib.crtp.init_drivers(enable_debug_driver=False) + + with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf: + reset_estimator(scf) + # start_position_printing(scf) + run_sequence(scf) + + openvr.shutdown() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_multigrab.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_multigrab.py new file mode 100644 index 00000000..8d30f053 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/lighthouse_openvr_multigrab.py @@ -0,0 +1,204 @@ +#!/usr/bin/env python3 +# Demo that makes two Crazyflie take off 30cm above the first controller found +# Using the controller trigger it is then possible to 'grab' the closest +# Crazyflie and to make it move. +import math +import sys +import time + +import openvr + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from cflib.crazyflie.syncLogger import SyncLogger + +# URI to the Crazyflie to connect to +uri0 = 'radio://0/80/2M' +uri1 = 'radio://0/80/2M/E7E7E7E701' + +print('Opening') +vr = openvr.init(openvr.VRApplication_Other) +print('Opened') + +# Find first controller or tracker +controllerId = None +poses = vr.getDeviceToAbsoluteTrackingPose(openvr.TrackingUniverseStanding, 0, + openvr.k_unMaxTrackedDeviceCount) +for i in range(openvr.k_unMaxTrackedDeviceCount): + if poses[i].bPoseIsValid: + device_class = vr.getTrackedDeviceClass(i) + if device_class == openvr.TrackedDeviceClass_Controller or \ + device_class == openvr.TrackedDeviceClass_GenericTracker: + controllerId = i + break + +if controllerId is None: + print('Cannot find controller or tracker, exiting') + sys.exit(1) + + +def wait_for_position_estimator(scf): + print('Waiting for estimator to find position...') + + log_config = LogConfig(name='Kalman Variance', period_in_ms=500) + log_config.add_variable('kalman.varPX', 'float') + log_config.add_variable('kalman.varPY', 'float') + log_config.add_variable('kalman.varPZ', 'float') + + var_y_history = [1000] * 10 + var_x_history = [1000] * 10 + var_z_history = [1000] * 10 + + threshold = 0.001 + + with SyncLogger(scf, log_config) as logger: + for log_entry in logger: + data = log_entry[1] + + var_x_history.append(data['kalman.varPX']) + var_x_history.pop(0) + var_y_history.append(data['kalman.varPY']) + var_y_history.pop(0) + var_z_history.append(data['kalman.varPZ']) + var_z_history.pop(0) + + min_x = min(var_x_history) + max_x = max(var_x_history) + min_y = min(var_y_history) + max_y = max(var_y_history) + min_z = min(var_z_history) + max_z = max(var_z_history) + + # print("{} {} {}". + # format(max_x - min_x, max_y - min_y, max_z - min_z)) + + if (max_x - min_x) < threshold and ( + max_y - min_y) < threshold and ( + max_z - min_z) < threshold: + break + + +def reset_estimator(scf): + cf = scf.cf + cf.param.set_value('kalman.resetEstimation', '1') + time.sleep(0.1) + cf.param.set_value('kalman.resetEstimation', '0') + + wait_for_position_estimator(cf) + + +def position_callback(timestamp, data, logconf): + x = data['kalman.stateX'] + y = data['kalman.stateY'] + z = data['kalman.stateZ'] + print('pos: ({}, {}, {})'.format(x, y, z)) + + +def start_position_printing(scf): + log_conf = LogConfig(name='Position', period_in_ms=500) + log_conf.add_variable('kalman.stateX', 'float') + log_conf.add_variable('kalman.stateY', 'float') + log_conf.add_variable('kalman.stateZ', 'float') + + scf.cf.log.add_config(log_conf) + log_conf.data_received_cb.add_callback(position_callback) + log_conf.start() + + +def vector_substract(v0, v1): + return [v0[0] - v1[0], v0[1] - v1[1], v0[2] - v1[2]] + + +def vector_add(v0, v1): + return [v0[0] + v1[0], v0[1] + v1[1], v0[2] + v1[2]] + + +def vector_norm(v0): + return math.sqrt((v0[0] * v0[0]) + (v0[1] * v0[1]) + (v0[2] * v0[2])) + + +def run_sequence(scf0, scf1): + cf0 = scf0.cf + cf1 = scf1.cf + + poses = vr.getDeviceToAbsoluteTrackingPose( + openvr.TrackingUniverseStanding, 0, openvr.k_unMaxTrackedDeviceCount) + controller_pose = poses[controllerId] + pose = controller_pose.mDeviceToAbsoluteTracking + setpoints = [[-1*pose[2][3], -1*pose[0][3] - 0.5, pose[1][3] + 0.3], + [-1*pose[2][3], -1*pose[0][3] + 0.5, pose[1][3] + 0.3]] + + closest = 0 + + grabbed = False + grab_controller_start = [0, 0, 0] + grab_setpoint_start = [0, 0, 0] + + while True: + poses = vr.getDeviceToAbsoluteTrackingPose( + openvr.TrackingUniverseStanding, 0, + openvr.k_unMaxTrackedDeviceCount) + controller_state = vr.getControllerState(controllerId)[1] + + trigger = ((controller_state.ulButtonPressed & 0x200000000) != 0) + + controller_pose = poses[controllerId] + pose = controller_pose.mDeviceToAbsoluteTracking + + if not grabbed and trigger: + print('Grab started') + grab_controller_start = [-1*pose[2][3], -1*pose[0][3], pose[1][3]] + + dist0 = vector_norm(vector_substract(grab_controller_start, + setpoints[0])) + dist1 = vector_norm(vector_substract(grab_controller_start, + setpoints[1])) + + if dist0 < dist1: + closest = 0 + else: + closest = 1 + + grab_setpoint_start = setpoints[closest] + + if grabbed and not trigger: + print('Grab ended') + + grabbed = trigger + + if trigger: + curr = [-1*pose[2][3], -1*pose[0][3], pose[1][3]] + setpoints[closest] = vector_add( + grab_setpoint_start, vector_substract(curr, + grab_controller_start)) + + cf0.commander.send_position_setpoint(setpoints[0][0], + setpoints[0][1], + setpoints[0][2], + 0) + cf1.commander.send_position_setpoint(setpoints[1][0], + setpoints[1][1], + setpoints[1][2], + 0) + + time.sleep(0.02) + + cf0.commander.send_setpoint(0, 0, 0, 0) + cf1.commander.send_setpoint(0, 0, 0, 0) + # Make sure that the last packet leaves before the link is closed + # since the message queue is not flushed before closing + time.sleep(0.1) + + +if __name__ == '__main__': + cflib.crtp.init_drivers(enable_debug_driver=False) + + with SyncCrazyflie(uri0, cf=Crazyflie(rw_cache='./cache')) as scf0: + reset_estimator(scf0) + with SyncCrazyflie(uri1, cf=Crazyflie(rw_cache='./cache')) as scf1: + reset_estimator(scf1) + run_sequence(scf0, scf1) + + openvr.shutdown() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/read-geometry-mem.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/read-geometry-mem.py new file mode 100644 index 00000000..d6cd5b12 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/read-geometry-mem.py @@ -0,0 +1,69 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# 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. +""" +Example of how to read the Lighthouse base station geometry memory from a +Crazyflie +""" +import logging +import time + +import cflib.crtp # noqa +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.mem import MemoryElement +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +# Only output errors from the logging framework + +logging.basicConfig(level=logging.ERROR) + + +class ReadMem: + def __init__(self, uri): + self.got_data = False + + with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf: + mems = scf.cf.mem.get_mems(MemoryElement.TYPE_LH) + + count = len(mems) + if count != 1: + raise Exception('Unexpected nr of memories found:', count) + + print('Rquesting data') + mems[0].update(self._data_updated) + + while not self.got_data: + time.sleep(1) + + def _data_updated(self, mem): + mem.dump() + self.got_data = True + + +if __name__ == '__main__': + # URI to the Crazyflie to connect to + uri = 'radio://0/80/2M' + + # Initialize the low-level drivers (don't list the debug drivers) + cflib.crtp.init_drivers(enable_debug_driver=False) + + ReadMem(uri) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/write-geometry-mem.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/write-geometry-mem.py new file mode 100644 index 00000000..65fd3161 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/lighthouse/write-geometry-mem.py @@ -0,0 +1,88 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# 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. +""" +Example of how to write to the Lighthouse base station geometry memory in a +Crazyflie +""" +import logging +import time + +import cflib.crtp # noqa +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.mem import LighthouseBsGeometry +from cflib.crazyflie.mem import MemoryElement +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +# Only output errors from the logging framework + +logging.basicConfig(level=logging.ERROR) + + +class WriteMem: + def __init__(self, uri, bs1, bs2): + self.data_written = False + + with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf: + mems = scf.cf.mem.get_mems(MemoryElement.TYPE_LH) + + count = len(mems) + if count != 1: + raise Exception('Unexpected nr of memories found:', count) + + mems[0].geometry_data = [bs1, bs2] + + print('Writing data') + mems[0].write_data(self._data_written) + + while not self.data_written: + time.sleep(1) + + def _data_written(self, mem, addr): + self.data_written = True + print('Data written') + + +if __name__ == '__main__': + # URI to the Crazyflie to connect to + uri = 'radio://0/80/2M' + + # Initialize the low-level drivers (don't list the debug drivers) + cflib.crtp.init_drivers(enable_debug_driver=False) + + bs1 = LighthouseBsGeometry() + bs1.origin = [1.0, 2.0, 3.0] + bs1.rotation_matrix = [ + [4.0, 5.0, 6.0], + [7.0, 8.0, 9.0], + [10.0, 11.0, 12.0], + ] + + bs2 = LighthouseBsGeometry() + bs2.origin = [21.0, 22.0, 23.0] + bs2.rotation_matrix = [ + [24.0, 25.0, 26.0], + [27.0, 28.0, 29.0], + [30.0, 31.0, 32.0], + ] + + WriteMem(uri, bs1, bs2) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/motion_commander_demo.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/motion_commander_demo.py new file mode 100644 index 00000000..6040d1ff --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/motion_commander_demo.py @@ -0,0 +1,100 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2017 Bitcraze AB +# +# Crazyflie Nano Quadcopter Client +# +# 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. +""" +This script shows the basic use of the MotionCommander class. + +Simple example that connects to the crazyflie at `URI` and runs a +sequence. This script requires some kind of location system, it has been +tested with (and designed for) the flow deck. + +The MotionCommander uses velocity setpoints. + +Change the URI variable to your Crazyflie configuration. +""" +import logging +import time + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from cflib.positioning.motion_commander import MotionCommander + +URI = 'radio://0/70/2M' + +# Only output errors from the logging framework +logging.basicConfig(level=logging.ERROR) + + +if __name__ == '__main__': + # Initialize the low-level drivers (don't list the debug drivers) + cflib.crtp.init_drivers(enable_debug_driver=False) + + with SyncCrazyflie(URI, cf=Crazyflie(rw_cache='./cache')) as scf: + # We take off when the commander is created + with MotionCommander(scf) as mc: + time.sleep(1) + + # There is a set of functions that move a specific distance + # We can move in all directions + mc.forward(0.8) + mc.back(0.8) + time.sleep(1) + + mc.up(0.5) + mc.down(0.5) + time.sleep(1) + + # We can also set the velocity + mc.right(0.5, velocity=0.8) + time.sleep(1) + mc.left(0.5, velocity=0.4) + time.sleep(1) + + # We can do circles or parts of circles + mc.circle_right(0.5, velocity=0.5, angle_degrees=180) + + # Or turn + mc.turn_left(90) + time.sleep(1) + + # We can move along a line in 3D space + mc.move_distance(-1, 0.0, 0.5, velocity=0.6) + time.sleep(1) + + # There is also a set of functions that start a motion. The + # Crazyflie will keep on going until it gets a new command. + + mc.start_left(velocity=0.5) + # The motion is started and we can do other stuff, printing for + # instance + for _ in range(5): + print('Doing other work') + time.sleep(0.2) + + # And we can stop + mc.stop() + + # We land when the MotionCommander goes out of scope diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/multiramp.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/multiramp.py index 326d2dc7..076820c5 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/multiramp.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/multiramp.py @@ -44,7 +44,7 @@ class MotorRampExample: def __init__(self, link_uri): """ Initialize and run the example with the specified link_uri """ - self._cf = Crazyflie() + self._cf = Crazyflie(rw_cache='./cache') self._cf.connected.add_callback(self._connected) self._cf.disconnected.add_callback(self._disconnected) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/multiranger_pointcloud.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/multiranger_pointcloud.py new file mode 100644 index 00000000..ddd0354e --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/multiranger_pointcloud.py @@ -0,0 +1,365 @@ +#!/usr/bin/env python2 +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2018 Bitcraze AB +# +# Crazyflie Python Library +# +# 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. +""" +Example script that plots the output ranges from the Multiranger and Flow +deck in a 3D plot. + +When the application is started the Crazyflie will hover at 0.3 m. The +Crazyflie can then be controlled by using keyboard input: + * Move by using the arrow keys (left/right/forward/backwards) + * Adjust the right with w/s (0.1 m for each keypress) + * Yaw slowly using a/d (CCW/CW) + * Yaw fast using z/x (CCW/CW) + +There's additional setting for (see constants below): + * Plotting the downwards sensor + * Plotting the estimated Crazyflie postition + * Max threashold for sensors + * Speed factor that set's how fast the Crazyflie moves + +The demo is ended by either closing the graph window. + +For the example to run the following hardware is needed: + * Crazyflie 2.0 + * Crazyradio PA + * Flow deck + * Multiranger deck +""" +import logging +import math +import sys + +import numpy as np +from vispy import scene +from vispy.scene import visuals +from vispy.scene.cameras import TurntableCamera + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.log import LogConfig + +try: + from sip import setapi + setapi('QVariant', 2) + setapi('QString', 2) +except ImportError: + pass + +from PyQt5 import QtCore, QtWidgets + +logging.basicConfig(level=logging.INFO) + +URI = 'radio://0/80/2M' + +if len(sys.argv) > 1: + URI = sys.argv[1] + +# Enable plotting of Crazyflie +PLOT_CF = False +# Enable plotting of down sensor +PLOT_SENSOR_DOWN = False +# Set the sensor threashold (in mm) +SENSOR_TH = 2000 +# Set the speed factor for moving and rotating +SPEED_FACTOR = 0.3 + + +class MainWindow(QtWidgets.QMainWindow): + + def __init__(self, URI): + QtWidgets.QMainWindow.__init__(self) + + self.resize(700, 500) + self.setWindowTitle('Multi-ranger point cloud') + + self.canvas = Canvas(self.updateHover) + self.canvas.create_native() + self.canvas.native.setParent(self) + + self.setCentralWidget(self.canvas.native) + + cflib.crtp.init_drivers(enable_debug_driver=False) + self.cf = Crazyflie(ro_cache=None, rw_cache='cache') + + # Connect callbacks from the Crazyflie API + self.cf.connected.add_callback(self.connected) + self.cf.disconnected.add_callback(self.disconnected) + + # Connect to the Crazyflie + self.cf.open_link(URI) + + self.hover = {'x': 0.0, 'y': 0.0, 'z': 0.0, 'yaw': 0.0, 'height': 0.3} + + self.hoverTimer = QtCore.QTimer() + self.hoverTimer.timeout.connect(self.sendHoverCommand) + self.hoverTimer.setInterval(100) + self.hoverTimer.start() + + def sendHoverCommand(self): + self.cf.commander.send_hover_setpoint( + self.hover['x'], self.hover['y'], self.hover['yaw'], + self.hover['height']) + + def updateHover(self, k, v): + if (k != 'height'): + self.hover[k] = v * SPEED_FACTOR + else: + self.hover[k] += v + + def disconnected(self, URI): + print('Disconnected') + + def connected(self, URI): + print('We are now connected to {}'.format(URI)) + + # The definition of the logconfig can be made before connecting + lpos = LogConfig(name='Position', period_in_ms=100) + lpos.add_variable('stateEstimate.x') + lpos.add_variable('stateEstimate.y') + lpos.add_variable('stateEstimate.z') + + try: + self.cf.log.add_config(lpos) + lpos.data_received_cb.add_callback(self.pos_data) + lpos.start() + except KeyError as e: + print('Could not start log configuration,' + '{} not found in TOC'.format(str(e))) + except AttributeError: + print('Could not add Position log config, bad configuration.') + + lmeas = LogConfig(name='Meas', period_in_ms=100) + lmeas.add_variable('range.front') + lmeas.add_variable('range.back') + lmeas.add_variable('range.up') + lmeas.add_variable('range.left') + lmeas.add_variable('range.right') + lmeas.add_variable('range.zrange') + lmeas.add_variable('stabilizer.roll') + lmeas.add_variable('stabilizer.pitch') + lmeas.add_variable('stabilizer.yaw') + + try: + self.cf.log.add_config(lmeas) + lmeas.data_received_cb.add_callback(self.meas_data) + lmeas.start() + except KeyError as e: + print('Could not start log configuration,' + '{} not found in TOC'.format(str(e))) + except AttributeError: + print('Could not add Measurement log config, bad configuration.') + + def pos_data(self, timestamp, data, logconf): + position = [ + data['stateEstimate.x'], + data['stateEstimate.y'], + data['stateEstimate.z'] + ] + self.canvas.set_position(position) + + def meas_data(self, timestamp, data, logconf): + measurement = { + 'roll': data['stabilizer.roll'], + 'pitch': data['stabilizer.pitch'], + 'yaw': data['stabilizer.yaw'], + 'front': data['range.front'], + 'back': data['range.back'], + 'up': data['range.up'], + 'down': data['range.zrange'], + 'left': data['range.left'], + 'right': data['range.right'] + } + self.canvas.set_measurement(measurement) + + def closeEvent(self, event): + if (self.cf is not None): + self.cf.close_link() + + +class Canvas(scene.SceneCanvas): + def __init__(self, keyupdateCB): + scene.SceneCanvas.__init__(self, keys=None) + self.size = 800, 600 + self.unfreeze() + self.view = self.central_widget.add_view() + self.view.bgcolor = '#ffffff' + self.view.camera = TurntableCamera( + fov=10.0, distance=30.0, up='+z', center=(0.0, 0.0, 0.0)) + self.last_pos = [0, 0, 0] + self.pos_markers = visuals.Markers() + self.meas_markers = visuals.Markers() + self.pos_data = np.array([0, 0, 0], ndmin=2) + self.meas_data = np.array([0, 0, 0], ndmin=2) + self.lines = [] + + self.view.add(self.pos_markers) + self.view.add(self.meas_markers) + for i in range(6): + line = visuals.Line() + self.lines.append(line) + self.view.add(line) + + self.keyCB = keyupdateCB + + self.freeze() + + scene.visuals.XYZAxis(parent=self.view.scene) + + def on_key_press(self, event): + if (not event.native.isAutoRepeat()): + if (event.native.key() == QtCore.Qt.Key_Left): + self.keyCB('y', 1) + if (event.native.key() == QtCore.Qt.Key_Right): + self.keyCB('y', -1) + if (event.native.key() == QtCore.Qt.Key_Up): + self.keyCB('x', 1) + if (event.native.key() == QtCore.Qt.Key_Down): + self.keyCB('x', -1) + if (event.native.key() == QtCore.Qt.Key_A): + self.keyCB('yaw', -70) + if (event.native.key() == QtCore.Qt.Key_D): + self.keyCB('yaw', 70) + if (event.native.key() == QtCore.Qt.Key_Z): + self.keyCB('yaw', -200) + if (event.native.key() == QtCore.Qt.Key_X): + self.keyCB('yaw', 200) + if (event.native.key() == QtCore.Qt.Key_W): + self.keyCB('height', 0.1) + if (event.native.key() == QtCore.Qt.Key_S): + self.keyCB('height', -0.1) + + def on_key_release(self, event): + if (not event.native.isAutoRepeat()): + if (event.native.key() == QtCore.Qt.Key_Left): + self.keyCB('y', 0) + if (event.native.key() == QtCore.Qt.Key_Right): + self.keyCB('y', 0) + if (event.native.key() == QtCore.Qt.Key_Up): + self.keyCB('x', 0) + if (event.native.key() == QtCore.Qt.Key_Down): + self.keyCB('x', 0) + if (event.native.key() == QtCore.Qt.Key_A): + self.keyCB('yaw', 0) + if (event.native.key() == QtCore.Qt.Key_D): + self.keyCB('yaw', 0) + if (event.native.key() == QtCore.Qt.Key_W): + self.keyCB('height', 0) + if (event.native.key() == QtCore.Qt.Key_S): + self.keyCB('height', 0) + if (event.native.key() == QtCore.Qt.Key_Z): + self.keyCB('yaw', 0) + if (event.native.key() == QtCore.Qt.Key_X): + self.keyCB('yaw', 0) + + def set_position(self, pos): + self.last_pos = pos + if (PLOT_CF): + self.pos_data = np.append(self.pos_data, [pos], axis=0) + self.pos_markers.set_data(self.pos_data, face_color='red', size=5) + + def rot(self, roll, pitch, yaw, origin, point): + cosr = math.cos(math.radians(roll)) + cosp = math.cos(math.radians(pitch)) + cosy = math.cos(math.radians(yaw)) + + sinr = math.sin(math.radians(roll)) + sinp = math.sin(math.radians(pitch)) + siny = math.sin(math.radians(yaw)) + + roty = np.array([[cosy, -siny, 0], + [siny, cosy, 0], + [0, 0, 1]]) + + rotp = np.array([[cosp, 0, sinp], + [0, 1, 0], + [-sinp, 0, cosp]]) + + rotr = np.array([[1, 0, 0], + [0, cosr, -sinr], + [0, sinr, cosr]]) + + rotFirst = np.dot(rotr, rotp) + + rot = np.array(np.dot(rotFirst, roty)) + + tmp = np.subtract(point, origin) + tmp2 = np.dot(rot, tmp) + return np.add(tmp2, origin) + + def rotate_and_create_points(self, m): + data = [] + o = self.last_pos + roll = m['roll'] + pitch = -m['pitch'] + yaw = m['yaw'] + + if (m['up'] < SENSOR_TH): + up = [o[0], o[1], o[2] + m['up'] / 1000.0] + data.append(self.rot(roll, pitch, yaw, o, up)) + + if (m['down'] < SENSOR_TH and PLOT_SENSOR_DOWN): + down = [o[0], o[1], o[2] - m['down'] / 1000.0] + data.append(self.rot(roll, pitch, yaw, o, down)) + + if (m['left'] < SENSOR_TH): + left = [o[0], o[1] + m['left'] / 1000.0, o[2]] + data.append(self.rot(roll, pitch, yaw, o, left)) + + if (m['right'] < SENSOR_TH): + right = [o[0], o[1] - m['right'] / 1000.0, o[2]] + data.append(self.rot(roll, pitch, yaw, o, right)) + + if (m['front'] < SENSOR_TH): + front = [o[0] + m['front'] / 1000.0, o[1], o[2]] + data.append(self.rot(roll, pitch, yaw, o, front)) + + if (m['back'] < SENSOR_TH): + back = [o[0] - m['back'] / 1000.0, o[1], o[2]] + data.append(self.rot(roll, pitch, yaw, o, back)) + + return data + + def set_measurement(self, measurements): + data = self.rotate_and_create_points(measurements) + o = self.last_pos + for i in range(6): + if (i < len(data)): + o = self.last_pos + self.lines[i].set_data(np.array([o, data[i]])) + else: + self.lines[i].set_data(np.array([o, o])) + + if (len(data) > 0): + self.meas_data = np.append(self.meas_data, data, axis=0) + self.meas_markers.set_data(self.meas_data, face_color='blue', size=5) + + +if __name__ == '__main__': + appQt = QtWidgets.QApplication(sys.argv) + win = MainWindow(URI) + win.show() + appQt.exec_() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/multiranger_push.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/multiranger_push.py new file mode 100755 index 00000000..a63e01f8 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/multiranger_push.py @@ -0,0 +1,105 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2017 Bitcraze AB +# +# Crazyflie Python Library +# +# 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. +""" +Example scipts that allows a user to "push" the Crazyflie 2.0 around +using your hands while it's hovering. + +This examples uses the Flow and Multi-ranger decks to measure distances +in all directions and tries to keep away from anything that comes closer +than 0.2m by setting a velocity in the opposite direction. + +The demo is ended by either pressing Ctrl-C or by holding your hand above the +Crazyflie. + +For the example to run the following hardware is needed: + * Crazyflie 2.0 + * Crazyradio PA + * Flow deck + * Multiranger deck +""" +import logging +import sys +import time + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from cflib.positioning.motion_commander import MotionCommander +from cflib.utils.multiranger import Multiranger + +URI = 'radio://0/80/2M' + +if len(sys.argv) > 1: + URI = sys.argv[1] + +# Only output errors from the logging framework +logging.basicConfig(level=logging.ERROR) + + +def is_close(range): + MIN_DISTANCE = 0.2 # m + + if range is None: + return False + else: + return range < MIN_DISTANCE + + +if __name__ == '__main__': + # Initialize the low-level drivers (don't list the debug drivers) + cflib.crtp.init_drivers(enable_debug_driver=False) + + cf = Crazyflie(rw_cache='./cache') + with SyncCrazyflie(URI, cf=cf) as scf: + with MotionCommander(scf) as motion_commander: + with Multiranger(scf) as multiranger: + keep_flying = True + + while keep_flying: + VELOCITY = 0.5 + velocity_x = 0.0 + velocity_y = 0.0 + + if is_close(multiranger.front): + velocity_x -= VELOCITY + if is_close(multiranger.back): + velocity_x += VELOCITY + + if is_close(multiranger.left): + velocity_y -= VELOCITY + if is_close(multiranger.right): + velocity_y += VELOCITY + + if is_close(multiranger.up): + keep_flying = False + + motion_commander.start_linear_motion( + velocity_x, velocity_y, 0) + + time.sleep(0.1) + + print('Demo terminated!') diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/position_commander_demo.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/position_commander_demo.py new file mode 100644 index 00000000..e00a28f0 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/position_commander_demo.py @@ -0,0 +1,82 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2018 Bitcraze AB +# +# 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. +""" +This script shows the basic use of the PositionHlCommander class. + +Simple example that connects to the crazyflie at `URI` and runs a +sequence. This script requires some kind of location system. + +The PositionHlCommander uses position setpoints. + +Change the URI variable to your Crazyflie configuration. +""" +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from cflib.positioning.position_hl_commander import PositionHlCommander + +# URI to the Crazyflie to connect to +uri = 'radio://0/80/2M/E7E7E7E7E7' + + +def slightly_more_complex_usage(): + with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf: + with PositionHlCommander( + scf, + x=0.0, y=0.0, z=0.0, + default_velocity=0.3, + default_height=0.5, + controller=PositionHlCommander.CONTROLLER_MELLINGER) as pc: + # Go to a coordinate + pc.go_to(1.0, 1.0, 1.0) + + # Move relative to the current position + pc.right(1.0) + + # Go to a coordinate and use default height + pc.go_to(0.0, 0.0) + + # Go slowly to a coordinate + pc.go_to(1.0, 1.0, velocity=0.2) + + # Set new default velocity and height + pc.set_default_velocity(0.3) + pc.set_default_height(1.0) + pc.go_to(0.0, 0.0) + + +def simple_sequence(): + with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf: + with PositionHlCommander(scf) as pc: + pc.forward(1.0) + pc.left(1.0) + pc.back(1.0) + pc.go_to(0.0, 0.0, 1.0) + + +if __name__ == '__main__': + cflib.crtp.init_drivers(enable_debug_driver=False) + + simple_sequence() + # slightly_more_complex_usage() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/bezier_trajectory.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/bezier_trajectory.py new file mode 100644 index 00000000..9b26ad94 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/bezier_trajectory.py @@ -0,0 +1,425 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# 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. +""" +Example of how to generate trajectories for the High Level commander using +Bezier curves. The output from this script is intended to be pasted into the +autonomous_sequence_high_level.py example. + +This code uses Bezier curves of degree 7, that is with 8 control points. +See https://en.wikipedia.org/wiki/B%C3%A9zier_curve + +All coordinates are (x, y, z, yaw) +""" +import math + +import numpy as np + + +class Node: + """ + A node represents the connection point between two Bezier curves + (called Segments). + It holds 4 control points for each curve and the positions of the control + points are set to join the curves with continuity in c0, c1, c2, c3. + See https://www.cl.cam.ac.uk/teaching/2000/AGraphHCI/SMEG/node3.html + + The control points are named + p4, p5, p6 and p7 for the tail of the first curve + q0, q1, q2, q3 for the head of the second curve + """ + + def __init__(self, q0, q1=None, q2=None, q3=None): + """ + Create a Node. Pass in control points to define the shape of the + two segments that share the Node. The control points are for the + second segment, that is the four first control points of the Bezier + curve after the node. The control points for the Bezier curve before + the node are calculated from the existing control points. + The control points are for scale = 1, that is if the Bezier curve + after the node has scale = 1 it will have exactly these handles. If the + curve after the node has a different scale the handles will be moved + accordingly when the Segment is created. + + q0 is required, the other points are optional. + if q1 is missing it will be set to generate no velocity in q0. + If q2 is missing it will be set to generate no acceleration in q0. + If q3 is missing it will be set to generate no jerk in q0. + + If only q0 is set, the node will represent a point where the Crazyflie + has no velocity. Good for starting and stopping. + + To get a fluid motion between segments, q1 must be set. + + :param q0: The position of the node + :param q1: The position of the first control point + :param q2: The position of the second control point + :param q3: The position of the third control point + """ + self._control_points = np.zeros([2, 4, 4]) + + q0 = np.array(q0) + + if q1 is None: + q1 = q0 + else: + q1 = np.array(q1) + # print('q1 generated:', q1) + + d = q1 - q0 + + if q2 is None: + q2 = q0 + 2 * d + # print('q2 generated:', q2) + else: + q2 = np.array(q2) + + e = 3 * q2 - 2 * q0 - 6 * d + + if q3 is None: + q3 = e + 3 * d + # print('q3 generated:', q3) + else: + q3 = np.array(q3) + + p7 = q0 + p6 = q1 - 2 * d + p5 = q2 - 4 * d + p4 = 2 * e - q3 + + self._control_points[0][0] = q0 + self._control_points[0][1] = q1 + self._control_points[0][2] = q2 + self._control_points[0][3] = q3 + + self._control_points[1][3] = p7 + self._control_points[1][2] = p6 + self._control_points[1][1] = p5 + self._control_points[1][0] = p4 + + def get_head_points(self): + return self._control_points[0] + + def get_tail_points(self): + return self._control_points[1] + + def draw_unscaled_controlpoints(self, visualizer): + color = (0.8, 0.8, 0.8) + for p in self._control_points[0]: + visualizer.marker(p[0:3], color=color) + for p in self._control_points[1]: + visualizer.marker(p[0:3], color=color) + + def print(self): + print('Node ---') + print('Tail:') + for c in self._control_points[1]: + print(c) + print('Head:') + for c in self._control_points[0]: + print(c) + + +class Segment: + """ + A Segment represents a Bezier curve of degree 7. It uses two Nodes to + define the shape. The scaling of the segment will move the handles compared + to the Node to maintain continuous position, velocity, acceleration and + jerk through the Node. + A Segment can generate a polynomial that is compatible with the High Level + Commander, either in python to be sent to the Crazyflie, or as C code to be + used in firmware. + A Segment can also be rendered in Vispy. + """ + + def __init__(self, head_node, tail_node, scale): + self._scale = scale + + unscaled_points = np.concatenate( + [head_node.get_head_points(), tail_node.get_tail_points()]) + + self._points = self._scale_control_points(unscaled_points, self._scale) + + polys = self._convert_to_polys() + self._polys = self._stretch_polys(polys, self._scale) + + self._vel = self._deriv(self._polys) + self._acc = self._deriv(self._vel) + self._jerk = self._deriv(self._acc) + + def _convert_to_polys(self): + n = len(self._points) - 1 + result = np.zeros([4, 8]) + + for d in range(4): + for j in range(n + 1): + s = 0.0 + for i in range(j + 1): + s += ((-1) ** (i + j)) * self._points[i][d] / ( + math.factorial(i) * math.factorial(j - i)) + + c = s * math.factorial(n) / math.factorial(n - j) + result[d][j] = c + + return result + + def draw_trajectory(self, visualizer): + self._draw(self._polys, 'black', visualizer) + + def draw_vel(self, visualizer): + self._draw(self._vel, 'green', visualizer) + + def draw_acc(self, visualizer): + self._draw(self._acc, 'red', visualizer) + + def draw_jerk(self, visualizer): + self._draw(self._jerk, 'blue', visualizer) + + def draw_control_points(self, visualizer): + for p in self._points: + visualizer.marker(p[0:3]) + + def _draw(self, polys, color, visualizer): + step = self._scale / 32 + prev = None + for t in np.arange(0.0, self._scale + step, step): + p = self._eval_xyz(polys, t) + + if prev is not None: + visualizer.line(p, prev, color=color) + + prev = p + + def velocity(self, t): + return self._eval_xyz(self._vel, t) + + def acceleration(self, t): + return self._eval_xyz(self._acc, t) + + def jerk(self, t): + return self._eval_xyz(self._jerk, t) + + def _deriv(self, p): + result = [] + for i in range(3): + result.append([ + 1 * p[i][1], + 2 * p[i][2], + 3 * p[i][3], + 4 * p[i][4], + 5 * p[i][5], + 6 * p[i][6], + 7 * p[i][7], + 0 + ]) + + return result + + def _eval(self, p, t): + result = 0 + for part in range(8): + result += p[part] * (t ** part) + return result + + def _eval_xyz(self, p, t): + return np.array( + [self._eval(p[0], t), self._eval(p[1], t), self._eval(p[2], t)]) + + def print_poly_python(self): + s = ' [' + str(self._scale) + ', ' + + for axis in range(4): + for d in range(8): + s += str(self._polys[axis][d]) + ', ' + + s += '], # noqa' + print(s) + + def print_poly_c(self): + s = '' + + for axis in range(4): + for d in range(8): + s += str(self._polys[axis][d]) + ', ' + + s += str(self._scale) + print(s) + + def print_points(self): + print(self._points) + + def print_peak_vals(self): + peak_v = 0.0 + peak_a = 0.0 + peak_j = 0.0 + + step = 0.05 + for t in np.arange(0.0, self._scale + step, step): + peak_v = max(peak_v, np.linalg.norm(self._eval_xyz(self._vel, t))) + peak_a = max(peak_a, np.linalg.norm(self._eval_xyz(self._acc, t))) + peak_j = max(peak_j, np.linalg.norm(self._eval_xyz(self._jerk, t))) + + print('Peak v:', peak_v, 'a:', peak_a, 'j:', peak_j) + + def _stretch_polys(self, polys, time): + result = np.zeros([4, 8]) + + recip = 1.0 / time + + for p in range(4): + scale = 1.0 + for t in range(8): + result[p][t] = polys[p][t] * scale + scale *= recip + + return result + + def _scale_control_points(self, unscaled_points, scale): + s = scale + l_s = 1 - s + p = unscaled_points + + result = [None] * 8 + + result[0] = p[0] + result[1] = l_s * p[0] + s * p[1] + result[2] = l_s ** 2 * p[0] + 2 * l_s * s * p[1] + s ** 2 * p[2] + result[3] = l_s ** 3 * p[0] + 3 * l_s ** 2 * s * p[ + 1] + 3 * l_s * s ** 2 * p[2] + s ** 3 * p[3] + result[4] = l_s ** 3 * p[7] + 3 * l_s ** 2 * s * p[ + 6] + 3 * l_s * s ** 2 * p[5] + s ** 3 * p[4] + result[5] = l_s ** 2 * p[7] + 2 * l_s * s * p[6] + s ** 2 * p[5] + result[6] = l_s * p[7] + s * p[6] + result[7] = p[7] + + return result + + +class Visualizer: + def __init__(self): + self.canvas = scene.SceneCanvas(keys='interactive', size=(800, 600), + show=True) + view = self.canvas.central_widget.add_view() + view.bgcolor = '#ffffff' + view.camera = TurntableCamera(fov=10.0, distance=40.0, up='+z', + center=(0.0, 0.0, 1.0)) + XYZAxis(parent=view.scene) + self.scene = view.scene + + def marker(self, pos, color='black', size=8): + Markers(pos=np.array(pos, ndmin=2), face_color=color, + parent=self.scene, size=size) + + def lines(self, points, color='black'): + LinePlot(points, color=color, parent=self.scene) + + def line(self, a, b, color='black'): + self.lines([a, b], color) + + def run(self): + self.canvas.app.run() + + +segment_time = 2 +z = 1 +yaw = 0 + +segments = [] + +# Nodes with one control point has not velocity, this is similar to calling +# goto in the High-level commander + +n0 = Node((0, 0, z, yaw)) +n1 = Node((1, 0, z, yaw)) +n2 = Node((1, 1, z, yaw)) +n3 = Node((0, 1, z, yaw)) + +segments.append(Segment(n0, n1, segment_time)) +segments.append(Segment(n1, n2, segment_time)) +segments.append(Segment(n2, n3, segment_time)) +segments.append(Segment(n3, n0, segment_time)) + + +# By setting the q1 control point we get velocity through the nodes +# Increase d to 0.7 to get some more action +d = 0.1 + +n5 = Node((1, 0, z, yaw), q1=(1 + d, 0 + d, z, yaw)) +n6 = Node((1, 1, z, yaw), q1=(1 - d, 1 + d, z, yaw)) +n7 = Node((0, 1, z, yaw), q1=(0 - d, 1 - d, z, yaw)) + +segments.append(Segment(n0, n5, segment_time)) +segments.append(Segment(n5, n6, segment_time)) +segments.append(Segment(n6, n7, segment_time)) +segments.append(Segment(n7, n0, segment_time)) + + +# When setting q2 we can also control acceleration and get more action. +# Yaw also adds to the fun. + +d2 = 0.2 +dyaw = 2 +f = -0.3 + +n8 = Node( + (1, 0, z, yaw), + q1=(1 + d2, 0 + d2, z, yaw), + q2=(1 + 2 * d2, 0 + 2 * d2 + 0*f * d2, 1, yaw)) +n9 = Node( + (1, 1, z, yaw + dyaw), + q1=(1 - d2, 1 + d2, z, yaw + dyaw), + q2=(1 - 2 * d2 + f * d2, 1 + 2 * d2 + f * d2, 1, yaw + dyaw)) +n10 = Node( + (0, 1, z, yaw - dyaw), + q1=(0 - d2, 1 - d2, z, yaw - dyaw), + q2=(0 - 2 * d2, 1 - 2 * d2, 1, yaw - dyaw)) + +segments.append(Segment(n0, n8, segment_time)) +segments.append(Segment(n8, n9, segment_time)) +segments.append(Segment(n9, n10, segment_time)) +segments.append(Segment(n10, n0, segment_time)) + + +print('Paste this code into the autonomous_sequence_high_level.py example to ' + 'see it fly') +for s in segments: + s.print_poly_python() + + +# Enable this if you have Vispy installed and want a visualization of the +# trajectory +if False: + # Import here to avoid problems for users that do not have Vispy + from vispy import scene + from vispy.scene import XYZAxis, LinePlot, TurntableCamera, Markers + + visualizer = Visualizer() + for s in segments: + s.draw_trajectory(visualizer) + # s.draw_vel(visualizer) + # s.draw_control_points(visualizer) + + for n in [n0, n1, n2, n3, n5, n6, n7, n8, n9, n10]: + n.draw_unscaled_controlpoints(visualizer) + + visualizer.run() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/swarmSequence.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/initial_position.py similarity index 60% rename from dfall_ws/src/dfall_pkg/crazyradio/examples/swarmSequence.py rename to dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/initial_position.py index 96037b56..29ed5bfa 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/swarmSequence.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/initial_position.py @@ -6,7 +6,7 @@ # +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ # || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ # -# Copyright (C) 2017 Bitcraze AB +# Copyright (C) 2019 Bitcraze AB # # Crazyflie Nano Quadcopter Client # @@ -24,40 +24,37 @@ # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. """ -Version of the AutonomousSequence.py example connecting to 2 Crazyflies and -flying them throught a list of setpoints at the same time. This shows how to -control more than one Crazyflie autonomously. +Simple example that connects to one crazyflie, sets the initial position/yaw +and flies a trajectory. + +The initial pose (x, y, z, yaw) is configured in a number of variables and +the trajectory is flown relative to this position, using the initial yaw. + +This example is intended to work with any absolute positioning system. +It aims at documenting how to take off with the Crazyflie in an orientation +that is different from the standard positive X orientation and how to set the +initial position of the kalman estimator. """ +import math import time import cflib.crtp +from cflib.crazyflie import Crazyflie from cflib.crazyflie.log import LogConfig -from cflib.crazyflie.swarm import Swarm +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie from cflib.crazyflie.syncLogger import SyncLogger -# Change uris and sequences according to your setup -URI0 = 'radio://0/70/2M' -URI1 = 'radio://0/90/2M' - -uris = {URI0, URI1} - -# x y z YAW -sequence0 = [(2.5, 2.5, 1.0, 0), - (2.5, 2.3, 1.0, 0), - (2.0, 2.3, 1.0, 0), - (2.0, 2.5, 1.0, 0), - (2.0, 2.5, 0.5, 0)] +# URI to the Crazyflie to connect to +uri = 'radio://0/80/2M' -sequence1 = [(2.0, 2.5, 1.0, 0), - (2.0, 2.7, 1.0, 0), - (2.5, 2.7, 1.0, 0), - (2.5, 2.5, 1.0, 0), - (2.5, 2.5, 0.5, 0)] - -seq_args = { - URI0: [sequence0], - URI1: [sequence1], -} +# Change the sequence according to your setup +# x y z +sequence = [ + (0, 0, 0.7), + (-0.7, 0, 0.7), + (0, 0, 0.7), + (0, 0, 0.2), +] def wait_for_position_estimator(scf): @@ -101,6 +98,15 @@ def wait_for_position_estimator(scf): break +def set_initial_position(scf, x, y, z, yaw_deg): + scf.cf.param.set_value('kalman.initialX', x) + scf.cf.param.set_value('kalman.initialY', y) + scf.cf.param.set_value('kalman.initialZ', z) + + yaw_radians = math.radians(yaw_deg) + scf.cf.param.set_value('kalman.initialYaw', yaw_radians) + + def reset_estimator(scf): cf = scf.cf cf.param.set_value('kalman.resetEstimation', '1') @@ -110,38 +116,21 @@ def reset_estimator(scf): wait_for_position_estimator(cf) -def position_callback(timestamp, data, logconf): - x = data['kalman.stateX'] - y = data['kalman.stateY'] - z = data['kalman.stateZ'] - print('pos: ({}, {}, {})'.format(x, y, z)) - - -def start_position_printing(scf): - log_conf = LogConfig(name='Position', period_in_ms=500) - log_conf.add_variable('kalman.stateX', 'float') - log_conf.add_variable('kalman.stateY', 'float') - log_conf.add_variable('kalman.stateZ', 'float') - - scf.cf.log.add_config(log_conf) - log_conf.data_received_cb.add_callback(position_callback) - log_conf.start() - - -def run_sequence(scf, sequence): +def run_sequence(scf, sequence, base_x, base_y, base_z, yaw): cf = scf.cf - cf.param.set_value('flightmode.posSet', '1') - for position in sequence: print('Setting position {}'.format(position)) + + x = position[0] + base_x + y = position[1] + base_y + z = position[2] + base_z + for i in range(50): - cf.commander.send_setpoint(position[1], position[0], - position[3], - int(position[2] * 1000)) + cf.commander.send_position_setpoint(x, y, z, yaw) time.sleep(0.1) - cf.commander.send_setpoint(0, 0, 0, 0) + cf.commander.send_stop_setpoint() # Make sure that the last packet leaves before the link is closed # since the message queue is not flushed before closing time.sleep(0.1) @@ -150,7 +139,19 @@ def run_sequence(scf, sequence): if __name__ == '__main__': cflib.crtp.init_drivers(enable_debug_driver=False) - with Swarm(uris) as swarm: - swarm.parallel(reset_estimator) - # swarm.parallel(start_position_printing) - swarm.parallel(run_sequence, args_dict=seq_args) + # Set these to the position and yaw based on how your Crazyflie is placed + # on the floor + initial_x = 1.0 + initial_y = 1.0 + initial_z = 0.0 + initial_yaw = 90 # In degrees + # 0: positive X direction + # 90: positive Y direction + # 180: negative X direction + # 270: negative Y direction + + with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf: + set_initial_position(scf, initial_x, initial_y, initial_z, initial_yaw) + reset_estimator(scf) + run_sequence(scf, sequence, + initial_x, initial_y, initial_z, initial_yaw) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/matrix_light_printer.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/matrix_light_printer.py new file mode 100644 index 00000000..cd62017e --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/matrix_light_printer.py @@ -0,0 +1,115 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2018 Bitcraze AB +# +# 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. +""" +This script implements a simple matrix light printer to be used with a +camera with open shutter in a dark room. + +It requires a Crazyflie capable of controlling its position and with +a Led ring attached to it. A piece of sicky paper can be attached on +the led ring to orient the ring light toward the front. + +To control it position, Crazyflie requires an absolute positioning +system such as the Lighthouse. +""" +import time + +import matplotlib.pyplot as plt + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from cflib.positioning.position_hl_commander import PositionHlCommander + +# URI to the Crazyflie to connect to +uri = 'radio://0/80' + + +class ImageDef: + def __init__(self, file_name): + self._image = plt.imread(file_name) + + self.x_pixels = self._image.shape[1] + self.y_pixels = self._image.shape[0] + + width = 1.0 + height = self.y_pixels * width / self.x_pixels + + self.x_start = -width / 2.0 + 0.5 + self.y_start = 0.7 + + self.x_step = width / self.x_pixels + self.y_step = height / self.y_pixels + + def get_color(self, x_index, y_index): + rgba = self._image[self.y_pixels - y_index - 1, x_index] + rgb = [int(rgba[0] * 90), int(rgba[1] * 90), int(rgba[2] * 90)] + return rgb + + +BLACK = [0, 0, 0] + + +def set_led_ring_solid(cf, rgb): + cf.param.set_value('ring.effect', 7) + print(rgb[0], rgb[1], rgb[2]) + cf.param.set_value('ring.solidRed', rgb[0]) + cf.param.set_value('ring.solidGreen', rgb[1]) + cf.param.set_value('ring.solidBlue', rgb[2]) + + +def matrix_print(cf, pc, image_def): + set_led_ring_solid(cf, BLACK) + time.sleep(3) + + for y_index in range(image_def.y_pixels): + y = image_def.y_start + image_def.y_step * y_index + + pc.go_to(0, image_def.x_start - 0.1, y) + time.sleep(1.0) + + scan_range = range(image_def.x_pixels) + + for x_index in scan_range: + x = image_def.x_start + image_def.x_step * x_index + + color = image_def.get_color(x_index, y_index) + + print(x, y, color) + + pc.go_to(0, x, y) + set_led_ring_solid(cf, color) + + set_led_ring_solid(cf, BLACK) + + print('---') + + +if __name__ == '__main__': + cflib.crtp.init_drivers(enable_debug_driver=False) + + image_def = ImageDef('monalisa.png') + + with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf: + with PositionHlCommander(scf, default_height=0.5) as pc: + matrix_print(scf.cf, pc, image_def) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/monalisa.png b/dfall_ws/src/dfall_pkg/crazyradio/examples/positioning/monalisa.png new file mode 100644 index 0000000000000000000000000000000000000000..f39be376ec492505861b2e6b2d93d3b31fa54e17 GIT binary patch literal 4886 zcmY*dcQ_o*)?QYLUP7#HSCFWyvmx5*y+jSsMU=&^7Flg|Rxi<O^cuZJ2_bq|B?uv+ z1qsn2<jU{f?|$Dm&vRzZoO#dto-=>VGtqiFsuZM5qyPYbLR}4RaI=cs7~~ew&CI$J z!+W#fAq`X&0ksn>J2x8=4>dC+06=#8ui*i*azHl#GiM`Hl&Q8B%nsouXk(ACbrAG( z^SD6+05X2C8`sSNWy9g;=IV}w`N=~5LBMYOzhNN=$3GC1i!8)cTaQBt;pM;~E+{4l zg*+tX;NXz)vUh|Tz*YW}ezTK>JVl{AU_wH^zP^IKqJju7Cm~^JX=x#-h>(bgzzsqG z>F<uR@e^=Ia{im-e|X>yNINfQ50o>)o#QXBjV;0(B@2Q475eY^cbzC_$NyDwNB*a+ zn+Apco(KsGLWTazeUmElHwx4Ba(1{;{>%SRSmqz(|BL-cM@Hzc`2Q*9-<|#wy=nC! zsf^Hnuk9hJRzHs!06=4`4p%TTB@xIRO?bTJIXH=44LtkVHT>BFzH1X}Ku6qCLSSZ3 zvk+s)p#Wf3yAJtHuK=iP9DmOzgsJW#rv=hbgP^WF>E*5VF=8X&E!@oE!O~go6H9Z^ zfrB3O;Tigo_wH;(^6^H{MPvuRNP8aLd0yp5{rw>Wv+o&Ir}*tU0wXDg3|*_0=~W%o zegc~vcy%(PzRFgkWRN*hBjddHsA9-C*Si#kqpo+k@x`f!-*9JWD_3l#e@hE;mg};0 zA@)Q%_I6nH#D3tt*7trJM>$oMS|u^Z=gWJ8N0yU@EX{4yuT8-`x>85RT#<G46Pv+~ zkpqray+c;{TS$7`9pnp%&EOV8)(TwzvRBop>Q<I)?$Z|yMz48|J|5c?TnB0n6epeP zoYH%9(t8W6RzZo1na}EJiBBF|vE;je*@a6d+Uma4cS&woW*o}UOD*MmTjwArd1NA; z<oDSjp&0@(e64QQ!O|jKDs$&MenP+^Ehe;Je1PS3zp!_CZ$;|(*00|g?3yNaC#vXi zDeEcH)b*}C&)P<w==HPwdr~{wORGVal2)?DoAq)51XeMI5Xd+Wzh_s}iJ2sa2z)Ni z!!znIlr|3KS-`GZNnm>`;_TCtpuKksBhJv^@2X(}QAI<XKA0uYRDWWDa0T}lO34jt z87DUT#`<Dc*o>3hAMCPrW$}{bMRk&!S!(AfY2D{d3J;B_x6k!=-~8E1vTC21@6%6^ zU7(6IPFq1lc<52n61>fk9gA*2s8~m@gv{)d6KP|*M%R0YhhVvYF&b`6(mJ<&Kc|A5 z)L8rUot8+;9<u1v@YEE>Hbv`^E#07FdCAj{9lnQpodNpD$&(ZFjVf%<Z?BrWp0oYJ zjT9I1Y`H9hzvlB_lmuOu#h>b$Q$YI5-5e#IY@9FM3T{W_41SLDe=lx57-%{m3UZnv z#g8MHp{G9jVQfZhIvD^p!&xYSi9mw>EMvGqvIIgrEBuVFBmK^MKdvUlK7@a|tZMZ> z{u*Mtrk5Nwx~Vunk32D7{`13}D$fLB{n1^@`Yr_y7j*UQ_SH7KFC8ipE8N24D@oKf z%)o)gRFQ5oli-DBoxMKJ#4ux`bwHl-3mgOQp>en`YE^c=NROTYAREKJB?+^C#QiwQ zAY7pCh<)Yc>K}Qz-`SlV-h1-<K9S<z0!)WaH@41wG~!*wp5WEF)#MO7LCEa0692+E zC7c`-M<1XAN>FzEJNTY2Cw+*_OYRbo>hvcftsTQNhjIw@J;$E*Zl=_E#s>8UC0m1y zo{}3s=pDo}kkKLtnKve!hGsQJ(Q}Dyx6miXr9|pBcbk{bpfg!D>6ac2sN^Mlc6Cf0 z%beXK{>Ys4lWbd(uX(Ua`5Dc@UTi}C-YK8zct?$KHNRP-?%O`BS2lldeU4Ig5_SA5 zG3nGTGvxSIcYeKTWOnl1nHDX26`%}BEJ#VA(PsM?5S{%>o?NK!_+gbQtLo_JyXQam zbiF;COu*Uhh9C-t4(Nge6?E7z3t#tWf6XKKM=wY%=jxCsy;4D;hNk5ET5&`Cf$YpQ z9(n6g>VU?BPB<G&L^Up4nL>r7yh4al9dWBdosiEE9Q9*Ts0=;~>g+YVPd@vhTr*69 zZ+tHL7lxJMqmuHz4^n;<3ovfL$e;rYSFa$r{HvAPj$A=^kvqi;KggE&bPbAF8zO}A z!<ybo$qHG6GNR5wk1FP|;_ck|rJ9z;Q2NN2OW<%KjIe39sPr0T1*KEL(NhlITip)K zc5c9XgXdypIVOdwO<4i;c%Zy}Dl+w1&zI8UC!FFHgNm1km9RdM-(TQi&NYS?s$$c2 z^_k&>AJ@7UQMG~d^PjOj+$q?=%OKs^op<oXc~tt|^W<m3Lczq-%UO_nAx<@HG*()g zn|?141X{r}jAu;QbG;t4X&sEHY?f%W-iHI1P9kN-_FM4$_|_u^GV)MLh6>H7@=x`% zu0-Ps0E=Ez4nq}LlYHa`v!^B+(m3uV%kI<x%788S7A`2h`L)?@yHN3^^AN53>-$Eu zU|k8~z^~)aQnb#b7i;d@kE;|oQqg9$MyBmeW9tgCJ%`$I_MJtCT5!M+tL}!da`K7K zJxJ@Rx!S$*)wM9s65=iI<}f$AqoFerht9!J{%6ZZ)fIE{<CW*O5ogt3O?&Wxb*6iZ z#hTiZ)&a!sW!3rU_St|Sxv9>>1D6Jl=^1j2wIHHU?s`ryG63(wV0+&e29t?8nJ%-t zyR3m-77-ZCZ?G7Vbv8~M&f`arHKjU)4k++wMimlGBx)M#>6R<|zb>qGZL%VaA(l;n znr0NaK<qflhml<!I9P=Zi$M%FFQ@p;aI9|fWNMwEWoc6UX$OB3?r^bob^IqSPNwcs zo=WJbvGew`jIeJ1uDa~jgw$FSSinOZD(k5OF<L(ryGbw4vh=8y?GP=;`2@MiBGq?) zsAQ5lrEDI!vZ(9fr5w7I6WNc|A^}d2jGPl*=&voJEO=wu+ceIT?X|R;=j!8utj6{9 z(cWgy2(ZRRmt|B#F%qv1)?YOqQ;2gIBE)Qu8Hxm>rc{l6^#Cf_qF&oSFU%P-7@Lkl zowZoKbTSWtPp`hzQw`XdlD{a3O}2GOS2XX)a?>N~P1yeI>_(cw@>x33$bjwlp75sw zv%)H)nh+`~9O%P-5}C7xB~-fCR(>2ciON*W21!ohGW(tp$Fs>zRIJ~%>6#{0{TT`5 z+H=FK+P~b0!%hgc!rr_WS9Y>tbYb$)syt>&=A5bN3G}P+Ax>w86x%&pVE<_hr;*?a zZ0P6mrp)0L*kV3vn|fMTM)+z#GR*>EU6f9h>a{?M@Q4c2F47^6XkfD7xNY@?^cHaP zF*u<*&+W(gde<z&6YL2$>UOIv`n=EXYAZ-)E<moWYUx&A)ri4XhS90Af;OZ>C6}Ap zM(&~B__VgXqp-S~t<}~x=yomkqe=m7;R>EC<%s>)Rwnaw<57*WjZBs~FS6?jzn89| zf1;Uj3&nc$Sng2$Z?JpEHg_=UeZJp;NysLMh(5U?S6*#dg<!!3xysJk)V$T6i}J&j zKVKLxhS&)DIX%bOxm?<OLjF8HZ7nx#cOT3%FW@YV58sw9DYLC-P#kR>(a4tG#mGc- zOH)+<o<kn`79v_z6jk^EaAx3|(x*-_^{_j2h<TLT7d@RHBln8w=Xv>Jpq2@hx{LCE z{9r%{F#0{IpBE+TH|mNJrgvE^k@Uv~nqH)IYXqQV+3NB~EN`9dd+6nkFt-?Mh>Yd$ zlUdOjg3#dw#j@Y}>O(|8?n*jk784jbFVMK;58O7B#Oo?4Y{8lXXrRe}aQ3K_O!So* zr<siRIbRO^ew?Rl%Ew}j!#|Me>!(GB*PEK}J#gD9HI&q29%DZ*40Lr&zNmhBA&B+r zd#WQw8V4}dw%G${y9o0_?tmQyM(%Uo6)g!)VjS}c`Q?Fa4$f0pRaHqkE`P$lmu~TD zu1g+c1&{AFrH}CUE8Usj$<{vUsCLXjbfY^Bo!4t<(raN*^F8RS?zLOx9qFT1Ilo5( z3e`eApuNQljk3u(Bkz|)M33Fg0FiWhytVGTsW@7@;hZSnC<0ZzI_;+OOyGXZ<4RW_ z`ThWw-aQWPi*Fp!2HCgQ(8;+zVq+waDx2b(0^~1mU3+S9p7X<dXz-~E_LYzqyFa(T z20u#27Q(kvuK9SDi#eajU7e9g|44(msWO<%ve3!Lj2dSa6UIP-<;IKW#9>3t@*`{d z{c*<xPKs6FF|idWmHe5T|0;ecm-uMM>@1!5P&0IBZ6B<LoxIAz-0>^^su+hy-#}hO znXlh)9ZR}ui@c4d@xPto3>M_;tC^>`@6k)eJz}=JAaGYQ@Rw-iFTR|lVS1xo78MbL z9h)3gv0nlvTl39xy^z)x+{@UvPk3HQO!<zm4V8LQ#3k}E4?_T~^x|~{_r*&ZOMNBF zE#7T6SsWo{l-t)JBTBbqrNoH@tsWT1G6N~yQphlwC-`8gi5Bj;w!;FU$Ph)U=VFYZ zUd~M)pPKxdSW-$}of+U^rc~|gR~I0EN;AEf3WJU^0X0S6UY`qdi#9Mp<9CucZ_!rz zVhx5gyxto{XnRqQQPalQr@eNv;CwlQ@T5l*X_aUBElYSwxjrbB%3^DI+MpgRJoGrc zfjXbBvI^51S1`hqU`_@6@cD(wywM?D=Jk-vgWaNovU&MKDw1V)VisChw~q5LFBgag zxsYhJ#S*?;oQ`TMTMfS-(jEJOb-FCktlqpZghYpme>(5Uc!*@&4tW2{{Y_1beSAoW z|1zE;XHXTiJ=lT#vJJSCcS==Y0Sbk{7vVKJ6+?bu;k+H1--4xsLDIjm2$78<)$bnt z`x{9SY8U-kVsz!>1uz=rBS^@Pa%T9*FUm+6DT}r&#hbVLHGUKfzV#K{Ei=J3)A;*B zR<-qc)1BjZ?$mI+lV>f%O<$znL{y>Mo|A1pzxyPEvNkQRB2?jp+Um1lrI+k4zEh_; z14W_F{2U9j3Lh&ZM>rBrHR$Y*o1nX|axJ@2XVl_=OEBk0KOAYf_AR%{MPhv9*T-dL z%%-#n$(Z@!1n_QAD1mK?+IZIpx5RLf^g4}stqXMUu?>kx0srokYEp-swAnuEp2W^~ z+{|M0&uUf#S+K%0E(R|>T6<StkhBGBg^o?wq+zb)$t0}wlwc(t+K;3#J(mngpZxYp zea?t?PhOfd#Czw?S{8*|s;!}b4tCatVGZnrlxesQ+XSDdHM!H)%5Wu$9S0pNw%s8c z6aBv4kmk~Dek7Om+~BOTx+r!>*jc6`Ju6?QP+S+?&zRE0xUl>gO_tseDxsq$@3DLU zd#-`8=QQPm)8`gqBwcQ;>sn=ex|p%sXJzBicfEEYSqxFzzEU?>ZS`kV`B9zbu_qSr z)taRq4iVT9cBL8(7f4AT<q@T8)8@F%dibdbbK3MJt~O<7DDh%}>2x537?==EKJ_|l z`W1CcBKRRq{RBB9Fl>P!Zo($x*7-M7FaOym7CgD1lW|{~^Ozr?KGgmE%B)00&KVa8 z1v#waAK~BW=U})#b6ud2W$KD^b*pzgUXIJ-0nU-dI4~>eoJO<DUieLX3z2xh`sMle z6H}m9JK4(8m}~QxSlA=%`??Xcl$bzwp0D#NLwm34QXUkZZYLpQO!4ziFX>d`ng;DW z81d`MOnN5N>nSgeMCxDon{IEnX(sF|fh5uhMC)Vx2UH5d1o##hU*_e{fa`QJ?z>Wg z@9GEfL3Rr(oVt=V#Z3*M09p7WIXQ2fib9iF6$ekzr{Em^*#<^l0@?m4imM0SB_$y? z_-eu;B;POVMD|w{f3iX+RCyQl5D^M&iDdUx&L&@27WzEE<IRZb3Y47dMv!}>oT$RB z4<bnyno2((foU~;_)>kK*~T5SoDUO8Ooz}UN$87(`3DFZ=LiaLW0QC|r;KLdR}J0C zJ;(a9-ILH9brgV%@)VX;XL%AFq%GK9|LP4eRfBXIK;|hy+G-zf;o`L}3J!}i=<nVt zddGY9E3n*2Ez+*Q-tOfFa0e^LwA~yaIlIc*%da)lF!25GC0L8RCc9b-lgI;Z>RjYc zRp1xD{d=x<p#1*S^tf6v4MzG@GAoz5kgq`8!Z15(A!0l5-1K>_nuC@EyR_!L_L>2U zu~GMe7%;@Xn~Sa~%2(^z;S^O<jRgS_lADQeByf+b3%-8!d(;52qA(3n)nbF9oXe4I zqhqm3^J~Pm&ONa^KOc8(`u$FL8Hcd|WR-hRXdtGK51U*lUiu3U45({f9qdt9mUtI} zrijwN>4QDVD}+b<gq^ngW`~Hs60SItraqA5Re2P0&AxFl={AZWR{Z-}rLL?4uT``T F{TE}}5yJog literal 0 HcmV?d00001 diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/qualisys/qualisys_hl_commander.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/qualisys/qualisys_hl_commander.py new file mode 100644 index 00000000..dc30c68b --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/qualisys/qualisys_hl_commander.py @@ -0,0 +1,315 @@ +# -*- coding: utf-8 -*- +# +# ,---------, ____ _ __ +# | ,-^-, | / __ )(_) /_______________ _____ ___ +# | ( O ) | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# | / ,--' | / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# +------` /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# 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, in version 3. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see <http://www.gnu.org/licenses/>. +""" +Example of how to connect to a Qualisys QTM system and feed the position to a +Crazyflie. It uses the high level commander to upload a trajectory to fly a +figure 8. + +Set the uri to the radio settings of the Crazyflie and modify the +ridgid_body_name to match the name of the Crazyflie in QTM. + +Limitations: This script does not support full pose and the Crazyflie +must be started facing positive X. +""" +import asyncio +import math +import time +import xml.etree.cElementTree as ET +from threading import Thread + +import qtm + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.mem import MemoryElement +from cflib.crazyflie.mem import Poly4D +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from cflib.crazyflie.syncLogger import SyncLogger + + +# URI to the Crazyflie to connect to +uri = 'radio://0/80/2M' + +# The name of the rigid body in QTM that represents the Crazyflie +ridgid_body_name = 'cf' + +# The trajectory to fly +# See https://github.com/whoenig/uav_trajectories for a tool to generate +# trajectories + +# Duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7 +figure8 = [ + [1.050000, 0.000000, -0.000000, 0.000000, -0.000000, 0.830443, -0.276140, -0.384219, 0.180493, -0.000000, 0.000000, -0.000000, 0.000000, -1.356107, 0.688430, 0.587426, -0.329106, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.710000, 0.396058, 0.918033, 0.128965, -0.773546, 0.339704, 0.034310, -0.026417, -0.030049, -0.445604, -0.684403, 0.888433, 1.493630, -1.361618, -0.139316, 0.158875, 0.095799, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.620000, 0.922409, 0.405715, -0.582968, -0.092188, -0.114670, 0.101046, 0.075834, -0.037926, -0.291165, 0.967514, 0.421451, -1.086348, 0.545211, 0.030109, -0.050046, -0.068177, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.700000, 0.923174, -0.431533, -0.682975, 0.177173, 0.319468, -0.043852, -0.111269, 0.023166, 0.289869, 0.724722, -0.512011, -0.209623, -0.218710, 0.108797, 0.128756, -0.055461, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.560000, 0.405364, -0.834716, 0.158939, 0.288175, -0.373738, -0.054995, 0.036090, 0.078627, 0.450742, -0.385534, -0.954089, 0.128288, 0.442620, 0.055630, -0.060142, -0.076163, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.560000, 0.001062, -0.646270, -0.012560, -0.324065, 0.125327, 0.119738, 0.034567, -0.063130, 0.001593, -1.031457, 0.015159, 0.820816, -0.152665, -0.130729, -0.045679, 0.080444, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.700000, -0.402804, -0.820508, -0.132914, 0.236278, 0.235164, -0.053551, -0.088687, 0.031253, -0.449354, -0.411507, 0.902946, 0.185335, -0.239125, -0.041696, 0.016857, 0.016709, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.620000, -0.921641, -0.464596, 0.661875, 0.286582, -0.228921, -0.051987, 0.004669, 0.038463, -0.292459, 0.777682, 0.565788, -0.432472, -0.060568, -0.082048, -0.009439, 0.041158, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [0.710000, -0.923935, 0.447832, 0.627381, -0.259808, -0.042325, -0.032258, 0.001420, 0.005294, 0.288570, 0.873350, -0.515586, -0.730207, -0.026023, 0.288755, 0.215678, -0.148061, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa + [1.053185, -0.398611, 0.850510, -0.144007, -0.485368, -0.079781, 0.176330, 0.234482, -0.153567, 0.447039, -0.532729, -0.855023, 0.878509, 0.775168, -0.391051, -0.713519, 0.391628, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000], # noqa +] + + +class QtmWrapper(Thread): + def __init__(self, body_name): + Thread.__init__(self) + + self.body_name = body_name + self.on_pose = None + self.connection = None + self.qtm_6DoF_labels = [] + self._stay_open = True + + self.start() + + def close(self): + self._stay_open = False + self.join() + + def run(self): + asyncio.run(self._life_cycle()) + + async def _life_cycle(self): + await self._connect() + while(self._stay_open): + await asyncio.sleep(1) + await self._close() + + async def _connect(self): + qtm_instance = await self._discover() + host = qtm_instance.host + print('Connecting to QTM on ' + host) + self.connection = await qtm.connect(host) + + params = await self.connection.get_parameters(parameters=['6d']) + xml = ET.fromstring(params) + self.qtm_6DoF_labels = [label.text for label in xml.iter('Name')] + print(self.qtm_6DoF_labels) + + await self.connection.stream_frames( + components=['6D'], + on_packet=self._on_packet) + + async def _discover(self): + async for qtm_instance in qtm.Discover('0.0.0.0'): + return qtm_instance + + def _on_packet(self, packet): + header, bodies = packet.get_6d() + + if bodies is None: + return + + if self.body_name not in self.qtm_6DoF_labels: + print('Body ' + self.body_name + ' not found.') + else: + index = self.qtm_6DoF_labels.index(self.body_name) + temp_cf_pos = bodies[index] + x = temp_cf_pos[0][0] / 1000 + y = temp_cf_pos[0][1] / 1000 + z = temp_cf_pos[0][2] / 1000 + + r = temp_cf_pos[1].matrix + rot = [ + [r[0], r[3], r[6]], + [r[1], r[4], r[7]], + [r[2], r[5], r[8]], + ] + + if self.on_pose: + # Make sure we got a position + if math.isnan(x): + return + + self.on_pose([x, y, z, rot]) + + async def _close(self): + await self.connection.stream_frames_stop() + self.connection.disconnect() + + +class Uploader: + def __init__(self): + self._is_done = False + + def upload(self, trajectory_mem): + print('Uploading data') + trajectory_mem.write_data(self._upload_done) + + while not self._is_done: + time.sleep(0.2) + + def _upload_done(self, mem, addr): + print('Data uploaded') + self._is_done = True + + +def wait_for_position_estimator(scf): + print('Waiting for estimator to find position...') + + log_config = LogConfig(name='Kalman Variance', period_in_ms=500) + log_config.add_variable('kalman.varPX', 'float') + log_config.add_variable('kalman.varPY', 'float') + log_config.add_variable('kalman.varPZ', 'float') + + var_y_history = [1000] * 10 + var_x_history = [1000] * 10 + var_z_history = [1000] * 10 + + threshold = 0.001 + + with SyncLogger(scf, log_config) as logger: + for log_entry in logger: + data = log_entry[1] + + var_x_history.append(data['kalman.varPX']) + var_x_history.pop(0) + var_y_history.append(data['kalman.varPY']) + var_y_history.pop(0) + var_z_history.append(data['kalman.varPZ']) + var_z_history.pop(0) + + min_x = min(var_x_history) + max_x = max(var_x_history) + min_y = min(var_y_history) + max_y = max(var_y_history) + min_z = min(var_z_history) + max_z = max(var_z_history) + + # print("{} {} {}". + # format(max_x - min_x, max_y - min_y, max_z - min_z)) + + if (max_x - min_x) < threshold and ( + max_y - min_y) < threshold and ( + max_z - min_z) < threshold: + break + + +def _sqrt(a): + """ + There might be rounding errors making 'a' slightly negative. + Make sure we don't throw an exception. + """ + if a < 0.0: + return 0.0 + return math.sqrt(a) + + +def send_extpose_rot_matrix(cf, x, y, z, rot): + """ + Send the current Crazyflie X, Y, Z position and attitude as a (3x3) + rotaton matrix. This is going to be forwarded to the Crazyflie's + position estimator. + """ + qw = _sqrt(1 + rot[0][0] + rot[1][1] + rot[2][2]) / 2 + qx = _sqrt(1 + rot[0][0] - rot[1][1] - rot[2][2]) / 2 + qy = _sqrt(1 - rot[0][0] + rot[1][1] - rot[2][2]) / 2 + qz = _sqrt(1 - rot[0][0] - rot[1][1] + rot[2][2]) / 2 + + # Normalize the quaternion + ql = math.sqrt(qx ** 2 + qy ** 2 + qz ** 2 + qw ** 2) + + cf.extpos.send_extpose(x, y, z, qx / ql, qy / ql, qz / ql, qw / ql) + + +def reset_estimator(cf): + cf.param.set_value('kalman.resetEstimation', '1') + time.sleep(0.1) + cf.param.set_value('kalman.resetEstimation', '0') + + # time.sleep(1) + wait_for_position_estimator(cf) + + +def activate_kalman_estimator(cf): + cf.param.set_value('stabilizer.estimator', '2') + + # Set the std deviation for the quaternion data pushed into the + # kalman filter. The default value seems to be a bit too low. + cf.param.set_value('locSrv.extQuatStdDev', 0.06) + + +def activate_high_level_commander(cf): + cf.param.set_value('commander.enHighLevel', '1') + + +def activate_mellinger_controller(cf): + cf.param.set_value('stabilizer.controller', '2') + + +def upload_trajectory(cf, trajectory_id, trajectory): + trajectory_mem = cf.mem.get_mems(MemoryElement.TYPE_TRAJ)[0] + + total_duration = 0 + for row in trajectory: + duration = row[0] + x = Poly4D.Poly(row[1:9]) + y = Poly4D.Poly(row[9:17]) + z = Poly4D.Poly(row[17:25]) + yaw = Poly4D.Poly(row[25:33]) + trajectory_mem.poly4Ds.append(Poly4D(duration, x, y, z, yaw)) + total_duration += duration + + Uploader().upload(trajectory_mem) + cf.high_level_commander.define_trajectory(trajectory_id, 0, + len(trajectory_mem.poly4Ds)) + return total_duration + + +def run_sequence(cf, trajectory_id, duration): + commander = cf.high_level_commander + + commander.takeoff(1.0, 2.0) + time.sleep(3.0) + relative = True + commander.start_trajectory(trajectory_id, 1.0, relative) + time.sleep(duration) + commander.land(0.0, 2.0) + time.sleep(2) + commander.stop() + + +cflib.crtp.init_drivers(enable_debug_driver=False) + +# Connect to QTM +qtm_wrapper = QtmWrapper(ridgid_body_name) + +with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf: + cf = scf.cf + trajectory_id = 1 + + # Set up a callback to handle data from QTM + qtm_wrapper.on_pose = lambda pose: send_extpose_rot_matrix( + cf, pose[0], pose[1], pose[2], pose[3]) + + activate_kalman_estimator(cf) + activate_high_level_commander(cf) + activate_mellinger_controller(cf) + duration = upload_trajectory(cf, trajectory_id, figure8) + print('The sequence is {:.1f} seconds long'.format(duration)) + reset_estimator(cf) + run_sequence(cf, trajectory_id, duration) + +qtm_wrapper.close() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/radio-test.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/radio-test.py index d4c90e28..9e4d811e 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/radio-test.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/radio-test.py @@ -8,8 +8,12 @@ It finally sets the Crazyflie channel back to default, plots link quality data, and offers good channel suggestion. - Better used when the Crazyflie2-nrf-firmware is compiled with bluetooth - disabled. + This script should be used on a Crazyflie with bluetooth disabled and RSSI + ack packet enabled to get RSSI feedback. To configure the Crazyflie in this + mode build the crazyflie2-nrf-firmware with + ```make BLE=0 CONFIG=-DRSSI_ACK_PACKET```. + See https://github.com/bitcraze/crazyflie-lib-python/issues/131 for more + informations. ''' import argparse diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/ramp.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/ramp.py index 63aae005..d5d9808d 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/ramp.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/ramp.py @@ -44,7 +44,7 @@ class MotorRampExample: def __init__(self, link_uri): """ Initialize and run the example with the specified link_uri """ - self._cf = Crazyflie() + self._cf = Crazyflie(rw_cache='./cache') self._cf.connected.add_callback(self._connected) self._cf.disconnected.add_callback(self._disconnected) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/read-ow.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/read-ow.py index 428d5f91..235e9eae 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/read-ow.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/read-ow.py @@ -79,6 +79,7 @@ class OWExample: def _data_updated(self, mem): print('Updated id={}'.format(mem.id)) + print('\tAddr : {}'.format(mem.addr)) print('\tType : {}'.format(mem.type)) print('\tSize : {}'.format(mem.size)) print('\tValid : {}'.format(mem.valid)) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/hl-commander-swarm.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/hl-commander-swarm.py new file mode 100644 index 00000000..c1685342 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/hl-commander-swarm.py @@ -0,0 +1,145 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# 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. +""" +Simple example of a swarm using the High level commander. + +The swarm takes off and flies a synchronous square shape before landing. +The trajectories are relative to the starting positions and the Crazyfles can +be at any position on the floor when the script is started. + +This example is intended to work with any absolute positioning system. +It aims at documenting how to use the High Level Commander together with +the Swarm class. +""" +import time + +import cflib.crtp +from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.swarm import CachedCfFactory +from cflib.crazyflie.swarm import Swarm +from cflib.crazyflie.syncLogger import SyncLogger + + +def wait_for_position_estimator(scf): + print('Waiting for estimator to find position...') + + log_config = LogConfig(name='Kalman Variance', period_in_ms=500) + log_config.add_variable('kalman.varPX', 'float') + log_config.add_variable('kalman.varPY', 'float') + log_config.add_variable('kalman.varPZ', 'float') + + var_y_history = [1000] * 10 + var_x_history = [1000] * 10 + var_z_history = [1000] * 10 + + threshold = 0.001 + + with SyncLogger(scf, log_config) as logger: + for log_entry in logger: + data = log_entry[1] + + var_x_history.append(data['kalman.varPX']) + var_x_history.pop(0) + var_y_history.append(data['kalman.varPY']) + var_y_history.pop(0) + var_z_history.append(data['kalman.varPZ']) + var_z_history.pop(0) + + min_x = min(var_x_history) + max_x = max(var_x_history) + min_y = min(var_y_history) + max_y = max(var_y_history) + min_z = min(var_z_history) + max_z = max(var_z_history) + + # print("{} {} {}". + # format(max_x - min_x, max_y - min_y, max_z - min_z)) + + if (max_x - min_x) < threshold and ( + max_y - min_y) < threshold and ( + max_z - min_z) < threshold: + break + + +def reset_estimator(scf): + cf = scf.cf + cf.param.set_value('kalman.resetEstimation', '1') + time.sleep(0.1) + cf.param.set_value('kalman.resetEstimation', '0') + wait_for_position_estimator(scf) + + +def activate_high_level_commander(scf): + scf.cf.param.set_value('commander.enHighLevel', '1') + + +def activate_mellinger_controller(scf, use_mellinger): + controller = 1 + if use_mellinger: + controller = 2 + scf.cf.param.set_value('stabilizer.controller', controller) + + +def run_shared_sequence(scf): + activate_mellinger_controller(scf, False) + + box_size = 1 + flight_time = 2 + + commander = scf.cf.high_level_commander + + commander.takeoff(1.0, 2.0) + time.sleep(3) + + commander.go_to(box_size, 0, 0, 0, flight_time, relative=True) + time.sleep(flight_time) + + commander.go_to(0, box_size, 0, 0, flight_time, relative=True) + time.sleep(flight_time) + + commander.go_to(-box_size, 0, 0, 0, flight_time, relative=True) + time.sleep(flight_time) + + commander.go_to(0, -box_size, 0, 0, flight_time, relative=True) + time.sleep(flight_time) + + commander.land(0.0, 2.0) + time.sleep(2) + + commander.stop() + + +uris = { + 'radio://0/30/2M/E7E7E7E711', + 'radio://0/30/2M/E7E7E7E712', + # Add more URIs if you want more copters in the swarm +} + +if __name__ == '__main__': + cflib.crtp.init_drivers(enable_debug_driver=False) + factory = CachedCfFactory(rw_cache='./cache') + with Swarm(uris, factory=factory) as swarm: + swarm.parallel_safe(activate_high_level_commander) + swarm.parallel_safe(reset_estimator) + swarm.parallel_safe(run_shared_sequence) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/swarmSequence.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/swarmSequence.py new file mode 100644 index 00000000..2b442987 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/swarmSequence.py @@ -0,0 +1,296 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2017-2018 Bitcraze AB +# +# Crazyflie Nano Quadcopter Client +# +# 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. +""" +Version of the AutonomousSequence.py example connecting to 10 Crazyflies. +The Crazyflies go straight up, hover a while and land but the code is fairly +generic and each Crazyflie has its own sequence of setpoints that it files +to. + +The layout of the positions: + x2 x1 x0 + +y3 10 4 + + ^ Y + | +y2 9 6 3 + | + +------> X + +y1 8 5 2 + + + +y0 7 1 + +""" +import time + +import cflib.crtp +from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.swarm import CachedCfFactory +from cflib.crazyflie.swarm import Swarm +from cflib.crazyflie.syncLogger import SyncLogger + +# Change uris and sequences according to your setup +URI1 = 'radio://0/70/2M/E7E7E7E701' +URI2 = 'radio://0/70/2M/E7E7E7E702' +URI3 = 'radio://0/70/2M/E7E7E7E703' +URI4 = 'radio://0/70/2M/E7E7E7E704' +URI5 = 'radio://0/70/2M/E7E7E7E705' +URI6 = 'radio://0/70/2M/E7E7E7E706' +URI7 = 'radio://0/70/2M/E7E7E7E707' +URI8 = 'radio://0/70/2M/E7E7E7E708' +URI9 = 'radio://0/70/2M/E7E7E7E709' +URI10 = 'radio://0/70/2M/E7E7E7E70A' + + +z0 = 0.4 +z = 1.0 + +x0 = 0.7 +x1 = 0 +x2 = -0.7 + +y0 = -1.0 +y1 = -0.4 +y2 = 0.4 +y3 = 1.0 + +# x y z time +sequence1 = [ + (x0, y0, z0, 3.0), + (x0, y0, z, 30.0), + (x0, y0, z0, 3.0), +] + +sequence2 = [ + (x0, y1, z0, 3.0), + (x0, y1, z, 30.0), + (x0, y1, z0, 3.0), +] + +sequence3 = [ + (x0, y2, z0, 3.0), + (x0, y2, z, 30.0), + (x0, y2, z0, 3.0), +] + +sequence4 = [ + (x0, y3, z0, 3.0), + (x0, y3, z, 30.0), + (x0, y3, z0, 3.0), +] + +sequence5 = [ + (x1, y1, z0, 3.0), + (x1, y1, z, 30.0), + (x1, y1, z0, 3.0), +] + +sequence6 = [ + (x1, y2, z0, 3.0), + (x1, y2, z, 30.0), + (x1, y2, z0, 3.0), +] + +sequence7 = [ + (x2, y0, z0, 3.0), + (x2, y0, z, 30.0), + (x2, y0, z0, 3.0), +] + +sequence8 = [ + (x2, y1, z0, 3.0), + (x2, y1, z, 30.0), + (x2, y1, z0, 3.0), +] + +sequence9 = [ + (x2, y2, z0, 3.0), + (x2, y2, z, 30.0), + (x2, y2, z0, 3.0), +] + +sequence10 = [ + (x2, y3, z0, 3.0), + (x2, y3, z, 30.0), + (x2, y3, z0, 3.0), +] + +seq_args = { + URI1: [sequence1], + URI2: [sequence2], + URI3: [sequence3], + URI4: [sequence4], + URI5: [sequence5], + URI6: [sequence6], + URI7: [sequence7], + URI8: [sequence8], + URI9: [sequence9], + URI10: [sequence10], +} + +# List of URIs, comment the one you do not want to fly +uris = { + URI1, + URI2, + URI3, + URI4, + URI5, + URI6, + URI7, + URI8, + URI9, + URI10 +} + + +def wait_for_position_estimator(scf): + print('Waiting for estimator to find position...') + + log_config = LogConfig(name='Kalman Variance', period_in_ms=500) + log_config.add_variable('kalman.varPX', 'float') + log_config.add_variable('kalman.varPY', 'float') + log_config.add_variable('kalman.varPZ', 'float') + + var_y_history = [1000] * 10 + var_x_history = [1000] * 10 + var_z_history = [1000] * 10 + + threshold = 0.001 + + with SyncLogger(scf, log_config) as logger: + for log_entry in logger: + data = log_entry[1] + + var_x_history.append(data['kalman.varPX']) + var_x_history.pop(0) + var_y_history.append(data['kalman.varPY']) + var_y_history.pop(0) + var_z_history.append(data['kalman.varPZ']) + var_z_history.pop(0) + + min_x = min(var_x_history) + max_x = max(var_x_history) + min_y = min(var_y_history) + max_y = max(var_y_history) + min_z = min(var_z_history) + max_z = max(var_z_history) + + # print("{} {} {}". + # format(max_x - min_x, max_y - min_y, max_z - min_z)) + + if (max_x - min_x) < threshold and ( + max_y - min_y) < threshold and ( + max_z - min_z) < threshold: + break + + +def wait_for_param_download(scf): + while not scf.cf.param.is_updated: + time.sleep(1.0) + print('Parameters downloaded for', scf.cf.link_uri) + + +def reset_estimator(scf): + cf = scf.cf + cf.param.set_value('kalman.resetEstimation', '1') + time.sleep(0.1) + cf.param.set_value('kalman.resetEstimation', '0') + + wait_for_position_estimator(cf) + + +def take_off(cf, position): + take_off_time = 1.0 + sleep_time = 0.1 + steps = int(take_off_time / sleep_time) + vz = position[2] / take_off_time + + print(vz) + + for i in range(steps): + cf.commander.send_velocity_world_setpoint(0, 0, vz, 0) + time.sleep(sleep_time) + + +def land(cf, position): + landing_time = 1.0 + sleep_time = 0.1 + steps = int(landing_time / sleep_time) + vz = -position[2] / landing_time + + print(vz) + + for _ in range(steps): + cf.commander.send_velocity_world_setpoint(0, 0, vz, 0) + time.sleep(sleep_time) + + cf.commander.send_stop_setpoint() + # Make sure that the last packet leaves before the link is closed + # since the message queue is not flushed before closing + time.sleep(0.1) + + +def run_sequence(scf, sequence): + try: + cf = scf.cf + + take_off(cf, sequence[0]) + for position in sequence: + print('Setting position {}'.format(position)) + end_time = time.time() + position[3] + while time.time() < end_time: + cf.commander.send_position_setpoint(position[0], + position[1], + position[2], 0) + time.sleep(0.1) + land(cf, sequence[-1]) + except Exception as e: + print(e) + + +if __name__ == '__main__': + # logging.basicConfig(level=logging.DEBUG) + cflib.crtp.init_drivers(enable_debug_driver=False) + + factory = CachedCfFactory(rw_cache='./cache') + with Swarm(uris, factory=factory) as swarm: + # If the copters are started in their correct positions this is + # probably not needed. The Kalman filter will have time to converge + # any way since it takes a while to start them all up and connect. We + # keep the code here to illustrate how to do it. + # swarm.parallel(reset_estimator) + + # The current values of all parameters are downloaded as a part of the + # connections sequence. Since we have 10 copters this is clogging up + # communication and we have to wait for it to finish before we start + # flying. + print('Waiting for parameters to be downloaded...') + swarm.parallel(wait_for_param_download) + + swarm.parallel(run_sequence, args_dict=seq_args) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/swarmSequenceCircle.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/swarmSequenceCircle.py similarity index 96% rename from dfall_ws/src/dfall_pkg/crazyradio/examples/swarmSequenceCircle.py rename to dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/swarmSequenceCircle.py index 70733f71..d0c63780 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/swarmSequenceCircle.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/swarmSequenceCircle.py @@ -42,6 +42,7 @@ import math import time import cflib.crtp +from cflib.crazyflie.swarm import CachedCfFactory from cflib.crazyflie.swarm import Swarm # Change uris according to your setup @@ -143,6 +144,7 @@ def run_sequence(scf, params): if __name__ == '__main__': cflib.crtp.init_drivers(enable_debug_driver=False) - with Swarm(uris) as swarm: + factory = CachedCfFactory(rw_cache='./cache') + with Swarm(uris, factory=factory) as swarm: swarm.parallel(reset_estimator) swarm.parallel(run_sequence, args_dict=params) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/synchronizedSequence.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/synchronizedSequence.py new file mode 100755 index 00000000..fc9e6b60 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/swarm/synchronizedSequence.py @@ -0,0 +1,250 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# 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. +""" +Simple example of a synchronized swarm choreography using the High level +commander. + +The swarm takes off and flies a synchronous choreography before landing. +The take-of is relative to the start position but the Goto are absolute. +The sequence contains a list of commands to be executed at each step. + +This example is intended to work with any absolute positioning system. +It aims at documenting how to use the High Level Commander together with +the Swarm class to achieve synchronous sequences. +""" +import threading +import time +from collections import namedtuple +from queue import Queue + +import cflib.crtp +from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.swarm import CachedCfFactory +from cflib.crazyflie.swarm import Swarm +from cflib.crazyflie.syncLogger import SyncLogger + +# Time for one step in second +STEP_TIME = 1 + +# Possible commands, all times are in seconds +Takeoff = namedtuple('Takeoff', ['height', 'time']) +Land = namedtuple('Land', ['time']) +Goto = namedtuple('Goto', ['x', 'y', 'z', 'time']) +# RGB [0-255], Intensity [0.0-1.0] +Ring = namedtuple('Ring', ['r', 'g', 'b', 'intensity', 'time']) +# Reserved for the control loop, do not use in sequence +Quit = namedtuple('Quit', []) + +uris = [ + 'radio://0/10/2M/E7E7E7E701', # cf_id 0, startup position [-0.5, -0.5] + 'radio://0/10/2M/E7E7E7E702', # cf_id 1, startup position [ 0, 0] + 'radio://0/10/2M/E7E7E7E703', # cf_id 3, startup position [0.5, 0.5] + # Add more URIs if you want more copters in the swarm +] + +sequence = [ + # Step, CF_id, action + (0, 0, Takeoff(0.5, 2)), + (0, 2, Takeoff(0.5, 2)), + + (1, 1, Takeoff(1.0, 2)), + + (2, 0, Goto(-0.5, -0.5, 0.5, 1)), + (2, 2, Goto(0.5, 0.5, 0.5, 1)), + + (3, 1, Goto(0, 0, 1, 1)), + + (4, 0, Ring(255, 255, 255, 0.2, 0)), + (4, 1, Ring(255, 0, 0, 0.2, 0)), + (4, 2, Ring(255, 255, 255, 0.2, 0)), + + (5, 0, Goto(0.5, -0.5, 0.5, 2)), + (5, 2, Goto(-0.5, 0.5, 0.5, 2)), + + (7, 0, Goto(0.5, 0.5, 0.5, 2)), + (7, 2, Goto(-0.5, -0.5, 0.5, 2)), + + (9, 0, Goto(-0.5, 0.5, 0.5, 2)), + (9, 2, Goto(0.5, -0.5, 0.5, 2)), + + (11, 0, Goto(-0.5, -0.5, 0.5, 2)), + (11, 2, Goto(0.5, 0.5, 0.5, 2)), + + (13, 0, Land(2)), + (13, 1, Land(2)), + (13, 2, Land(2)), + + (15, 0, Ring(0, 0, 0, 0, 5)), + (15, 1, Ring(0, 0, 0, 0, 5)), + (15, 2, Ring(0, 0, 0, 0, 5)), +] + + +def wait_for_position_estimator(scf): + print('Waiting for estimator to find position...') + + log_config = LogConfig(name='Kalman Variance', period_in_ms=500) + log_config.add_variable('kalman.varPX', 'float') + log_config.add_variable('kalman.varPY', 'float') + log_config.add_variable('kalman.varPZ', 'float') + + var_y_history = [1000] * 10 + var_x_history = [1000] * 10 + var_z_history = [1000] * 10 + + threshold = 0.001 + + with SyncLogger(scf, log_config) as logger: + for log_entry in logger: + data = log_entry[1] + + var_x_history.append(data['kalman.varPX']) + var_x_history.pop(0) + var_y_history.append(data['kalman.varPY']) + var_y_history.pop(0) + var_z_history.append(data['kalman.varPZ']) + var_z_history.pop(0) + + min_x = min(var_x_history) + max_x = max(var_x_history) + min_y = min(var_y_history) + max_y = max(var_y_history) + min_z = min(var_z_history) + max_z = max(var_z_history) + + # print("{} {} {}". + # format(max_x - min_x, max_y - min_y, max_z - min_z)) + + if (max_x - min_x) < threshold and ( + max_y - min_y) < threshold and ( + max_z - min_z) < threshold: + break + + +def reset_estimator(scf): + cf = scf.cf + cf.param.set_value('kalman.resetEstimation', '1') + time.sleep(0.1) + cf.param.set_value('kalman.resetEstimation', '0') + wait_for_position_estimator(scf) + + +def activate_high_level_commander(scf): + scf.cf.param.set_value('commander.enHighLevel', '1') + + +def activate_mellinger_controller(scf, use_mellinger): + controller = 1 + if use_mellinger: + controller = 2 + scf.cf.param.set_value('stabilizer.controller', str(controller)) + + +def set_ring_color(cf, r, g, b, intensity, time): + cf.param.set_value('ring.fadeTime', str(time)) + + r *= intensity + g *= intensity + b *= intensity + + color = (int(r) << 16) | (int(g) << 8) | int(b) + + cf.param.set_value('ring.fadeColor', str(color)) + + +def crazyflie_control(scf): + cf = scf.cf + control = controlQueues[uris.index(cf.link_uri)] + + activate_mellinger_controller(scf, True) + + commander = scf.cf.high_level_commander + + # Set fade to color effect and reset to Led-ring OFF + set_ring_color(cf, 0, 0, 0, 0, 0) + cf.param.set_value('ring.effect', '14') + + while True: + command = control.get() + if type(command) is Quit: + return + elif type(command) is Takeoff: + commander.takeoff(command.height, command.time) + elif type(command) is Land: + commander.land(0.0, command.time) + elif type(command) is Goto: + commander.go_to(command.x, command.y, command.z, 0, command.time) + elif type(command) is Ring: + set_ring_color(cf, command.r, command.g, command.b, + command.intensity, command.time) + pass + else: + print('Warning! unknown command {} for uri {}'.format(command, + cf.uri)) + + +def control_thread(): + pointer = 0 + step = 0 + stop = False + + while not stop: + print('Step {}:'.format(step)) + while sequence[pointer][0] <= step: + cf_id = sequence[pointer][1] + command = sequence[pointer][2] + + print(' - Running: {} on {}'.format(command, cf_id)) + controlQueues[cf_id].put(command) + pointer += 1 + + if pointer >= len(sequence): + print('Reaching the end of the sequence, stopping!') + stop = True + break + + step += 1 + time.sleep(STEP_TIME) + + for ctrl in controlQueues: + ctrl.put(Quit()) + + +if __name__ == '__main__': + controlQueues = [Queue() for _ in range(len(uris))] + + cflib.crtp.init_drivers(enable_debug_driver=False) + factory = CachedCfFactory(rw_cache='./cache') + with Swarm(uris, factory=factory) as swarm: + swarm.parallel_safe(activate_high_level_commander) + swarm.parallel_safe(reset_estimator) + + print('Starting sequence!') + + threading.Thread(target=control_thread).start() + + swarm.parallel_safe(crazyflie_control) + + time.sleep(1) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/examples/write-ow.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/write-ow.py index 9dc2a8f5..17ab60ee 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/examples/write-ow.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/examples/write-ow.py @@ -24,8 +24,12 @@ # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. """ -Simple example that connects to the first Crazyflie found, looks for -EEPROM memories and lists its contents. +This example connects to the first Crazyflie that it finds and writes to the +one wire memory. + +Note: this example will not work with the BLE version of the nRF51 firmware +(flashed on production units). +See https://github.com/bitcraze/crazyflie-clients-python/issues/166 """ import logging import sys @@ -40,11 +44,7 @@ from cflib.crazyflie.mem import OWElement logging.basicConfig(level=logging.ERROR) -class EEPROMExample: - """ - Simple example listing the EEPROMs found and lists its contents. - """ - +class WriteOwExample: def __init__(self, link_uri): """ Initialize and run the example with the specified link_uri """ @@ -136,6 +136,7 @@ if __name__ == '__main__': print('This example will not work with the BLE version of the nRF51' ' firmware (flashed on production units). See https://github.com' '/bitcraze/crazyflie-clients-python/issues/166') + # Initialize the low-level drivers (don't list the debug drivers) cflib.crtp.init_drivers(enable_debug_driver=False) # Scan for Crazyflies and use the first one found @@ -146,7 +147,7 @@ if __name__ == '__main__': print(i[0]) if len(available) > 0: - le = EEPROMExample(available[0][0]) + le = WriteOwExample(available[0][0]) else: print('No Crazyflies found, cannot run example') diff --git a/dfall_ws/src/dfall_pkg/crazyradio/lpslib/lopoanchor.py b/dfall_ws/src/dfall_pkg/crazyradio/lpslib/lopoanchor.py index aa7fb4da..e07d7f12 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/lpslib/lopoanchor.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/lpslib/lopoanchor.py @@ -30,10 +30,15 @@ import struct class LoPoAnchor(): LPP_TYPE_POSITION = 1 LPP_TYPE_REBOOT = 2 + LPP_TYPE_MODE = 3 REBOOT_TO_BOOTLOADER = 0 REBOOT_TO_FIRMWARE = 1 + MODE_TWR = 1 + MODE_TDOA = 2 # TDoA 2 + MODE_TDOA3 = 3 + def __init__(self, crazyflie): """ :param crazyflie: A crazyflie object to be used as a bridge to the LoPo @@ -57,3 +62,11 @@ class LoPoAnchor(): def reboot(self, anchor_id, mode): data = struct.pack('<BB', LoPoAnchor.LPP_TYPE_REBOOT, mode) self.crazyflie.loc.send_short_lpp_packet(anchor_id, data) + + def set_mode(self, anchor_id, mode): + """ + Send a packet to set the anchor mode. If the anchor receive the packet, + it will change mode and resets. + """ + data = struct.pack('<BB', LoPoAnchor.LPP_TYPE_MODE, mode) + self.crazyflie.loc.send_short_lpp_packet(anchor_id, data) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/setup.py b/dfall_ws/src/dfall_pkg/crazyradio/setup.py index 878fc102..ee6f22f1 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/setup.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/setup.py @@ -4,7 +4,7 @@ from setuptools import setup setup( name='cflib', - version='0.1.3', + version='0.1.10', packages=find_packages(exclude=['examples', 'tests']), description='Crazyflie python driver', diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/__init__.py similarity index 100% rename from dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/__init__.py rename to dfall_ws/src/dfall_pkg/crazyradio/sys_test/__init__.py diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/__init__.py similarity index 85% rename from dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/__init__.py rename to dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/__init__.py index f0fd2d73..c68f60ff 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/__init__.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/__init__.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python # -*- coding: utf-8 -*- # # || ____ _ __ @@ -7,9 +6,7 @@ # +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ # || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ # -# Copyright (C) 2011-2013 Bitcraze AB -# -# Crazyflie Nano Quadcopter Client +# Copyright (C) 2019 Bitcraze AB # # This program is free software; you can redistribute it and/or # modify it under the terms of the GNU General Public License @@ -24,6 +21,3 @@ # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. -""" -Drivers for the link interfaces that can be used by CRTP. -""" diff --git a/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/cload_all_nrf.sh b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/cload_all_nrf.sh new file mode 100755 index 00000000..7feabb0e --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/cload_all_nrf.sh @@ -0,0 +1,14 @@ +#!/usr/bin/env bash + +file=$1 + +python3 -m cfloader flash $file nrf51-fw -w radio://0/42/2M/E7E7E74201 +python3 -m cfloader flash $file nrf51-fw -w radio://0/42/2M/E7E7E74202 +python3 -m cfloader flash $file nrf51-fw -w radio://0/42/2M/E7E7E74203 +python3 -m cfloader flash $file nrf51-fw -w radio://0/42/2M/E7E7E74204 +python3 -m cfloader flash $file nrf51-fw -w radio://0/42/2M/E7E7E74205 +python3 -m cfloader flash $file nrf51-fw -w radio://0/42/2M/E7E7E74206 +python3 -m cfloader flash $file nrf51-fw -w radio://0/42/2M/E7E7E74207 +python3 -m cfloader flash $file nrf51-fw -w radio://0/42/2M/E7E7E74208 +python3 -m cfloader flash $file nrf51-fw -w radio://0/42/2M/E7E7E74209 +python3 -m cfloader flash $file nrf51-fw -w radio://0/42/2M/E7E7E7420A diff --git a/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/cload_all_stm.sh b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/cload_all_stm.sh new file mode 100755 index 00000000..01f837f0 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/cload_all_stm.sh @@ -0,0 +1,14 @@ +#!/usr/bin/env bash + +file=$1 + +python3 -m cfloader flash $file stm32-fw -w radio://0/42/2M/E7E7E74201 +python3 -m cfloader flash $file stm32-fw -w radio://0/42/2M/E7E7E74202 +python3 -m cfloader flash $file stm32-fw -w radio://0/42/2M/E7E7E74203 +python3 -m cfloader flash $file stm32-fw -w radio://0/42/2M/E7E7E74204 +python3 -m cfloader flash $file stm32-fw -w radio://0/42/2M/E7E7E74205 +python3 -m cfloader flash $file stm32-fw -w radio://0/42/2M/E7E7E74206 +python3 -m cfloader flash $file stm32-fw -w radio://0/42/2M/E7E7E74207 +python3 -m cfloader flash $file stm32-fw -w radio://0/42/2M/E7E7E74208 +python3 -m cfloader flash $file stm32-fw -w radio://0/42/2M/E7E7E74209 +python3 -m cfloader flash $file stm32-fw -w radio://0/42/2M/E7E7E7420A diff --git a/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/rig_support.py b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/rig_support.py new file mode 100644 index 00000000..9fec7a73 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/rig_support.py @@ -0,0 +1,77 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# 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. +import time + +from cflib.crtp import RadioDriver +from cflib.drivers.crazyradio import Crazyradio + + +class RigSupport: + def __init__(self): + self.all_uris = [ + 'radio://0/42/2M/E7E7E74201', + 'radio://0/42/2M/E7E7E74202', + 'radio://0/42/2M/E7E7E74203', + 'radio://0/42/2M/E7E7E74204', + 'radio://0/42/2M/E7E7E74205', + 'radio://0/42/2M/E7E7E74206', + 'radio://0/42/2M/E7E7E74207', + 'radio://0/42/2M/E7E7E74208', + 'radio://0/42/2M/E7E7E74209', + 'radio://0/42/2M/E7E7E7420A', + ] + + def restart_devices(self, uris): + def send_packets(uris, value, description): + for uri in uris: + devid, channel, datarate, address = RadioDriver.parse_uri(uri) + radio.set_channel(channel) + radio.set_data_rate(datarate) + radio.set_address(address) + + received_packet = False + for i in range(10): + result = radio.send_packet((0xf3, 0xfe, value)) + if result.ack is True: + received_packet = True + # if i > 0: + # print('Lost packets', i, uri) + break + + if not received_packet: + raise Exception('Failed to turn device {}, for {}'. + format(description, uri)) + + print('Restarting devices') + + BOOTLOADER_CMD_SYSOFF = 0x02 + BOOTLOADER_CMD_SYSON = 0x03 + + radio = Crazyradio() + send_packets(uris, BOOTLOADER_CMD_SYSOFF, 'off') + send_packets(uris, BOOTLOADER_CMD_SYSON, 'on') + + # Wait for devices to boot + time.sleep(8) + radio.close() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_connection.py b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_connection.py new file mode 100644 index 00000000..14c4b211 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_connection.py @@ -0,0 +1,114 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# 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. +import time +import unittest + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.swarm import CachedCfFactory +from cflib.crazyflie.swarm import Swarm +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from sys_test.swarm_test_rig.rig_support import RigSupport + + +class TestConnection(unittest.TestCase): + def setUp(self): + cflib.crtp.init_drivers(enable_debug_driver=False) + self.test_rig_support = RigSupport() + + def test_that_connection_time_scales_with_more_devices_without_cache(self): + # Fixture + self.test_rig_support.restart_devices(self.test_rig_support.all_uris) + + EXPECTED_CONNECTION_TIME = 5 + + for nr_of_devices in range(1, len(self.test_rig_support.all_uris)): + # Test + uris = self.test_rig_support.all_uris[:nr_of_devices] + + start_time = time.time() + with Swarm(uris): + connected_time = time.time() + + actual = connected_time - start_time + max_expected = EXPECTED_CONNECTION_TIME * nr_of_devices + print('Connection time for', nr_of_devices, ':', actual, + ', per device:', actual / nr_of_devices) + + # Assert + self.assertLess(actual, max_expected) + + def test_that_connection_time_scales_with_more_devices_with_cache(self): + # Fixture + self.test_rig_support.restart_devices(self.test_rig_support.all_uris) + + # Fill caches first by connecting to all devices + factory = CachedCfFactory(rw_cache='./cache') + with Swarm(self.test_rig_support.all_uris, factory=factory): + pass + + EXPECTED_CONNECTION_TIME = 1.5 + + for nr_of_devices in range(1, len(self.test_rig_support.all_uris)): + # Test + uris = self.test_rig_support.all_uris[:nr_of_devices] + + start_time = time.time() + with Swarm(uris, factory=factory): + connected_time = time.time() + + actual = connected_time - start_time + max_expected = EXPECTED_CONNECTION_TIME * nr_of_devices + print('Connection time for', nr_of_devices, ':', actual, + ', per device:', actual / nr_of_devices) + + # Assert + self.assertLess(actual, max_expected) + + def test_that_all_devices_are_restarted(self): + # Fixture + uris = self.test_rig_support.all_uris + + # Test + # Assert + self.test_rig_support.restart_devices(uris) + + def test_that_all_devices_are_restarted_multiple_times(self): + # Fixture + uris = self.test_rig_support.all_uris + + # Test + # Assert + for i in range(10): + self.test_rig_support.restart_devices(uris) + + def test_that_the_same_cf_object_can_be_connected_multiple_times(self): + # Fixture + self.test_rig_support.restart_devices(self.test_rig_support.all_uris) + cf = Crazyflie(rw_cache='./cache') + + # Test + for uri in self.test_rig_support.all_uris: + with SyncCrazyflie(uri, cf=cf): + pass diff --git a/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_logging.py b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_logging.py new file mode 100644 index 00000000..839058cc --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_logging.py @@ -0,0 +1,73 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# 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. +import unittest + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.swarm import CachedCfFactory +from cflib.crazyflie.swarm import Swarm +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from cflib.crazyflie.syncLogger import SyncLogger +from sys_test.swarm_test_rig.rig_support import RigSupport + + +class TestLogging(unittest.TestCase): + def setUp(self): + cflib.crtp.init_drivers(enable_debug_driver=False) + self.test_rig_support = RigSupport() + + def test_that_requested_logging_is_received_properly_from_one_cf(self): + # Fixture + uri = self.test_rig_support.all_uris[0] + self.test_rig_support.restart_devices([uri]) + cf = Crazyflie(rw_cache='./cache') + + # Test and Assert + with SyncCrazyflie(uri, cf=cf) as scf: + self.assert_add_logging_and_get_non_zero_value(scf) + + def test_that_requested_logging_is_received_properly_from_all_cfs(self): + # Fixture + uris = self.test_rig_support.all_uris + self.test_rig_support.restart_devices(uris) + factory = CachedCfFactory(rw_cache='./cache') + + # Test and Assert + with Swarm(uris, factory=factory) as swarm: + swarm.parallel_safe(self.assert_add_logging_and_get_non_zero_value) + + def assert_add_logging_and_get_non_zero_value(self, scf): + log_name = 'stabilizer.roll' + expected = 0.0 + + lg_conf = LogConfig(name='SysTest', period_in_ms=10) + lg_conf.add_variable(log_name, 'float') + + with SyncLogger(scf, lg_conf) as logger: + for log_entry in logger: + actual = log_entry[1][log_name] + break + + self.assertNotAlmostEqual(expected, actual, places=4) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_memory_map.py b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_memory_map.py new file mode 100644 index 00000000..873b8bfc --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_memory_map.py @@ -0,0 +1,110 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# 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. +import time +import unittest + +import cflib.crtp +from cflib.crazyflie import Crazyflie +from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.mem import MemoryElement +from cflib.crazyflie.swarm import CachedCfFactory +from cflib.crazyflie.swarm import Swarm +from cflib.crazyflie.syncCrazyflie import SyncCrazyflie +from cflib.crazyflie.syncLogger import SyncLogger +from sys_test.swarm_test_rig.rig_support import RigSupport + + +class TestMemoryMapping(unittest.TestCase): + def setUp(self): + cflib.crtp.init_drivers(enable_debug_driver=False) + self.test_rig_support = RigSupport() + + def test_memory_mapping_with_one_cf(self): + # Fixture + uri = self.test_rig_support.all_uris[0] + self.test_rig_support.restart_devices([uri]) + cf = Crazyflie(rw_cache='./cache') + + # Test and Assert + with SyncCrazyflie(uri, cf=cf) as scf: + self.assert_memory_mapping(scf) + + def test_memory_mapping_with_all_cfs(self): + # Fixture + uris = self.test_rig_support.all_uris + self.test_rig_support.restart_devices(uris) + factory = CachedCfFactory(rw_cache='./cache') + + # Test and Assert + with Swarm(uris, factory=factory) as swarm: + swarm.parallel_safe(self.assert_memory_mapping) + + def test_memory_mapping_with_reuse_of_cf_object(self): + # Fixture + uri = self.test_rig_support.all_uris[0] + self.test_rig_support.restart_devices([uri]) + cf = Crazyflie(rw_cache='./cache') + + # Test and Assert + for connections in range(10): + with SyncCrazyflie(uri, cf=cf) as scf: + for mem_ops in range(5): + self.assert_memory_mapping(scf) + + # Utils + + def assert_memory_mapping(self, scf): + mems = scf.cf.mem.get_mems(MemoryElement.TYPE_MEMORY_TESTER) + count = len(mems) + self.assertEqual(1, count, 'unexpected number of memories found') + + self.verify_reading_memory_data(mems) + self.verify_writing_memory_data(mems, scf) + + def verify_writing_memory_data(self, mems, scf): + self.wrote_data = False + scf.cf.param.set_value('memTst.resetW', '1') + time.sleep(0.1) + mems[0].write_data(5, 1000, self._data_written) + while not self.wrote_data: + time.sleep(1) + log_conf = LogConfig(name='memtester', period_in_ms=100) + log_conf.add_variable('memTst.errCntW', 'uint32_t') + with SyncLogger(scf, log_conf) as logger: + for log_entry in logger: + errorCount = log_entry[1]['memTst.errCntW'] + self.assertEqual(0, errorCount) + break + + def verify_reading_memory_data(self, mems): + self.got_data = False + mems[0].read_data(5, 1000, self._data_read) + while not self.got_data: + time.sleep(1) + + def _data_read(self, mem): + self.got_data = True + + def _data_written(self, mem, address): + self.wrote_data = True diff --git a/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_response_time.py b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_response_time.py new file mode 100644 index 00000000..159e2c14 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/sys_test/swarm_test_rig/test_response_time.py @@ -0,0 +1,144 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2019 Bitcraze AB +# +# 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. +import time +import unittest + +import cflib.crtp +from cflib.crtp.crtpstack import CRTPPacket +from cflib.crtp.crtpstack import CRTPPort +from sys_test.swarm_test_rig.rig_support import RigSupport + + +class TestResponseTime(unittest.TestCase): + ECHO = 0 + + def setUp(self): + cflib.crtp.init_drivers(enable_debug_driver=False) + self.test_rig_support = RigSupport() + + self.links = [] + + def tearDown(self): + for link in self.links: + link.close() + self.links = [] + + def test_response_time_to_one_cf(self): + # Fixture + uri = self.test_rig_support.all_uris[0] + self.test_rig_support.restart_devices([uri]) + link = self.connect_link(uri) + seq_nr = 47 + expected_max_response_time = 0.01 + + # Test + time_send_echo = time.time() + self.request_echo_with_seq_nr(link, seq_nr) + response_timestamps = self.assert_wait_for_all_seq_nrs([link], seq_nr) + response_time = response_timestamps[uri] - time_send_echo + + # Assert + self.assertLess(response_time, expected_max_response_time) + + def test_response_time_to_all_cfs(self): + # Fixture + uris = self.test_rig_support.all_uris + self.test_rig_support.restart_devices(uris) + + for uri in uris: + self.connect_link(uri) + + seq_nr = 47 + expected_max_response_time = 0.1 + expected_mean_response_time = 0.05 + + # Test + time_send_echo = time.time() + for link in self.links: + self.request_echo_with_seq_nr(link, seq_nr) + + response_timestamps = self.assert_wait_for_all_seq_nrs( + self.links, seq_nr) + + # Assert + response_times = {} + for uri, response_time in response_timestamps.items(): + response_times[uri] = response_time - time_send_echo + + times = response_times.values() + max_time = max(times) + mean_time = float(sum(times)) / len(times) + + # print(max_time, mean_time, times) + self.assertLess(max_time, expected_max_response_time) + self.assertLess(mean_time, expected_mean_response_time) + + def request_echo_with_seq_nr(self, link, seq_nr): + pk = CRTPPacket() + pk.set_header(CRTPPort.LINKCTRL, self.ECHO) + pk.data = (seq_nr,) + link.send_packet(pk) + + def assert_wait_for_all_seq_nrs(self, links, seq_nr, timeout=1): + NO_BLOCKING = -1 + + time_end = time.time() + timeout + response_timestamps = {} + while time.time() < time_end: + for link in links: + if link.uri not in response_timestamps: + response = link.receive_packet(time=NO_BLOCKING) + if self._is_response_correct_seq_nr(response, seq_nr): + response_timestamps[link.uri] = time.time() + + if len(response_timestamps) == len(self.links): + return response_timestamps + + time.sleep(0.001) + + self.fail('Time out while waiting for seq nrs.') + + def _is_response_correct_seq_nr(self, response, seq_nr): + if response is not None: + if response._get_channel() == self.ECHO and \ + response._get_port() == CRTPPort.LINKCTRL: + received_seq = response._get_data_t()[0] + if received_seq == seq_nr: + return True + + return False + + def connect_link(self, uri): + link = cflib.crtp.get_link_driver(uri, self._link_quality_cb, + self._link_error_cb) + self.assertIsNotNone(link) + self.links.append(link) + + return link + + def _link_quality_cb(self, percentage): + pass + + def _link_error_cb(self, errmsg): + self.fail(errmsg) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncCrazyflie.py b/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncCrazyflie.py index 9f84a897..22e23374 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncCrazyflie.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncCrazyflie.py @@ -91,6 +91,7 @@ class SyncCrazyflieTest(unittest.TestCase): # Assert self.assertEqual(expected, actual) + self._assertAllCallbacksAreRemoved() def test_open_link_of_already_open_link_raises_exception(self): # Fixture @@ -111,6 +112,7 @@ class SyncCrazyflieTest(unittest.TestCase): # Assert self.cf_mock.close_link.assert_called_once_with() self.assertFalse(self.sut.is_link_open()) + self._assertAllCallbacksAreRemoved() def test_close_link_that_is_not_open(self): # Fixture @@ -132,6 +134,7 @@ class SyncCrazyflieTest(unittest.TestCase): # Assert self.assertFalse(self.sut.is_link_open()) + self._assertAllCallbacksAreRemoved() def test_open_close_with_context_mangement(self): # Fixture @@ -142,3 +145,9 @@ class SyncCrazyflieTest(unittest.TestCase): # Assert self.cf_mock.close_link.assert_called_once_with() + self._assertAllCallbacksAreRemoved() + + def _assertAllCallbacksAreRemoved(self): + self.assertEqual(0, len(self.cf_mock.connected.callbacks)) + self.assertEqual(0, len(self.cf_mock.connection_failed.callbacks)) + self.assertEqual(0, len(self.cf_mock.disconnected.callbacks)) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncLogger.py b/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncLogger.py index 92ec918d..64d2baee 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncLogger.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncLogger.py @@ -6,7 +6,7 @@ # +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ # || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ # -# Copyright (C) 2016 Bitcraze AB +# Copyright (C) 2016-2020 Bitcraze AB # # Crazyflie Nano Quadcopter Client # @@ -36,8 +36,10 @@ from cflib.utils.callbacks import Caller if sys.version_info < (3, 3): from mock import MagicMock + from mock import call else: from unittest.mock import MagicMock + from unittest.mock import call class SyncLoggerTest(unittest.TestCase): @@ -52,7 +54,12 @@ class SyncLoggerTest(unittest.TestCase): self.log_config_mock = MagicMock(spec=LogConfig) self.log_config_mock.data_received_cb = Caller() + self.log_config_mock2 = MagicMock(spec=LogConfig) + self.log_config_mock2.data_received_cb = Caller() + self.sut = SyncLogger(self.cf_mock, self.log_config_mock) + self.sut_multi = SyncLogger( + self.cf_mock, [self.log_config_mock, self.log_config_mock2]) def test_that_log_configuration_is_added_on_connect(self): # Fixture @@ -63,6 +70,18 @@ class SyncLoggerTest(unittest.TestCase): # Assert self.log_mock.add_config.assert_called_once_with(self.log_config_mock) + def test_that_multiple_log_configurations_are_added_on_connect(self): + # Fixture + + # Test + self.sut_multi.connect() + + # Assert + self.log_mock.add_config.assert_has_calls([ + call(self.log_config_mock), + call(self.log_config_mock2) + ]) + def test_that_logging_is_started_on_connect(self): # Fixture @@ -72,6 +91,16 @@ class SyncLoggerTest(unittest.TestCase): # Assert self.log_config_mock.start.assert_called_once_with() + def test_that_logging_is_started_on_connect_for_multiple_log_confs(self): + # Fixture + + # Test + self.sut_multi.connect() + + # Assert + self.log_config_mock.start.assert_called_once_with() + self.log_config_mock2.start.assert_called_once_with() + def test_connection_status_after_connect(self): # Fixture self.sut.connect() @@ -105,6 +134,20 @@ class SyncLoggerTest(unittest.TestCase): self.log_config_mock.stop.assert_called_once_with() self.log_config_mock.delete.assert_called_once_with() + def test_that_multiple_log_configs_are_stopped_on_disconnect(self): + # Fixture + self.sut_multi.connect() + + # Test + self.sut_multi.disconnect() + + # Assert + self.log_config_mock.stop.assert_called_once_with() + self.log_config_mock.delete.assert_called_once_with() + + self.log_config_mock2.stop.assert_called_once_with() + self.log_config_mock2.delete.assert_called_once_with() + def test_that_data_is_received(self): # Fixture self.sut.connect() @@ -115,7 +158,10 @@ class SyncLoggerTest(unittest.TestCase): ).trigger() # Test - actual = self.sut.__next__() + actual = None + for log_block in self.sut: + actual = log_block + break # Assert self.assertEqual(expected, actual) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/test/positioning/__init__.py similarity index 100% rename from dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/__init__.py rename to dfall_ws/src/dfall_pkg/crazyradio/test/positioning/__init__.py diff --git a/dfall_ws/src/dfall_pkg/crazyradio/test/positioning/test_motion_commander.py b/dfall_ws/src/dfall_pkg/crazyradio/test/positioning/test_motion_commander.py new file mode 100644 index 00000000..7fd3d7ce --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/test/positioning/test_motion_commander.py @@ -0,0 +1,491 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2017 Bitcraze AB +# +# 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. +import math +import sys +import unittest + +from cflib.crazyflie import Commander +from cflib.crazyflie import Crazyflie +from cflib.crazyflie import Param +from cflib.positioning.motion_commander import _SetPointThread +from cflib.positioning.motion_commander import MotionCommander + +if sys.version_info < (3, 3): + from mock import MagicMock, patch, call +else: + from unittest.mock import MagicMock, patch, call + + +@patch('time.sleep') +@patch('cflib.positioning.motion_commander._SetPointThread', + return_value=MagicMock(spec=_SetPointThread)) +class TestMotionCommander(unittest.TestCase): + def setUp(self): + self.commander_mock = MagicMock(spec=Commander) + self.param_mock = MagicMock(spec=Param) + self.cf_mock = MagicMock(spec=Crazyflie) + self.cf_mock.commander = self.commander_mock + self.cf_mock.param = self.param_mock + self.cf_mock.is_connected.return_value = True + + self.sut = MotionCommander(self.cf_mock) + + def test_that_the_estimator_is_reset_on_take_off( + self, _SetPointThread_mock, sleep_mock): + # Fixture + + # Test + self.sut.take_off() + + # Assert + self.param_mock.set_value.assert_has_calls([ + call('kalman.resetEstimation', '1'), + call('kalman.resetEstimation', '0') + ]) + + def test_that_take_off_raises_exception_if_not_connected( + self, _SetPointThread_mock, sleep_mock): + # Fixture + self.cf_mock.is_connected.return_value = False + + # Test + # Assert + with self.assertRaises(Exception): + self.sut.take_off() + + def test_that_take_off_raises_exception_when_already_flying( + self, _SetPointThread_mock, sleep_mock): + # Fixture + self.sut.take_off() + + # Test + # Assert + with self.assertRaises(Exception): + self.sut.take_off() + + def test_that_it_goes_up_on_take_off( + self, _SetPointThread_mock, sleep_mock): + # Fixture + thread_mock = _SetPointThread_mock() + + # Test + self.sut.take_off(height=0.4, velocity=0.5) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(0.0, 0.0, 0.5, 0.0), + call(0.0, 0.0, 0.0, 0.0) + ]) + sleep_mock.assert_called_with(0.4 / 0.5) + + def test_that_it_goes_up_to_default_height( + self, _SetPointThread_mock, sleep_mock): + # Fixture + thread_mock = _SetPointThread_mock() + sut = MotionCommander(self.cf_mock, default_height=0.4) + + # Test + sut.take_off(velocity=0.6) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(0.0, 0.0, 0.6, 0.0), + call(0.0, 0.0, 0.0, 0.0) + ]) + sleep_mock.assert_called_with(0.4 / 0.6) + + def test_that_the_thread_is_started_on_takeoff( + self, _SetPointThread_mock, sleep_mock): + # Fixture + thread_mock = _SetPointThread_mock() + + # Test + self.sut.take_off() + + # Assert + thread_mock.start.assert_called_with() + + def test_that_it_goes_down_on_landing( + self, _SetPointThread_mock, sleep_mock): + # Fixture + thread_mock = _SetPointThread_mock() + thread_mock.get_height.return_value = 0.4 + + self.sut.take_off() + thread_mock.reset_mock() + + # Test + self.sut.land(velocity=0.5) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(0.0, 0.0, -0.5, 0.0), + call(0.0, 0.0, 0.0, 0.0) + ]) + sleep_mock.assert_called_with(0.4 / 0.5) + + def test_that_it_takes_off_and_lands_as_context_manager( + self, _SetPointThread_mock, sleep_mock): + # Fixture + thread_mock = _SetPointThread_mock() + thread_mock.reset_mock() + + thread_mock.get_height.return_value = 0.3 + + # Test + with self.sut: + pass + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(0.0, 0.0, 0.2, 0.0), + call(0.0, 0.0, 0.0, 0.0), + call(0.0, 0.0, -0.2, 0.0), + call(0.0, 0.0, 0.0, 0.0) + ]) + sleep_mock.assert_called_with(0.3 / 0.2) + sleep_mock.assert_called_with(0.3 / 0.2) + + def test_that_it_starts_moving_multi_dimensional( + self, _SetPointThread_mock, sleep_mock): + # Fixture + thread_mock = _SetPointThread_mock() + self.sut.take_off() + thread_mock.reset_mock() + + # Test + self.sut.start_linear_motion(0.1, 0.2, 0.3) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(0.1, 0.2, 0.3, 0.0), + ]) + + def test_that_it_starts_moving( + self, _SetPointThread_mock, sleep_mock): + # Fixture + self.sut.take_off() + vel = 0.3 + + data = [ + [self.sut.start_forward, (vel, 0.0, 0.0, 0.0)], + [self.sut.start_back, (-vel, 0.0, 0.0, 0.0)], + [self.sut.start_left, (0.0, vel, 0.0, 0.0)], + [self.sut.start_right, (0.0, -vel, 0.0, 0.0)], + [self.sut.start_up, (0.0, 0.0, vel, 0.0)], + [self.sut.start_down, (0.0, 0.0, -vel, 0.0)], + ] + # Test + # Assert + for line in data: + self._verify_start_motion(line[0], vel, line[1], + _SetPointThread_mock) + + def test_that_it_moves_multi_dimensional_distance( + self, _SetPointThread_mock, sleep_mock): + # Fixture + thread_mock = _SetPointThread_mock() + x = 0.1 + y = 0.2 + z = 0.3 + vel = 0.2 + distance = math.sqrt(x * x + y * y + z * z) + expected_time = distance / vel + expected_vel_x = vel * x / distance + expected_vel_y = vel * y / distance + expected_vel_z = vel * z / distance + + self.sut.take_off() + thread_mock.reset_mock() + sleep_mock.reset_mock() + + # Test + self.sut.move_distance(x, y, z) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(expected_vel_x, expected_vel_y, expected_vel_z, 0.0), + ]) + sleep_mock.assert_called_with(expected_time) + + def test_that_it_moves(self, _SetPointThread_mock, sleep_mock): + # Fixture + vel = 0.3 + self.sut.take_off() + + data = [ + [self.sut.forward, (vel, 0.0, 0.0, 0.0)], + [self.sut.back, (-vel, 0.0, 0.0, 0.0)], + [self.sut.left, (0.0, vel, 0.0, 0.0)], + [self.sut.right, (0.0, -vel, 0.0, 0.0)], + [self.sut.up, (0.0, 0.0, vel, 0.0)], + [self.sut.down, (0.0, 0.0, -vel, 0.0)], + ] + # Test + # Assert + for test in data: + self._verify_move(test[0], vel, test[1], + _SetPointThread_mock, sleep_mock) + + def test_that_it_starts_turn_right(self, _SetPointThread_mock, sleep_mock): + # Fixture + rate = 20 + thread_mock = _SetPointThread_mock() + self.sut.take_off() + thread_mock.reset_mock() + + # Test + self.sut.start_turn_right(rate) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(0.0, 0.0, 0.0, rate), + ]) + + def test_that_it_starts_turn_left(self, _SetPointThread_mock, sleep_mock): + # Fixture + rate = 20 + thread_mock = _SetPointThread_mock() + self.sut.take_off() + thread_mock.reset_mock() + + # Test + self.sut.start_turn_left(rate) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(0.0, 0.0, 0.0, -rate), + ]) + + def test_that_it_starts_circle_right( + self, _SetPointThread_mock, sleep_mock): + # Fixture + velocity = 0.5 + radius = 0.9 + expected_rate = 360 * velocity / (2 * radius * math.pi) + + thread_mock = _SetPointThread_mock() + self.sut.take_off() + thread_mock.reset_mock() + + # Test + self.sut.start_circle_right(radius, velocity=velocity) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(velocity, 0.0, 0.0, expected_rate), + ]) + + def test_that_it_starts_circle_left( + self, _SetPointThread_mock, sleep_mock): + # Fixture + velocity = 0.5 + radius = 0.9 + expected_rate = 360 * velocity / (2 * radius * math.pi) + + thread_mock = _SetPointThread_mock() + self.sut.take_off() + thread_mock.reset_mock() + + # Test + self.sut.start_circle_left(radius, velocity=velocity) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(velocity, 0.0, 0.0, -expected_rate), + ]) + + def test_that_it_turns_right(self, _SetPointThread_mock, sleep_mock): + # Fixture + rate = 20 + angle = 45 + turn_time = angle / rate + thread_mock = _SetPointThread_mock() + self.sut.take_off() + thread_mock.reset_mock() + + # Test + self.sut.turn_right(angle, rate=rate) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(0.0, 0.0, 0.0, rate), + call(0.0, 0.0, 0.0, 0.0) + ]) + sleep_mock.assert_called_with(turn_time) + + def test_that_it_turns_left(self, _SetPointThread_mock, sleep_mock): + # Fixture + rate = 20 + angle = 45 + turn_time = angle / rate + thread_mock = _SetPointThread_mock() + self.sut.take_off() + thread_mock.reset_mock() + + # Test + self.sut.turn_left(angle, rate=rate) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(0.0, 0.0, 0.0, -rate), + call(0.0, 0.0, 0.0, 0.0) + ]) + sleep_mock.assert_called_with(turn_time) + + def test_that_it_circles_right(self, _SetPointThread_mock, sleep_mock): + # Fixture + radius = 0.7 + velocity = 0.3 + angle = 45 + + distance = 2 * radius * math.pi * angle / 360.0 + turn_time = distance / velocity + rate = angle / turn_time + + thread_mock = _SetPointThread_mock() + self.sut.take_off() + thread_mock.reset_mock() + + # Test + self.sut.circle_right(radius, velocity, angle) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(velocity, 0.0, 0.0, rate), + call(0.0, 0.0, 0.0, 0.0) + ]) + sleep_mock.assert_called_with(turn_time) + + def test_that_it_circles_left(self, _SetPointThread_mock, sleep_mock): + # Fixture + radius = 0.7 + velocity = 0.3 + angle = 45 + + distance = 2 * radius * math.pi * angle / 360.0 + turn_time = distance / velocity + rate = angle / turn_time + + thread_mock = _SetPointThread_mock() + self.sut.take_off() + thread_mock.reset_mock() + + # Test + self.sut.circle_left(radius, velocity, angle) + + # Assert + thread_mock.set_vel_setpoint.assert_has_calls([ + call(velocity, 0.0, 0.0, -rate), + call(0.0, 0.0, 0.0, 0.0) + ]) + sleep_mock.assert_called_with(turn_time) + + ###################################################################### + + def _verify_start_motion(self, function_under_test, velocity, expected, + _SetPointThread_mock): + # Fixture + thread_mock = _SetPointThread_mock() + thread_mock.reset_mock() + + # Test + function_under_test(velocity=velocity) + + # Assert + try: + thread_mock.set_vel_setpoint.assert_has_calls([ + call(*expected), + ]) + except AssertionError as e: + self._eprint('Failed when testing function ' + + function_under_test.__name__) + raise e + + def _verify_move(self, function_under_test, velocity, expected, + _SetPointThread_mock, sleep_mock): + # Fixture + thread_mock = _SetPointThread_mock() + + distance = 1.2 + expected_time = distance / velocity + + thread_mock.reset_mock() + sleep_mock.reset_mock() + + # Test + function_under_test(distance, velocity=velocity) + + # Assert + try: + thread_mock.set_vel_setpoint.assert_has_calls([ + call(*expected), + call(0.0, 0.0, 0.0, 0.0), + ]) + sleep_mock.assert_called_with(expected_time) + except AssertionError as e: + print('Failed when testing function ' + + function_under_test.__name__) + raise e + + +class TestSetpointThread(unittest.TestCase): + def setUp(self): + self.commander_mock = MagicMock(spec=Commander) + self.cf_mock = MagicMock(spec=Crazyflie) + self.cf_mock.commander = self.commander_mock + + self.sut = _SetPointThread(self.cf_mock) + + def test_that_thread_stops(self): + # Fixture + self.sut.start() + self.sut.stop() + + # Test + actual = self.sut.is_alive() + + # Assert + self.assertFalse(actual) + + def test_that_x_y_and_yaw_is_set(self): + # Fixture + x = 1.0 + y = 2.0 + yaw = 3.0 + + self.sut.start() + + # Test + self.sut.set_vel_setpoint(x, y, 0, yaw) + + # Assert + self.sut.stop() + + self.commander_mock.send_hover_setpoint.assert_called_once_with( + x, y, yaw, 0) + + +if __name__ == '__main__': + unittest.main() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/test/positioning/test_position_hl_commander.py b/dfall_ws/src/dfall_pkg/crazyradio/test/positioning/test_position_hl_commander.py new file mode 100644 index 00000000..a347824d --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/test/positioning/test_position_hl_commander.py @@ -0,0 +1,386 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2018 Bitcraze AB +# +# 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. +import math +import sys +import unittest + +from cflib.crazyflie import Crazyflie +from cflib.crazyflie import HighLevelCommander +from cflib.crazyflie import Param +from cflib.positioning.position_hl_commander import PositionHlCommander + +if sys.version_info < (3, 3): + from mock import MagicMock, patch, call +else: + from unittest.mock import MagicMock, patch, call + + +@patch('time.sleep') +class TestPositionHlCommander(unittest.TestCase): + def setUp(self): + self.commander_mock = MagicMock(spec=HighLevelCommander) + self.param_mock = MagicMock(spec=Param) + self.cf_mock = MagicMock(spec=Crazyflie) + self.cf_mock.high_level_commander = self.commander_mock + self.cf_mock.param = self.param_mock + self.cf_mock.is_connected.return_value = True + + self.sut = PositionHlCommander(self.cf_mock) + + def test_that_the_estimator_is_reset_on_take_off( + self, sleep_mock): + # Fixture + sut = PositionHlCommander(self.cf_mock, 1.0, 2.0, 3.0) + + # Test + sut.take_off() + + # Assert + self.param_mock.set_value.assert_has_calls([ + call('kalman.initialX', '{:.2f}'.format(1.0)), + call('kalman.initialY', '{:.2f}'.format(2.0)), + call('kalman.initialZ', '{:.2f}'.format(3.0)), + + call('kalman.resetEstimation', '1'), + call('kalman.resetEstimation', '0') + ]) + + def test_that_the_hi_level_commander_is_activated_on_take_off( + self, sleep_mock): + # Fixture + + # Test + self.sut.take_off() + + # Assert + self.param_mock.set_value.assert_has_calls([ + call('commander.enHighLevel', '1') + ]) + + def test_that_controller_is_selected_on_take_off( + self, sleep_mock): + # Fixture + self.sut.set_controller(PositionHlCommander.CONTROLLER_MELLINGER) + + # Test + self.sut.take_off() + + # Assert + self.param_mock.set_value.assert_has_calls([ + call('stabilizer.controller', '2') + ]) + + def test_that_take_off_raises_exception_if_not_connected( + self, sleep_mock): + # Fixture + self.cf_mock.is_connected.return_value = False + + # Test + # Assert + with self.assertRaises(Exception): + self.sut.take_off() + + def test_that_take_off_raises_exception_when_already_flying( + self, sleep_mock): + # Fixture + self.sut.take_off() + + # Test + # Assert + with self.assertRaises(Exception): + self.sut.take_off() + + def test_that_it_goes_up_on_take_off( + self, sleep_mock): + # Fixture + + # Test + self.sut.take_off(height=0.4, velocity=0.6) + + # Assert + duration = 0.4 / 0.6 + self.commander_mock.takeoff.assert_called_with(0.4, duration) + sleep_mock.assert_called_with(duration) + + def test_that_it_goes_up_to_default_height( + self, sleep_mock): + # Fixture + sut = PositionHlCommander(self.cf_mock, default_height=0.4) + + # Test + sut.take_off(velocity=0.6) + + # Assert + duration = 0.4 / 0.6 + self.commander_mock.takeoff.assert_called_with(0.4, duration) + sleep_mock.assert_called_with(duration) + + def test_that_it_goes_down_on_landing( + self, sleep_mock): + # Fixture + self.sut.take_off(height=0.4) + + # Test + self.sut.land(velocity=0.6) + + # Assert + duration = 0.4 / 0.6 + self.commander_mock.land.assert_called_with(0.0, duration) + sleep_mock.assert_called_with(duration) + + def test_that_it_takes_off_and_lands_as_context_manager( + self, sleep_mock): + # Fixture + + # Test + with self.sut: + pass + + # Assert + duration1 = 0.5 / 0.5 + duration2 = 0.5 / 0.5 + self.commander_mock.takeoff.assert_called_with(0.5, duration1) + self.commander_mock.land.assert_called_with(0.0, duration2) + sleep_mock.assert_called_with(duration1) + sleep_mock.assert_called_with(duration2) + + def test_that_it_returns_current_position( + self, sleep_mock): + # Fixture + self.sut.take_off(height=0.4, velocity=0.6) + + # Test + actual = self.sut.get_position() + + # Assert + self.assertEqual(actual, (0.0, 0.0, 0.4)) + + def test_that_it_goes_to_position( + self, sleep_mock): + # Fixture + self.sut.take_off() + inital_pos = self.sut.get_position() + + # Test + self.sut.go_to(1.0, 2.0, 3.0, 4.0) + + # Assert + distance = self._distance(inital_pos, (1.0, 2.0, 3.0)) + duration = distance / 4.0 + self.commander_mock.go_to.assert_called_with( + 1.0, 2.0, 3.0, 0.0, duration) + sleep_mock.assert_called_with(duration) + + def test_that_it_does_not_send_goto_to_same_position( + self, sleep_mock): + # Fixture + self.sut.take_off() + inital_pos = self.sut.get_position() + + # Test + self.sut.go_to(inital_pos[0], inital_pos[1], inital_pos[2]) + + # Assert + self.commander_mock.go_to.assert_not_called() + + def test_that_it_moves_distance( + self, sleep_mock): + # Fixture + self.sut.take_off() + inital_pos = self.sut.get_position() + + # Test + self.sut.move_distance(1.0, 2.0, 3.0, 4.0) + + # Assert + distance = self._distance((0.0, 0.0, 0.0), (1.0, 2.0, 3.0)) + duration = distance / 4.0 + final_pos = ( + inital_pos[0] + 1.0, + inital_pos[1] + 2.0, + inital_pos[2] + 3.0) + self.commander_mock.go_to.assert_called_with( + final_pos[0], final_pos[1], final_pos[2], 0.0, duration) + sleep_mock.assert_called_with(duration) + + def test_that_it_goes_forward( + self, sleep_mock): + # Fixture + self.sut.take_off() + inital_pos = self.sut.get_position() + + # Test + self.sut.forward(1.0, 2.0) + + # Assert + duration = 1.0 / 2.0 + final_pos = ( + inital_pos[0] + 1.0, + inital_pos[1], + inital_pos[2]) + self.commander_mock.go_to.assert_called_with( + final_pos[0], final_pos[1], final_pos[2], 0.0, duration) + sleep_mock.assert_called_with(duration) + + def test_that_it_goes_back( + self, sleep_mock): + # Fixture + self.sut.take_off() + inital_pos = self.sut.get_position() + + # Test + self.sut.back(1.0, 2.0) + + # Assert + duration = 1.0 / 2.0 + final_pos = ( + inital_pos[0] - 1.0, + inital_pos[1], + inital_pos[2]) + self.commander_mock.go_to.assert_called_with( + final_pos[0], final_pos[1], final_pos[2], 0.0, duration) + sleep_mock.assert_called_with(duration) + + def test_that_it_goes_left( + self, sleep_mock): + # Fixture + self.sut.take_off() + inital_pos = self.sut.get_position() + + # Test + self.sut.left(1.0, 2.0) + + # Assert + duration = 1.0 / 2.0 + final_pos = ( + inital_pos[0], + inital_pos[1] + 1.0, + inital_pos[2]) + self.commander_mock.go_to.assert_called_with( + final_pos[0], final_pos[1], final_pos[2], 0.0, duration) + sleep_mock.assert_called_with(duration) + + def test_that_it_goes_right( + self, sleep_mock): + # Fixture + self.sut.take_off() + inital_pos = self.sut.get_position() + + # Test + self.sut.right(1.0, 2.0) + + # Assert + duration = 1.0 / 2.0 + final_pos = ( + inital_pos[0], + inital_pos[1] - 1, + inital_pos[2]) + self.commander_mock.go_to.assert_called_with( + final_pos[0], final_pos[1], final_pos[2], 0, duration) + sleep_mock.assert_called_with(duration) + + def test_that_it_goes_up( + self, sleep_mock): + # Fixture + self.sut.take_off() + inital_pos = self.sut.get_position() + + # Test + self.sut.up(1.0, 2.0) + + # Assert + duration = 1.0 / 2.0 + final_pos = ( + inital_pos[0], + inital_pos[1], + inital_pos[2] + 1) + self.commander_mock.go_to.assert_called_with( + final_pos[0], final_pos[1], final_pos[2], 0, duration) + sleep_mock.assert_called_with(duration) + + def test_that_it_goes_down( + self, sleep_mock): + # Fixture + self.sut.take_off() + inital_pos = self.sut.get_position() + + # Test + self.sut.down(1.0, 2.0) + + # Assert + duration = 1.0 / 2.0 + final_pos = ( + inital_pos[0], + inital_pos[1], + inital_pos[2] - 1) + self.commander_mock.go_to.assert_called_with( + final_pos[0], final_pos[1], final_pos[2], 0, duration) + sleep_mock.assert_called_with(duration) + + def test_that_default_velocity_is_used( + self, sleep_mock): + # Fixture + self.sut.take_off() + inital_pos = self.sut.get_position() + self.sut.set_default_velocity(7) + + # Test + self.sut.go_to(1.0, 2.0, 3.0) + + # Assert + distance = self._distance(inital_pos, (1.0, 2.0, 3.0)) + duration = distance / 7.0 + self.commander_mock.go_to.assert_called_with( + 1.0, 2.0, 3.0, 0.0, duration) + sleep_mock.assert_called_with(duration) + + def test_that_default_height_is_used( + self, sleep_mock): + # Fixture + self.sut.take_off() + inital_pos = self.sut.get_position() + self.sut.set_default_velocity(7.0) + self.sut.set_default_height(5.0) + + # Test + self.sut.go_to(1.0, 2.0) + + # Assert + distance = self._distance(inital_pos, (1.0, 2.0, 5.0)) + duration = distance / 7.0 + self.commander_mock.go_to.assert_called_with( + 1.0, 2.0, 5.0, 0.0, duration) + sleep_mock.assert_called_with(duration) + + ###################################################################### + + def _distance(self, p1, p2): + dx = p1[0] - p2[0] + dy = p1[1] - p2[1] + dz = p1[2] - p2[2] + return math.sqrt(dx * dx + dy * dy + dz * dz) + + +if __name__ == '__main__': + unittest.main() diff --git a/dfall_ws/src/dfall_pkg/crazyradio/test/utils/test_multiranger.py b/dfall_ws/src/dfall_pkg/crazyradio/test/utils/test_multiranger.py new file mode 100644 index 00000000..f4a514b4 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/test/utils/test_multiranger.py @@ -0,0 +1,262 @@ +# -*- coding: utf-8 -*- +# +# || ____ _ __ +# +------+ / __ )(_) /_______________ _____ ___ +# | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ +# +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ +# || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ +# +# Copyright (C) 2018 Bitcraze AB +# +# 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. +import sys +import unittest + +from cflib.crazyflie import Crazyflie +from cflib.crazyflie import Log +from cflib.crazyflie.log import LogConfig +from cflib.utils.callbacks import Caller +from cflib.utils.multiranger import Multiranger + +if sys.version_info < (3, 3): + from mock import MagicMock, call, patch +else: + from unittest.mock import MagicMock, call, patch + + +class MultirangerTest(unittest.TestCase): + FRONT = 'range.front' + BACK = 'range.back' + LEFT = 'range.left' + RIGHT = 'range.right' + UP = 'range.up' + DOWN = 'range.zrange' + + OUT_OF_RANGE = 8000 + + def setUp(self): + self.cf_mock = MagicMock(spec=Crazyflie) + + self.log_config_mock = MagicMock(spec=LogConfig) + self.log_config_mock.data_received_cb = Caller() + + self.log_mock = MagicMock(spec=Log) + self.cf_mock.log = self.log_mock + + self.front_data = 2345 + self.back_data = 2345 + self.left_data = 123 + self.right_data = 5432 + self.up_data = 3456 + self.down_data = 1212 + self.log_data = { + self.FRONT: self.front_data, + self.BACK: self.back_data, + self.LEFT: self.left_data, + self.RIGHT: self.right_data, + self.UP: self.up_data, + self.DOWN: self.down_data, + } + + def test_that_log_configuration_is_added_on_connect(self): + # Fixture + with patch('cflib.utils.multiranger.LogConfig', + return_value=self.log_config_mock): + sut = Multiranger(self.cf_mock) + + # Test + sut.start() + + # Assert + self.log_mock.add_config.assert_called_once_with( + self.log_config_mock) + + def test_that_log_configuration_is_correct(self): + # Fixture + with patch('cflib.utils.multiranger.LogConfig', + return_value=self.log_config_mock): + sut = Multiranger(self.cf_mock) + + # Test + sut.start() + + # Assert + self.log_config_mock.add_variable.assert_has_calls([ + call(self.FRONT), + call(self.BACK), + call(self.LEFT), + call(self.RIGHT), + call(self.UP), + ]) + + def test_that_log_configuration_is_correct_with_zranger(self): + # Fixture + with patch('cflib.utils.multiranger.LogConfig', + return_value=self.log_config_mock): + sut = Multiranger(self.cf_mock, zranger=True) + + # Test + sut.start() + + # Assert + self.log_config_mock.add_variable.assert_has_calls([ + call(self.FRONT), + call(self.BACK), + call(self.LEFT), + call(self.RIGHT), + call(self.UP), + call(self.DOWN) + ]) + + # def test_that_rate_configuration_is_applied(self): + # # Fixture + # with patch('cflib.utils.multiranger.LogConfig', + # return_value=self.log_config_mock): + # + # # Test + # Multiranger(self.cf_mock, rate_ms=123) + # + # # Assert + # self.log_config_mock.assert_called_once_with('multiranger', 123) + + def test_that_logging_is_started_on_start(self): + # Fixture + with patch('cflib.utils.multiranger.LogConfig', + return_value=self.log_config_mock): + sut = Multiranger(self.cf_mock) + + # Test + sut.start() + + # Assert + self.log_config_mock.start.assert_called_once_with() + + def test_that_data_callback_is_set(self): + # Fixture + with patch('cflib.utils.multiranger.LogConfig', + return_value=self.log_config_mock): + sut = Multiranger(self.cf_mock) + + # Test + sut.start() + + # Assert + self.log_config_mock.start.assert_called_once_with() + self.assertEqual(1, len( + self.log_config_mock.data_received_cb.callbacks)) + + def test_that_the_log_config_is_deleted_on_stop(self): + # Fixture + with patch('cflib.utils.multiranger.LogConfig', + return_value=self.log_config_mock): + sut = Multiranger(self.cf_mock) + sut.start() + + # Test + sut.stop() + + # Assert + self.log_config_mock.delete.assert_called_once_with() + + def test_that_using_context_manager_calls_start_and_stop(self): + # Fixture + with patch('cflib.utils.multiranger.LogConfig', + return_value=self.log_config_mock): + + with Multiranger(self.cf_mock): + pass + + # Assert + self.log_config_mock.start.assert_called_once_with() + self.log_config_mock.delete.assert_called_once_with() + + def test_that_data_received_from_log_is_available_from_up_getter(self): + self._validate_distance_from_getter(self.up_data / 1000.0, 'up') + + def test_that_none_is_returned_if_up_ranging_is_off_limit(self): + # Fixture + self.log_data[self.UP] = self.OUT_OF_RANGE + self._validate_distance_from_getter(None, 'up') + + def test_that_data_received_from_log_is_available_from_front_getter(self): + self._validate_distance_from_getter(self.front_data / 1000.0, + 'front') + + def test_that_none_is_returned_if_front_ranging_is_off_limit(self): + # Fixture + self.log_data[self.FRONT] = self.OUT_OF_RANGE + self._validate_distance_from_getter(None, 'front') + + def test_that_data_received_from_log_is_available_from_back_getter(self): + self._validate_distance_from_getter(self.back_data / 1000.0, + 'back') + + def test_that_none_is_returned_if_back_ranging_is_off_limit(self): + # Fixture + self.log_data[self.BACK] = self.OUT_OF_RANGE + self._validate_distance_from_getter(None, 'back') + + def test_that_data_received_from_log_is_available_from_left_getter(self): + self._validate_distance_from_getter(self.left_data / 1000.0, + 'left') + + def test_that_none_is_returned_if_left_ranging_is_off_limit(self): + # Fixture + self.log_data[self.LEFT] = self.OUT_OF_RANGE + self._validate_distance_from_getter(None, 'left') + + def test_that_data_received_from_log_is_available_from_right_getter(self): + self._validate_distance_from_getter(self.right_data / 1000.0, + 'right') + + def test_that_none_is_returned_if_right_ranging_is_off_limit(self): + # Fixture + self.log_data[self.RIGHT] = self.OUT_OF_RANGE + self._validate_distance_from_getter(None, 'right') + + def test_that_data_received_from_log_is_available_from_down_getter(self): + self._validate_distance_from_getter(self.down_data / 1000.0, + 'down', zranger=True) + + def test_that_none_is_returned_if_down_ranging_is_off_limit(self): + # Fixture + self.log_data[self.DOWN] = self.OUT_OF_RANGE + self._validate_distance_from_getter(None, 'down', zranger=True) + + def test_that_none_is_returned_from_down_if_zranger_is_disabled(self): + # Fixture + del self.log_data[self.DOWN] + self._validate_distance_from_getter(None, 'down', zranger=False) + + # Helpers ################################################################ + + def _validate_distance_from_getter(self, expected, getter_name, + zranger=False): + # Fixture + with patch('cflib.utils.multiranger.LogConfig', + return_value=self.log_config_mock): + sut = Multiranger(self.cf_mock, zranger=zranger) + + timestmp = 1234 + logconf = None + + self.log_config_mock.data_received_cb.call(timestmp, self.log_data, + logconf) + + # Test + actual = getattr(sut, getter_name) + + # Assert + self.assertEqual(expected, actual) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/tools/build/sys-test b/dfall_ws/src/dfall_pkg/crazyradio/tools/build/sys-test new file mode 100755 index 00000000..fd61ee99 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/crazyradio/tools/build/sys-test @@ -0,0 +1,16 @@ +#!/usr/bin/env python +import os +import os.path as _path +import subprocess + +try: + script_dir = os.path.dirname(os.path.realpath(__file__)) + root = _path.normpath(_path.join(script_dir, '../../sys_test')) + + print('**** Running sys tests ****') + subprocess.check_call(['python3', '-m', 'unittest', 'discover', root]) + + print('Unit tests pass') +except subprocess.CalledProcessError as e: + print('Error: Unit tests fail') + raise e diff --git a/dfall_ws/src/dfall_pkg/crazyradio/tools/build/test b/dfall_ws/src/dfall_pkg/crazyradio/tools/build/test index 09e9f549..d2ed4446 100755 --- a/dfall_ws/src/dfall_pkg/crazyradio/tools/build/test +++ b/dfall_ws/src/dfall_pkg/crazyradio/tools/build/test @@ -5,7 +5,7 @@ import subprocess try: script_dir = os.path.dirname(os.path.realpath(__file__)) - root = _path.normpath(_path.join(script_dir, '../..')) + root = _path.normpath(_path.join(script_dir, '../../test')) print('**** Running tests in python2 ****') subprocess.check_call(['python2', '-m', 'unittest', 'discover', root]) diff --git a/dfall_ws/src/dfall_pkg/crazyradio/tox.ini b/dfall_ws/src/dfall_pkg/crazyradio/tox.ini index 4806caf3..4e48e739 100644 --- a/dfall_ws/src/dfall_pkg/crazyradio/tox.ini +++ b/dfall_ws/src/dfall_pkg/crazyradio/tox.ini @@ -1,12 +1,12 @@ [tox] project = cflib -envlist = py27,py33,py34 +envlist = py27,py34 [testenv] deps = -rrequirements-dev.txt commands= coverage erase - coverage run -m unittest discover + coverage run -m unittest discover ./test coverage report --show-missing pre-commit run --all-files diff --git a/web_interface/install_dfall_server_WIP.sh b/web_interface/install_dfall_server_WIP.sh index b6ab3114..14e7f5f3 100644 --- a/web_interface/install_dfall_server_WIP.sh +++ b/web_interface/install_dfall_server_WIP.sh @@ -5,10 +5,52 @@ sudo apt install apache2 sudo apt install php # DISABLE iPv6 +# Taken from: +# https://www.configserverfirewall.com/ubuntu-linux/ubuntu-disable-ipv6/ + +# Permanently Disable IPv6 on Ubuntu 18.04/16.04 with sysctl + +# Easiest and safest method is to add configurations to the /etc/sysctl.conf file. To disable IPv6 using sysctl, Open the Ubuntu terminal and Perform the following steps: + +# Open the /etc/sysctl.conf file: + +# vim /etc/sysctl.conf + +# Add the following lines at the end of the sysctl.conf file: + +# net.ipv6.conf.all.disable_ipv6 = 1 +# net.ipv6.conf.default.disable_ipv6 = 1 +# net.ipv6.conf.lo.disable_ipv6 = 1 + +# In Ubuntu server 18.04, you will need to add additional lines for each interface you want to disable IPv6: + +# net.ipv6.conf.<ifname>.disable_ipv6 = 1 + +# For example, if the interface name is enp0s3, Then: + +# net.ipv6.conf.enp0s3.disable_ipv6 = 1 + +# For change to be effected, run the sysctl -p command. + +# sysctl -p + +# Then, run the following command to check the IPv6 status: + +# cat /proc/sys/net/ipv6/conf/all/disable_ipv6 + +# If the output is 1 then IPv6 is disabled, the command will output 0 when IPv6 is enabled. + +# If you want to re enable IPv6 addresses, remove the above configuration from the sysctl.conf and execute the sysctl -p command. + + + # CRTICAL TO GET THE gateway4 and nameserver correct # for example 192.168.0.1 + + + # Create a shared folder cd /home sudo mkdir www-share -- GitLab