From bbde15f9bfc77a59efbebc7787bed6b5c1910613 Mon Sep 17 00:00:00 2001 From: Bogdan Kolbov Date: Mon, 29 Jul 2019 08:17:46 +0300 Subject: [PATCH] Initial commit --- .cproject | 283 + .gitignore | 1 + .project | 32 + .settings/language.settings.xml | 25 + .settings/org.eclipse.cdt.codan.core.prefs | 67 + .../org.eclipse.cdt.managedbuilder.core.prefs | 11 + LICENSE.txt | 203 + README.md | 18 + Vinclude/CANBlockTransferInterface.h | 68 + Vinclude/CANOpen_drv.h | 170 + Vinclude/DRV_INTERFACE.h | 83 + Vinclude/DSP.h | 68 + Vinclude/EPwm_defines.h | 183 + Vinclude/Global_time.h | 196 + Vinclude/SM_CmdLogic.h | 96 + Vinclude/SM_Ctrl.h | 94 + Vinclude/SM_Net.h | 93 + Vinclude/SM_Protect.h | 128 + Vinclude/SM_Sys.h | 90 + Vinclude/V_AutoOffset.h | 72 + Vinclude/V_CANtoRS.h | 110 + Vinclude/V_CurPar.h | 101 + Vinclude/V_DPR_eCAP.h | 226 + Vinclude/V_IQmath.h | 337 + Vinclude/V_MBVarsConv.h | 90 + Vinclude/V_ModBus.h | 126 + Vinclude/V_PWM_Module.h | 173 + Vinclude/V_QEP.h | 251 + Vinclude/V_RTC_Clock.h | 83 + Vinclude/V_SSI_Encoder.h | 119 + Vinclude/V_UserMemory.h | 140 + Vinclude/V_adc.h | 145 + Vinclude/V_bits_to_enum_numbers.h | 77 + Vinclude/V_common.h | 128 + Vinclude/V_data_log.h | 224 + Vinclude/V_event_log.h | 131 + Vinclude/V_fifo.h | 72 + Vinclude/V_hzprof.h | 69 + Vinclude/V_led.h | 68 + Vinclude/V_pid_reg3.h | 108 + Vinclude/V_pid_reg3_pos.h | 108 + Vinclude/V_relay_reg.h | 67 + Vinclude/V_rmp_ctrl.h | 74 + Vinclude/V_rotor_observer.h | 61 + Vinclude/V_usblib.h | 35 + Vinclude/V_watchdog.h | 32 + Vinclude/X_CANFlashProgData.h | 51 + Vinclude/X_CANFlashProgStarter.h | 82 + Vinclude/build.h | 117 + Vinclude/clarke.h | 71 + Vinclude/co_ODvars.h | 867 ++ Vinclude/cood1.h | 78 + Vinclude/cood2.h | 78 + Vinclude/filter.h | 74 + Vinclude/ipark.h | 69 + Vinclude/main.h | 192 + Vinclude/mbod.h | 44 + Vinclude/park.h | 68 + Vsrc/CANOpenUDfuncs.c | 400 + Vsrc/DRV_INTERFACE.c | 108 + Vsrc/SM_CmdLogic.c | 109 + Vsrc/SM_Ctrl.c | 783 ++ Vsrc/SM_Net.c | 157 + Vsrc/SM_Protect.c | 205 + Vsrc/SM_Sys.c | 278 + Vsrc/V_AutoOffset.c | 73 + Vsrc/V_CANtoRS.c | 327 + Vsrc/V_CurPar.c | 89 + Vsrc/V_DPR_eCAP.c | 605 + Vsrc/V_Global_time.c | 217 + Vsrc/V_IQmath.c | 280 + Vsrc/V_PWM_Module.c | 652 + Vsrc/V_QEP.c | 318 + Vsrc/V_RTC_Clock.c | 206 + Vsrc/V_SSI_Encoder.c | 164 + Vsrc/V_UserMemory.c | 132 + Vsrc/V_adc.c | 185 + Vsrc/V_bits_to_enum_numbers.c | 72 + Vsrc/V_data_log.c | 281 + Vsrc/V_event_log.c | 252 + Vsrc/V_hzprof.c | 53 + Vsrc/V_led.c | 78 + Vsrc/V_pid_reg3.c | 111 + Vsrc/V_pid_reg3_pos.c | 109 + Vsrc/V_rmp_ctrl.c | 66 + Vsrc/V_rotor_observer.c | 47 + Vsrc/V_watchdog.c | 69 + Vsrc/clarke.c | 35 + Vsrc/cood1.c | 3939 ++++++ Vsrc/filter.c | 43 + Vsrc/ipark.c | 45 + Vsrc/main.c | 322 + Vsrc/park.c | 47 + asm/startup_K1921VK035_vector.S | 307 + cmd/build.ld | 242 + cood.xml | 4547 +++++++ include/K1921VK035.h | 10232 ++++++++++++++++ include/core_cm4.h | 1758 +++ include/core_cm4_simd.h | 650 + include/core_cmFunc.h | 617 + include/core_cmInstr.h | 619 + include/system_K1921VK035.h | 53 + lib/libCANOpen_drv.a | Bin 0 -> 371844 bytes lib/libc.a | Bin 0 -> 890244 bytes lib/libgcc.a | Bin 0 -> 1526062 bytes lib/libm.a | Bin 0 -> 494922 bytes src/system_K1921VK035.c | 185 + ...ЅРЅРѕРµ соглашение [CANOpen].txt | 42 + 108 files changed, 37036 insertions(+) create mode 100644 .cproject create mode 100644 .gitignore create mode 100644 .project create mode 100644 .settings/language.settings.xml create mode 100644 .settings/org.eclipse.cdt.codan.core.prefs create mode 100644 .settings/org.eclipse.cdt.managedbuilder.core.prefs create mode 100644 LICENSE.txt create mode 100644 README.md create mode 100644 Vinclude/CANBlockTransferInterface.h create mode 100644 Vinclude/CANOpen_drv.h create mode 100644 Vinclude/DRV_INTERFACE.h create mode 100644 Vinclude/DSP.h create mode 100644 Vinclude/EPwm_defines.h create mode 100644 Vinclude/Global_time.h create mode 100644 Vinclude/SM_CmdLogic.h create mode 100644 Vinclude/SM_Ctrl.h create mode 100644 Vinclude/SM_Net.h create mode 100644 Vinclude/SM_Protect.h create mode 100644 Vinclude/SM_Sys.h create mode 100644 Vinclude/V_AutoOffset.h create mode 100644 Vinclude/V_CANtoRS.h create mode 100644 Vinclude/V_CurPar.h create mode 100644 Vinclude/V_DPR_eCAP.h create mode 100644 Vinclude/V_IQmath.h create mode 100644 Vinclude/V_MBVarsConv.h create mode 100644 Vinclude/V_ModBus.h create mode 100644 Vinclude/V_PWM_Module.h create mode 100644 Vinclude/V_QEP.h create mode 100644 Vinclude/V_RTC_Clock.h create mode 100644 Vinclude/V_SSI_Encoder.h create mode 100644 Vinclude/V_UserMemory.h create mode 100644 Vinclude/V_adc.h create mode 100644 Vinclude/V_bits_to_enum_numbers.h create mode 100644 Vinclude/V_common.h create mode 100644 Vinclude/V_data_log.h create mode 100644 Vinclude/V_event_log.h create mode 100644 Vinclude/V_fifo.h create mode 100644 Vinclude/V_hzprof.h create mode 100644 Vinclude/V_led.h create mode 100644 Vinclude/V_pid_reg3.h create mode 100644 Vinclude/V_pid_reg3_pos.h create mode 100644 Vinclude/V_relay_reg.h create mode 100644 Vinclude/V_rmp_ctrl.h create mode 100644 Vinclude/V_rotor_observer.h create mode 100644 Vinclude/V_usblib.h create mode 100644 Vinclude/V_watchdog.h create mode 100644 Vinclude/X_CANFlashProgData.h create mode 100644 Vinclude/X_CANFlashProgStarter.h create mode 100644 Vinclude/build.h create mode 100644 Vinclude/clarke.h create mode 100644 Vinclude/co_ODvars.h create mode 100644 Vinclude/cood1.h create mode 100644 Vinclude/cood2.h create mode 100644 Vinclude/filter.h create mode 100644 Vinclude/ipark.h create mode 100644 Vinclude/main.h create mode 100644 Vinclude/mbod.h create mode 100644 Vinclude/park.h create mode 100644 Vsrc/CANOpenUDfuncs.c create mode 100644 Vsrc/DRV_INTERFACE.c create mode 100644 Vsrc/SM_CmdLogic.c create mode 100644 Vsrc/SM_Ctrl.c create mode 100644 Vsrc/SM_Net.c create mode 100644 Vsrc/SM_Protect.c create mode 100644 Vsrc/SM_Sys.c create mode 100644 Vsrc/V_AutoOffset.c create mode 100644 Vsrc/V_CANtoRS.c create mode 100644 Vsrc/V_CurPar.c create mode 100644 Vsrc/V_DPR_eCAP.c create mode 100644 Vsrc/V_Global_time.c create mode 100644 Vsrc/V_IQmath.c create mode 100644 Vsrc/V_PWM_Module.c create mode 100644 Vsrc/V_QEP.c create mode 100644 Vsrc/V_RTC_Clock.c create mode 100644 Vsrc/V_SSI_Encoder.c create mode 100644 Vsrc/V_UserMemory.c create mode 100644 Vsrc/V_adc.c create mode 100644 Vsrc/V_bits_to_enum_numbers.c create mode 100644 Vsrc/V_data_log.c create mode 100644 Vsrc/V_event_log.c create mode 100644 Vsrc/V_hzprof.c create mode 100644 Vsrc/V_led.c create mode 100644 Vsrc/V_pid_reg3.c create mode 100644 Vsrc/V_pid_reg3_pos.c create mode 100644 Vsrc/V_rmp_ctrl.c create mode 100644 Vsrc/V_rotor_observer.c create mode 100644 Vsrc/V_watchdog.c create mode 100644 Vsrc/clarke.c create mode 100644 Vsrc/cood1.c create mode 100644 Vsrc/filter.c create mode 100644 Vsrc/ipark.c create mode 100644 Vsrc/main.c create mode 100644 Vsrc/park.c create mode 100644 asm/startup_K1921VK035_vector.S create mode 100644 cmd/build.ld create mode 100644 cood.xml create mode 100644 include/K1921VK035.h create mode 100644 include/core_cm4.h create mode 100644 include/core_cm4_simd.h create mode 100644 include/core_cmFunc.h create mode 100644 include/core_cmInstr.h create mode 100644 include/system_K1921VK035.h create mode 100644 lib/libCANOpen_drv.a create mode 100644 lib/libc.a create mode 100644 lib/libgcc.a create mode 100644 lib/libm.a create mode 100644 src/system_K1921VK035.c create mode 100644 Лицензионное соглашение [CANOpen].txt diff --git a/.cproject b/.cproject new file mode 100644 index 0000000..b356d6a --- /dev/null +++ b/.cproject @@ -0,0 +1,283 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..3df573f --- /dev/null +++ b/.gitignore @@ -0,0 +1 @@ +/Debug/ diff --git a/.project b/.project new file mode 100644 index 0000000..523b3e3 --- /dev/null +++ b/.project @@ -0,0 +1,32 @@ + + + MCD_035 + + + + + + org.eclipse.cdt.managedbuilder.core.genmakebuilder + clean,full,incremental, + + + + + org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder + full,incremental, + + + + + + org.eclipse.cdt.core.cnature + org.eclipse.cdt.managedbuilder.core.managedBuildNature + org.eclipse.cdt.managedbuilder.core.ScannerConfigNature + + + + copy_PARENT + $%7BPARENT-3-PROJECT_LOC%7D/ProjectsGit/motorcontroldemo + + + diff --git a/.settings/language.settings.xml b/.settings/language.settings.xml new file mode 100644 index 0000000..2540c60 --- /dev/null +++ b/.settings/language.settings.xml @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/.settings/org.eclipse.cdt.codan.core.prefs b/.settings/org.eclipse.cdt.codan.core.prefs new file mode 100644 index 0000000..6e96f5d --- /dev/null +++ b/.settings/org.eclipse.cdt.codan.core.prefs @@ -0,0 +1,67 @@ +eclipse.preferences.version=1 +org.eclipse.cdt.codan.checkers.errnoreturn=Warning +org.eclipse.cdt.codan.checkers.errnoreturn.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},implicit\=>false} +org.eclipse.cdt.codan.checkers.errreturnvalue=Error +org.eclipse.cdt.codan.checkers.errreturnvalue.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.checkers.noreturn=Error +org.eclipse.cdt.codan.checkers.noreturn.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},implicit\=>false} +org.eclipse.cdt.codan.internal.checkers.AbstractClassCreation=Error +org.eclipse.cdt.codan.internal.checkers.AbstractClassCreation.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.AmbiguousProblem=Error +org.eclipse.cdt.codan.internal.checkers.AmbiguousProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.AssignmentInConditionProblem=Warning +org.eclipse.cdt.codan.internal.checkers.AssignmentInConditionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.AssignmentToItselfProblem=Error +org.eclipse.cdt.codan.internal.checkers.AssignmentToItselfProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.CaseBreakProblem=-Warning +org.eclipse.cdt.codan.internal.checkers.CaseBreakProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},no_break_comment\=>"no break",last_case_param\=>false,empty_case_param\=>false} +org.eclipse.cdt.codan.internal.checkers.CatchByReference=Warning +org.eclipse.cdt.codan.internal.checkers.CatchByReference.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},unknown\=>false,exceptions\=>()} +org.eclipse.cdt.codan.internal.checkers.CircularReferenceProblem=Error +org.eclipse.cdt.codan.internal.checkers.CircularReferenceProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.ClassMembersInitialization=Warning +org.eclipse.cdt.codan.internal.checkers.ClassMembersInitialization.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},skip\=>true} +org.eclipse.cdt.codan.internal.checkers.FieldResolutionProblem=Error +org.eclipse.cdt.codan.internal.checkers.FieldResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.FunctionResolutionProblem=Error +org.eclipse.cdt.codan.internal.checkers.FunctionResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.InvalidArguments=Error +org.eclipse.cdt.codan.internal.checkers.InvalidArguments.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.InvalidTemplateArgumentsProblem=Error +org.eclipse.cdt.codan.internal.checkers.InvalidTemplateArgumentsProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.LabelStatementNotFoundProblem=Error +org.eclipse.cdt.codan.internal.checkers.LabelStatementNotFoundProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.MemberDeclarationNotFoundProblem=Error +org.eclipse.cdt.codan.internal.checkers.MemberDeclarationNotFoundProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.MethodResolutionProblem=Error +org.eclipse.cdt.codan.internal.checkers.MethodResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.NamingConventionFunctionChecker=-Info +org.eclipse.cdt.codan.internal.checkers.NamingConventionFunctionChecker.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},pattern\=>"^[a-z]",macro\=>true,exceptions\=>()} +org.eclipse.cdt.codan.internal.checkers.NonVirtualDestructorProblem=Warning +org.eclipse.cdt.codan.internal.checkers.NonVirtualDestructorProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.OverloadProblem=Error +org.eclipse.cdt.codan.internal.checkers.OverloadProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.RedeclarationProblem=Error +org.eclipse.cdt.codan.internal.checkers.RedeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.RedefinitionProblem=Error +org.eclipse.cdt.codan.internal.checkers.RedefinitionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.ReturnStyleProblem=-Warning +org.eclipse.cdt.codan.internal.checkers.ReturnStyleProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.ScanfFormatStringSecurityProblem=-Warning +org.eclipse.cdt.codan.internal.checkers.ScanfFormatStringSecurityProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.StatementHasNoEffectProblem=Warning +org.eclipse.cdt.codan.internal.checkers.StatementHasNoEffectProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true,exceptions\=>()} +org.eclipse.cdt.codan.internal.checkers.SuggestedParenthesisProblem=-Warning +org.eclipse.cdt.codan.internal.checkers.SuggestedParenthesisProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},paramNot\=>false} +org.eclipse.cdt.codan.internal.checkers.SuspiciousSemicolonProblem=Warning +org.eclipse.cdt.codan.internal.checkers.SuspiciousSemicolonProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},else\=>false,afterelse\=>false} +org.eclipse.cdt.codan.internal.checkers.TypeResolutionProblem=Error +org.eclipse.cdt.codan.internal.checkers.TypeResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.UnusedFunctionDeclarationProblem=Warning +org.eclipse.cdt.codan.internal.checkers.UnusedFunctionDeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true} +org.eclipse.cdt.codan.internal.checkers.UnusedStaticFunctionProblem=Warning +org.eclipse.cdt.codan.internal.checkers.UnusedStaticFunctionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true} +org.eclipse.cdt.codan.internal.checkers.UnusedVariableDeclarationProblem=Warning +org.eclipse.cdt.codan.internal.checkers.UnusedVariableDeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true,exceptions\=>("@(\#)","$Id")} +org.eclipse.cdt.codan.internal.checkers.VariableResolutionProblem=Error +org.eclipse.cdt.codan.internal.checkers.VariableResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} diff --git a/.settings/org.eclipse.cdt.managedbuilder.core.prefs b/.settings/org.eclipse.cdt.managedbuilder.core.prefs new file mode 100644 index 0000000..b91eaca --- /dev/null +++ b/.settings/org.eclipse.cdt.managedbuilder.core.prefs @@ -0,0 +1,11 @@ +eclipse.preferences.version=1 +environment/buildEnvironmentInclude/ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.1605704765/CPATH/delimiter=; +environment/buildEnvironmentInclude/ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.1605704765/CPATH/operation=remove +environment/buildEnvironmentInclude/ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.1605704765/C_INCLUDE_PATH/delimiter=; +environment/buildEnvironmentInclude/ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.1605704765/C_INCLUDE_PATH/operation=remove +environment/buildEnvironmentInclude/ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.1605704765/append=true +environment/buildEnvironmentInclude/ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.1605704765/appendContributed=true +environment/buildEnvironmentLibrary/ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.1605704765/LIBRARY_PATH/delimiter=; +environment/buildEnvironmentLibrary/ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.1605704765/LIBRARY_PATH/operation=remove +environment/buildEnvironmentLibrary/ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.1605704765/append=true +environment/buildEnvironmentLibrary/ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.1605704765/appendContributed=true diff --git a/LICENSE.txt b/LICENSE.txt new file mode 100644 index 0000000..315621d --- /dev/null +++ b/LICENSE.txt @@ -0,0 +1,203 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. \ No newline at end of file diff --git a/README.md b/README.md new file mode 100644 index 0000000..0184e96 --- /dev/null +++ b/README.md @@ -0,0 +1,18 @@ +Данный репозиторий включает РІ себя полноценный работоспособный проект для задач управления двигателем РЅР° базе микроконтроллеров серии 1921Р’Рљ035 фирмы РђРћ «НРРР­РўВ». РџРѕРјРёРјРѕ РёСЃС…РѕРґРЅРѕРіРѕ РєРѕРґР° проекта, репозиторий содержит специализированное программное обеспечение, позволяющее производить разработку, отладку Рё исследование систем управления через интерфейс CAN СЃ протоколом верхнего СѓСЂРѕРІРЅСЏ CANopen. Начинать знакомство СЃ данным РџРћ следует СЃ файла ```Описание структуры РџРћ MotorControlDemo.pdf```, находящегося РІ разделе [Downloads](https://bitbucket.org/niietcm4/motorcontroldemo/downloads/) репозитория [MotorControlDemo](https://bitbucket.org/niietcm4/motorcontroldemo/). + +Состав репозитория: + +- MotorControlDemo – проект СЃ исходными кодами - реализует различные структуры управления электродвигателями различных типов, РІ том числе СЃ обратными СЃРІСЏР·СЏРјРё РїРѕ току, скорости, положению. РџРћ поддерживает обработку следующих датчиков положения/скорости ротора: датчики Холла, инкрементальный энкодер. Реализована коммуникация РїРѕ интерфейсу CAN РїРѕ протоколу верхнего СѓСЂРѕРІРЅСЏ CANopen. РџРћ микроконтроллера разработано РІ +бесплатной среде разработки [VectorIDE (Eclipse+GCC+OpenOCD)](http://motorcontrol.ru/production/soft/vector-ide/). +- COODEdit4 NIIET edition - редактор словарей CANopen, далее COODEdit (CanOpen Object Dictionary Editor) – программный РїСЂРѕРґСѓРєС‚, позволяющий осуществлять редактирование словарей объектов для CANopen-совместимых устройств СЃ драйвером данной реализации РІ графическом РІРёРґРµ. Подробнее СЃ возможностями программы можно ознакомиться РІ руководстве пользователя - СЃРј. файл ```COODEdit user manual.pdf``` РІ разделе [Downloads](https://bitbucket.org/niietcm4/motorcontroldemo/downloads/) репозитория [MotorControlDemo](https://bitbucket.org/niietcm4/motorcontroldemo/). +- UniCON - управляющий интерфейс пользователя, набор программных средств, позволяющих осуществлять мониторинг (РІ том числе снятие осциллограмм переходных процессов) Рё настройку CANopen-совместимых устройств посредством персонального компьютера. UniCON РїСЂРё помощи переходника CAN-USB или USB-UART конвертора взаимодействует через CANopen СЃ РџРћ микроконтроллера Рё обеспечивает интерфейс пользователя. +Подробнее СЃ возможностями программы можно ознакомиться РІ руководстве пользователя - СЃРј. файл ```UniCON руководство пользователя.pdf``` РІ разделе [Downloads](https://bitbucket.org/niietcm4/motorcontroldemo/downloads/) репозитория [MotorControlDemo](https://bitbucket.org/niietcm4/motorcontroldemo/). + + +РЎ вопросами Рё предложениями можно обращаться: + +- motorcontrol@niiet.ru +- [тема](http://forum.niiet.ru/viewtopic.php?f=37&t=536) РЅР° интернет-форуме РђРћ «НРРР­РўВ» +- интернет-форум РћРћРћ «НПФ ВЕКТОР» http://motorcontrol.ru/forum/ + +*Если РІС‹ нашли ошибку РІ программном обеспечении или документации РїСЂРѕСЃСЊР±Р° РїРѕ возможности оповестить РѕР± этом разработчиков любым удобным СЃРїРѕСЃРѕР±РѕРј.* \ No newline at end of file diff --git a/Vinclude/CANBlockTransferInterface.h b/Vinclude/CANBlockTransferInterface.h new file mode 100644 index 0000000..88e70c5 --- /dev/null +++ b/Vinclude/CANBlockTransferInterface.h @@ -0,0 +1,68 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file CANBlockTransferInterface.h + \brief Блочная передача данных для CANopen + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup CANOpen_drv Драйвер CANOpen + @{ +*/ +#ifndef CANBLOCKTRANS_INTERFACE_H +#define CANBLOCKTRANS_INTERFACE_H + +#ifdef __cplusplus +extern "C" +{ +#endif +#include "DSP.h" + +#define CANBT_INTERFACE_FREE 0 +#define CANBT_INTERFACE_BUSY 0x8000 +#define CANBT_INTERFACE_FLASH_PROG 1 +#define CANBT_INTERFACE_DATALOG1 2 +#define CANBT_INTERFACE_DATALOG2 3 // используется для 32-битного даталоггера + +struct SCanBTInterface{ + Uint16 alreadyInit; //признак первого вызова дискетного автомата. + Uint16 state_shadow;//Теневое состояние. + Uint16 state_prev; //Предыдущее сосяние (на один такт) + Uint16 E; //Флаг первого вхождения. + Uint32 time_prev; + Uint64 state_time; //время нахождения в текущем состоянии, в тиках проца. Для 150Мгц максимальное время около 4тыс. лет :) + Uint16 BlockTransferCommand; + void (*ms_calc)(volatile struct SCanBTInterface* p, Uint32 time, TCo_OdVars* co_ptr); + void (*slow_calc)(volatile struct SCanBTInterface* p); + }; + +typedef volatile struct SCanBTInterface TCanBTInterface; + +#define T_CANBT_INTERFACE_DEFAULTS {0,CANBT_INTERFACE_FREE,0xFF,1,\ + 0,0,0,\ + SMCanBTInterface_ms,\ + SMCanBTInterface_slow} + +void SMCanBTInterface_ms(volatile struct SCanBTInterface* p, Uint32 time, TCo_OdVars* co_ptr); +void SMCanBTInterface_slow(volatile struct SCanBTInterface* p); + +//колбэки длЯ 2700.00 +void callback_BTcmd(Uint16 par, Uint16 tag_CANnum); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/Vinclude/CANOpen_drv.h b/Vinclude/CANOpen_drv.h new file mode 100644 index 0000000..f5651e1 --- /dev/null +++ b/Vinclude/CANOpen_drv.h @@ -0,0 +1,170 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file CANOpen_drv.h + \brief Драйвер CANOpen + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 3.19 2019_03_06 + + \defgroup CANOpen_drv Драйвер CANOpen + @{ +*/ + +#ifndef CAN_OPEN_DRV_H +#define CAN_OPEN_DRV_H + +#ifdef __cplusplus +extern "C" { +#endif + +//******************************************************************************************** +// + +//!Включатель CAN 1 +#define CAN_1_ENABLE +//******************************************************************************************** +//!Включатель CAN 2 +//#define CAN_2_ENABLE +//******************************************************************************************** +/* + * Функции инициализации драйвера для CAN1 и CAN2 + * Драйвер использует работу с пользовательской памятью (интерфейс с которой определяется функциями co_UserMemoryRead и co_UserMemoryWrite - + * см. файл CANOpenUDfuncs.c), поэтому к моменту начала работы с драйвером пользователь должен ГАРАНТИРОВАТЬ, + * что драйвер пользовательской памяти проинициализирован. + */ +extern Uint16 co1_Init(TCo_OdVars* ppc);//В случае если инициализациЯ не удалась функциЯ возвращает 0, иначе 1. +extern Uint16 co2_Init(TCo_OdVars* ppc);//В случае если инициализациЯ не удалась функциЯ возвращают 0, иначе 1. + +//ФункциЯ переинициализации CAN без восстановлениЯ параметров из пользовательской памяти (может быть использована лишь длЯ ПОВТОРНОЙ инициализации) +extern Uint16 co_ReInit(TCo_OdVars* ppc);//В случае если инициализациЯ не удалась функциЯ возвращают 0, иначе 1. +extern void propReset (void); +//Прототипы функций +extern void co_UserMemoryRead (const T_UserMemoryContext *p); +extern void co_UserMemoryWrite (const T_UserMemoryContext *p); + +#ifdef CAN_1_ENABLE +extern void co_CAN1GpioInit(); +extern void co_CAN1INTEnable(); +extern void co_CAN1INTDisable(); +#endif + +#ifdef CAN_2_ENABLE +extern void co_CAN2GpioInit(); +extern void co_CAN2INTDisable(); +extern void co_CAN2INTEnable(); +#endif + + +//!функция драйвера CANOpen вызываемая в прерывании 1 мс таймера, тактирующего работу драйвера +extern void co_1ms_calc(TCo_OdVars*); + +//!функция обработчика драйвера CANOpen в фоновой программе +extern void co_background_calc(TCo_OdVars*); + +//!Функция восстановления значений параметров словаря объектов по умолчанию +/*! +Результатом работы функции является восстановление параметров указанного +типа и диапазона +type - 1 rw-параметры + 2 rwp-параметры + 3 rwps-параметры +range - 1 восстановление индексов 1000h-1FFFh + 2,3,4,5 +Функция по времени выполнения относится к длиным (вызывать следует в фоне) */ +extern void co_ODexpositor_instaurationDefault(TCo_OdVars* ppc, Uint16 type, Uint16 range); + +//!Функция сохранения значений параметров словаря объектов в ЭнОЗУ +/*!Результатом работы функции является сохранение параметров указанного +типа и диапазона +type - 1 rw-параметры + 2 rwp-параметры + 3 rwps-параметры +range - 1 восстановление индексов 1000h-1FFFh + 2,3,4,5 +Функция по времени выполнения относится к длиным (вызывать следует в фоне).*/ +extern void co_ODexpositor_paramConservation(TCo_OdVars* ppc, Uint16 type, Uint16 range); + +//!Функция восстановления значений параметров словаря объектов из ЭнОЗУ +/*! Результатом работы функции является восстановление параметров указанного +типа и диапазона +type - 1 rw-параметры + 2 rwp-параметры + 3 rwps-параметры +range - 1 восстановление индексов 1000h-1FFFh + 2,3,4,5 +Внимание!!!Восстановление параметров 2-го и 3-го типов возможно если +переменная co_protectBit = 0. Если co_protectBit = 1 , то функция ничего +не "делает". +Если восстановление параметров заданного типа и диапазона произошло +неудачно(контрольная сумма не сошлась), то восстановление заданного +типа и диапазона повторяется.Если после трех попыток восстановление +не завершилось успехом, то выполняется восстановление параметров заданного +типа и диапазона по умолчанию. +Функция по времени выполнения относится к длиным (вызывать следует в фоне).*/ +extern void co_ODexpositor_paramInstauration(TCo_OdVars* ppc, Uint16 type, Uint16 range); + +// функции сервиса NMT +// драйвер может выступать NMT мастером, либо быть NMT слэйвом +//! функция для отправки NMT (нужна только для NMT мастера) +void co_sendNMT(TCo_OdVars* ppc, Uint16 nmtCommand, Uint16 nmtNODE_ID); + +//!функция ПОЛЬЗОВАТЕЛя для отправки SDO запросов на чтение параметров сервера +extern void co_SDOrequestRead(TCo_OdVars*); +//!функция ПОЛЬЗОВАТЕЛя для отправки SDO запросов на запись параметров сервера +extern void co_SDOrequestWrite(TCo_OdVars*); + +extern void Z_co_receiveSDOrequest(TCo_OdVars*, TZCanMsg*); +extern void co_CANToExtInterface_Send(TZCanMsg* MSG, Uint16 tag_CANnum); + +/*!ФункциЯ возвращает адрес переменной по переданным индексу + и подындексу. Если "свЯзаннаЯ" переменнаЯ 32-х разрЯднаЯ, то + возвращаетсЯ указатель на старшую часть. + ВНИМАНИЕ!!!Если запрошенного индекса и подиндекса не существует, то + функциЯ возвращает 0 (это нужно обЯзательно отслеживать). */ +extern Uint16 * co_getAddr(TCo_OdVars* ppc, Uint32 ind_subind); +// Функция получения информации об объекте с заданным адресом. +// Возвращает 0, если объект не найден. +extern Uint16 co_getObjectInfo( + TCo_OdVars* ppc, // указатель на структуру используемого модуля CANopen + Uint32 ind_subind, // биты 16-31 - индекс, биты 0-7 - подындекс объекта + TObjectInfo* pObjectInfo // указатель на структуру, куда будет помещена информация об объекте + ); + +extern void co_RPDO1_Callback(Uint16 nodeID, Uint16 tag_CANnum); +extern void co_RPDO2_Callback(Uint16 nodeID, Uint16 tag_CANnum); +extern void co_RPDO3_Callback(Uint16 nodeID, Uint16 tag_CANnum); +extern void co_RPDO4_Callback(Uint16 nodeID, Uint16 tag_CANnum); +extern void co_RPDO5_Callback(Uint16 nodeID, Uint16 tag_CANnum); +extern void co_RPDO6_Callback(Uint16 nodeID, Uint16 tag_CANnum); +extern void co_RPDO7_Callback(Uint16 nodeID, Uint16 tag_CANnum); +extern void co_RPDO8_Callback(Uint16 nodeID, Uint16 tag_CANnum); + + +//функции ПОЛЬЗОВАТЕЛя, инициирующие передачу, или прием блока данных посредством +//сервиса блочной передачи +extern void CANBlockTransferInitTX(TCo_OdVars* ppc, Uint16 size, Uint16* source_ptr); +extern void CANBlockTransferInitRX(TCo_OdVars* ppc, Uint16 size, Uint16* dest_ptr); + + +#ifdef __cplusplus +} +#endif + + +#endif + + +/*@}*/ + diff --git a/Vinclude/DRV_INTERFACE.h b/Vinclude/DRV_INTERFACE.h new file mode 100644 index 0000000..7d1bb25 --- /dev/null +++ b/Vinclude/DRV_INTERFACE.h @@ -0,0 +1,83 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file DRV_INTERFACE.h + \brief Через данные модуль обеспечиваетсЯ работа с банком аварий (чтение, очистка). + //ПредполагаетсЯ, что модуль может расширЯть функциональность (скачивать каие-то другие данные)... + //ПРИМЕЧАНИЕ для программиста: + 1.для команд работающих по сети с автоматизированными системами (Юникон,, пульты и т.д.) после выполнения команды поле ans_data должно быть установлено значением запроса: + p->ans_data = temp; + что сообщит внешней системе, что запрос обработан. В этом случае поле p->ans_data обнуляется внешней автоматизированной системой после сбора информации с полей + p->data_Low + p->data_High + 2.для внутренних вызовов поле p->ans_data трогать не нужно + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.1 2017_07_24 + +*/ +// пример использованиЯ в модуле main +#ifndef DRV_INTERFACE_H +#define DRV_INTERFACE_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +#define DRV_INTERFACE_RESET_TIME 10 //выдержка в сек перед обнулением параметра Ans_Data + +//!запрос на чтение аварии +#define DATA_REQUEST_READ_FAULT 1 +//!запрос на запись аварии +#define DATA_REQUEST_WRITE_FAULT 2 +//!запрос на запись рабочего времени +#define DATA_REQUEST_WRITE_WORK_TIME 3 +//!запрос на чтение рабочего времени +#define DATA_REQUEST_READ_WORK_TIME 4 +#define DATA_REQUEST_WRITE_OPER_TIME 5 +//!запрос на чтение времени во включенном состоЯнии +#define DATA_REQUEST_READ_OPER_TIME 6 +//!очистка всего +#define DATA_REQUEST_CLEAR_ALL 10 + + + struct SDrvInterface + { + long req_data; + long ans_data; + long data_High; + long data_Low; + + long INTERFACE_time_sec;//!< + long INTERFACE_delta_time_sec;//!< + void (*calc)(struct SDrvInterface*); + }; + + typedef struct SDrvInterface TDrvInterface; + +#define DRV_INTERFACE_DEFAULTS {0,0,0,0,\ + 0,0,\ + DRV_INTERFACE_Calc,\ + } + + void DRV_INTERFACE_Calc(TDrvInterface*); + +#ifdef __cplusplus +} +#endif + +#endif + + diff --git a/Vinclude/DSP.h b/Vinclude/DSP.h new file mode 100644 index 0000000..c3923e6 --- /dev/null +++ b/Vinclude/DSP.h @@ -0,0 +1,68 @@ +/****************************************************************************** + * @file DSP.h + * @brief Файл подключения заголовочных файлов периферии и объявления системных констант + * @version v1.0 + * @date 11 декабря 2015 + * + * @note + * ООО "НПФ Вектор", все права защищены. Наш сайт: http://motorcontrol.ru + * + * @par + * ООО "НПФ Вектор" распространяет это программное обеспечение в демонстрационных + * целях, и оно может распространяться свободно. + * + * @par + * Данное программное обеспечение распространяется "как есть", и Вы, + * его пользователь, принимаете на себя все риски, связанные с его использованием. + * ООО "НПФ Вектор" не несет никакой ответственности за возможные убытки, + * связанные с его использованием. + * + ******************************************************************************/ + +#ifndef VINCLUDE_DSP_H_ +#define VINCLUDE_DSP_H_ + +#define __CM4_REV 0x0001 //в K1921VK01T.h есть объявление __CM4F_REV, но в core_cm4.h проверяется именно __CM4_REV. Если не объявлено там объявляется нулем и больше нигде, вроде, не используется эта константа +#define __CHECK_DEVICE_DEFINES + + +#include + +#include "K1921VK035.h" +#include "core_cm4.h" /* Cortex-M4 processor and core peripherals */ +#include //для memcpy +#include "EPwm_defines.h" + +typedef char int8; +typedef unsigned char Uint8; +typedef unsigned short int Uint16; +typedef unsigned int Uint32; +typedef short int int16; +typedef int int32; +typedef unsigned long long Uint64; +typedef long long int64; + +//Указатели на секцию памяти fastcode, где лежат функции для копирования из флеша в оперативку. +//Определены в файле компоновки памяти. +extern int __fastcode_ram_start; +extern int __fastcode_ram_end; +extern int __fastcode_flash_start; + +extern int __isr_vector_flash_start; +extern int __isr_vector_ram_start; +extern int __isr_vector_ram_end; + +//! Запрет прерываний +#define DINT __disable_irq() +//! Разрешение прерываний +#define EINT __enable_irq() + +#define IRQ_PRIORITY_TZ 1 +#define IRQ_PRIORITY_ADC 2 +#define IRQ_PRIORITY_10K 3 +#define IRQ_PRIORITY_CAP 4 +#define IRQ_PRIORITY_CAN 5 +#define IRQ_PRIORITY_1K 6 +#define IRQ_PRIORITY_EQEP 6 + +#endif /* VINCLUDE_DSP_H_ */ diff --git a/Vinclude/EPwm_defines.h b/Vinclude/EPwm_defines.h new file mode 100644 index 0000000..2d46b17 --- /dev/null +++ b/Vinclude/EPwm_defines.h @@ -0,0 +1,183 @@ +/****************************************************************************** + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + * @file EPwm_defines.h + * @brief Файл объявления системных констант для работы с ШИМ модулями + * @author ООО "НПФ Вектор". http://motorcontrol.ru + * @version v1.0 + * @date 11 декабря 2015 + + ******************************************************************************/ + +#ifndef EPWM_DEFINES_H +#define EPWM_DEFINES_H + + +#ifdef __cplusplus +extern "C" { +#endif + +// TBCTL (Time-Base Control) + + +// CTRMODE bits +#define TB_COUNT_UP 0x0 +#define TB_COUNT_DOWN 0x1 +#define TB_COUNT_UPDOWN 0x2 +#define TB_FREEZE 0x3 + +// PHSEN bit +#define TB_DISABLE 0x0 +#define TB_ENABLE 0x1 + +// PRDLD bit +#define TB_SHADOW 0x0 +#define TB_IMMEDIATE 0x1 + +// SYNCOSEL bits +#define TB_SYNC_IN 0x0 +#define TB_CTR_ZERO 0x1 +#define TB_CTR_CMPB 0x2 +#define TB_SYNC_DISABLE 0x3 + +// HSPCLKDIV and CLKDIV bits +#define TB_DIV1 0x0 +#define TB_DIV2 0x1 +#define TB_DIV4 0x2 + +// PHSDIR bit +#define TB_DOWN 0x0 +#define TB_UP 0x1 + +// CMPCTL (Compare Control) + +// LOADAMODE and LOADBMODE bits +#define CC_CTR_ZERO 0x0 +#define CC_CTR_PRD 0x1 +#define CC_CTR_ZERO_PRD 0x2 +#define CC_LD_DISABLE 0x3 + +// SHDWAMODE and SHDWBMODE bits +#define CC_SHADOW 0x0 +#define CC_IMMEDIATE 0x1 + + +// AQCTLA and AQCTLB (Action Qualifier Control) + +// ZRO, PRD, CAU, CAD, CBU, CBD bits +#define AQ_NO_ACTION 0x0 +#define AQ_CLEAR 0x1 +#define AQ_SET 0x2 +#define AQ_TOGGLE 0x3 + +// DBCTL (Dead-Band Control) + +// OUT MODE bits +#define DB_DISABLE 0x0 +#define DBA_ENABLE 0x1 +#define DBB_ENABLE 0x2 +#define DB_FULL_ENABLE 0x3 + +// POLSEL bits +#define DB_ACTV_HI 0x0 +#define DB_ACTV_LOC 0x1 +#define DB_ACTV_HIC 0x2 +#define DB_ACTV_LO 0x3 + +// IN MODE +#define DBA_ALL 0x0 +#define DBB_RED_DBA_FED 0x1 +#define DBA_RED_DBB_FED 0x2 +#define DBB_ALL 0x3 + +// CHPCTL (chopper control) + +// CHPEN bit +#define CHP_DISABLE 0x0 +#define CHP_ENABLE 0x1 + +// CHPFREQ bits +#define CHP_DIV1 0x0 +#define CHP_DIV2 0x1 +#define CHP_DIV3 0x2 +#define CHP_DIV4 0x3 +#define CHP_DIV5 0x4 +#define CHP_DIV6 0x5 +#define CHP_DIV7 0x6 +#define CHP_DIV8 0x7 + +// CHPDUTY bits +#define CHP1_8TH 0x0 +#define CHP2_8TH 0x1 +#define CHP3_8TH 0x2 +#define CHP4_8TH 0x3 +#define CHP5_8TH 0x4 +#define CHP6_8TH 0x5 +#define CHP7_8TH 0x6 + +// TZSEL (Trip Zone Select) +//========================== +// CBCn and OSHTn bits +#define TZ_DISABLE 0x0 +#define TZ_ENABLE 0x1 + +// TZCTL (Trip Zone Control) +//========================== +// TZA and TZB bits +#define TZ_HIZ 0x0 +#define TZ_FORCE_HI 0x1 +#define TZ_FORCE_LO 0x2 +#define TZ_NO_CHANGE 0x3 + +// ETSEL (Event Trigger Select) +//============================= +#define ET_CTR_ZERO 0x1 +#define ET_CTR_PRD 0x2 +#define ET_CTRU_CMPA 0x4 +#define ET_CTRD_CMPA 0x5 +#define ET_CTRU_CMPB 0x6 +#define ET_CTRD_CMPB 0x7 + +// ETPS (Event Trigger Pre-scale) +//=============================== +// INTPRD, SOCAPRD, SOCBPRD bits +#define ET_DISABLE 0x0 +#define ET_1ST 0x1 +#define ET_2ND 0x2 +#define ET_3RD 0x3 + + +//-------------------------------- +// HRPWM (High Resolution PWM) +//================================ +// HRCNFG +#define HR_Disable 0x0 +#define HR_REP 0x1 +#define HR_FEP 0x2 +#define HR_BEP 0x3 + +#define HR_CMP 0x0 +#define HR_PHS 0x1 + +#define HR_CTR_ZERO 0x0 +#define HR_CTR_PRD 0x1 + + +#ifdef __cplusplus +} +#endif /* extern "C" */ + +#endif + diff --git a/Vinclude/Global_time.h b/Vinclude/Global_time.h new file mode 100644 index 0000000..cc2a119 --- /dev/null +++ b/Vinclude/Global_time.h @@ -0,0 +1,196 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file Global_time.h + \brief Модуль работы со временем + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 1.1 2010_02_24 + +*/ + +#ifndef GLOBAL_TIME_H +#define GLOBAL_TIME_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include "DSP.h" + +#define GLOBAL_TIME_CALC_FREQ 10 //!<кГц частота вызова функции calc +//#define USE_ABSOLUTE_TIME_CLOCK //раскоментировать если используютсЯ часы реального времени + + + +#define GLOBAL_TIME_SPI_START_ADDR 6500 //!<начальный адрес в SPI + +#define GLOBAL_TIME_POWER_ON_TIME_ADDR GLOBAL_TIME_SPI_START_ADDR +#define GLOBAL_TIME_OPERATIONAL_TIME_ADDR GLOBAL_TIME_SPI_START_ADDR + 4 + + +//!Абсолютное времЯ + struct SABSOLUTE_TIME + { + int16 second; + int16 minute; + int16 hour; + int16 day; + int16 year; + }; + typedef volatile struct SABSOLUTE_TIME ABSOLUTE_TIME; + +//!ОтносительнаЯ дата + typedef struct + { + int16 millisecond; + int16 second; + int16 minute; + int32 hour; + }RELATIVE_DATE; + + +//!Относительное времЯ + struct SRELATIVE_TIME + { + int ON; + Uint32 tic_isr; + Uint32 millisecond_counter; + Uint32 second_counter; + int16 delta_millisecond; + int16 delta_second; + RELATIVE_DATE relative_date; + }; + typedef volatile struct SRELATIVE_TIME RELATIVE_TIME; + + + + /*! \class TGlobalTime + \brief Модуль работы со временем. + + Класс \a TGlobalTime, основанный на структуре SGlobalTime, содержит методы + длЯ работы со временем.Отсчитывает времЯ в:\n + длЯ отсчета времени работы и т.д.:\n + милисекунды: 0-999\n + секунды: 0-59\n + минуты: 0-59\n + часы: 0-23\n + дни: 0-364\n + года: 0-примерно до 160 лет\n + длЯ отсчета дельт (приращений времени):\n + милисекунды: 0-0xFFFFFFFF - соответствует примерно 1.5 месЯцам\n + секунды: 0-0xFFFFFFFF - соответствует примерно 160 годам\n + + Есть специальный способ, позволЯющий отсчитывать выдержки времени с точностью + до миллисекунд в перывании ШИМ. ИспользуетсЯ переменнаЯ delta_millisecond, + котораЯ возводитсЯ в единицу каждую миллисекунду и на следующем периоде ШИМ + сбрасываетсЯ. Тогда можно в необходимый счетчик добавить counter+=delta_millisecond и + получить в counter счетчик миллисекунд. Аналогично delta_second. + + ПРИМЕЧАНИЕ: 1. модуль не требует инициализации + 2. автоматически перенастраиваетсЯ при изменении несущей частоты + + ДЛЯ КОРРЕКТНОЙ РАБОТЫ МОДУЛЯ ПОЛЬЗОВАТЕЛЬ ДОЛЖЕН: + 1. в макросе GLOBAL_TIME_CALC_FREQ правильно указать несущую частоту вызова функции расчета. + Следует отметить, что значение GLOBAL_TIME_CALC_FREQ целочисленное, поэтому + модуль корректно работает только при целых значениЯх несущей частоты (в кГц). + Недостаток свЯзан с конкретной реализацией модулЯ. + */ + +//! см. TGlobalTime + struct SGlobalTime + { + RELATIVE_TIME relative_time1;//!относительное времЯ 1 + RELATIVE_TIME relative_time2;//!относительное времЯ 2 + ABSOLUTE_TIME absolute_time;//!абсолютное времЯ + int16 time_type;//!часы реального времени (1 - есть) + int32 PowerOn_time; //!<Общее времЯ наработки + int32 PowerOn_time_min; //!<Общее времЯ наработки в минутах + int32 operational_time; //!<Общее времЯ включенного состоЯниЯ + int32 operational_time_min; //!<Общее времЯ включенного состоЯниЯ в минутах + int16 WtiteSPI_flag; + int32 PrevWriteSPIHour; + void (*init)(volatile struct SGlobalTime*); + void (*calc)(volatile struct SGlobalTime*); + void (*ms_calc)(volatile struct SGlobalTime*); + void (*slow_calc)(volatile struct SGlobalTime*); + void (*read_PowerOn_time)(volatile struct SGlobalTime*); + void (*write_PowerOn_time)(volatile struct SGlobalTime*); + void (*read_oper_time) (volatile struct SGlobalTime*); + void (*write_oper_time)(volatile struct SGlobalTime*); + }; + + typedef volatile struct SGlobalTime TGlobalTime; + +//!Иницализатор относительной даты. +#define RELATIVE_DATE_DEFAULTS {0,0,0,0} + +//!Инициализатор относительного времени. +#define RELATIVE_TIME_DEFAULTS {0,\ + 0,0,0,0,0,\ + RELATIVE_DATE_DEFAULTS,\ + } +//!Инициализатор абсолютного времени. +#define ABSOLUTE_TIME_DEFAULTS {0,0,0,0,0} + +//!Инициализатор TGlobalTime. +#define GLOBAL_TIME_DEFAULTS { RELATIVE_TIME_DEFAULTS,\ + RELATIVE_TIME_DEFAULTS,\ + ABSOLUTE_TIME_DEFAULTS,\ + 1,0,0,0,0,0,0,\ + GlobalTime_init,\ + GlobalTime_calc,\ + GlobalTime_ms_calc,\ + GlobalTime_slow_calc,\ + GlobalTime_read_PowerOn_time, \ + GlobalTime_write_PowerOn_time, \ + GlobalTime_read_oper_time, \ + GlobalTime_write_oper_time,\ + } + +//! \memberof TGlobalTime + void GlobalTime_init(TGlobalTime*); +//! \memberof TGlobalTime + void GlobalTime_calc(TGlobalTime*); + //! \memberof TGlobalTime + void GlobalTime_ms_calc(TGlobalTime*); +//! \memberof TGlobalTime + void GlobalTime_slow_calc(TGlobalTime*); + +//! \memberof TGlobalTime + void GlobalTime_REL_TIME_calc(RELATIVE_TIME *p); + +//! \memberof TGlobalTime +void GlobalTime_read_PowerOn_time(TGlobalTime*); +//! \memberof TGlobalTime +void GlobalTime_write_PowerOn_time(TGlobalTime*); +//! \memberof TGlobalTime +void GlobalTime_read_oper_time(TGlobalTime*); +//! \memberof TGlobalTime +void GlobalTime_write_oper_time(TGlobalTime*); + + + +#ifdef __cplusplus +} +#endif + + +#endif + + + +/*@}*/ + diff --git a/Vinclude/SM_CmdLogic.h b/Vinclude/SM_CmdLogic.h new file mode 100644 index 0000000..394d9b7 --- /dev/null +++ b/Vinclude/SM_CmdLogic.h @@ -0,0 +1,96 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file SMCmdLogic.h + \brief Обработка команд и заданий, поступающих из различных источников. (см. TSM_CmdLogic) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup SMCmdLogic Обработка команд и заданий, поступающих из различных источников. (см. TSM_CmdLogic) + @{ +*/ + + +#ifndef SM_CmdLogicH +#define SM_CmdLogicH + +#include "V_common.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + + +//! Система остановлена, готова к запуску (ГОТОВ) +#define CMD_LOGIC_TURNED_OFF 0x0 +//! Состояние РАБОТА +#define CMD_LOGIC_TURNED_ON 0x2 + +/*! \class TSM_CmdLogic + \brief Обработка команд и заданий, поступающих из различных источников. + + Класс \a TSM_CmdLogic, основанный на структуре SSMCmdLogic, служит для обработки команд + оперативного управления и задания скорости. Команды могут поступать как по CANOpen, + так и по другим протоколам (ModBus). Содержит дискретный автомат, который переключает + систему между состояниями РАБОТА и ОСТАНОВ (ГОТОВ). +*/ + +//! см. TSM_CmdLogic + struct SSM_CmdLogic + { + int state;//!DATA & (1 << 7)) + + +/*! \class TSM_Protect + \brief Модуль защит. + + Класс \a TSM_Protect, основанный на структуре SSMProtect, + обрабатывает все возможные аварийные ситуации и возводит соответствующий этой + аварии бит в одном из слов bit_fault 1-2. далее происходит обработка этих слов, и, + если эта авария не замаскирована, происходит останов привода. +*/ + +//! см. TSM_Protect + struct SSM_Protect + { + Uint16 state;//!< Состояние + Uint16 state_prev;//!< Состояние предыдущее + + Uint16 readDrvSts; //!<Флаг запроса чтения статуса drv8301 + Uint16 clearDrvFault; //!<Флаг запроса сброса аварии drv8301 + + Uint16 bit_fault1;//!<Слово аварий 1 + Uint16 bit_fault2;//!<Слово аварий 2 + + Uint16 masked_bit_fault1;//!<Слово аварий после маскирования + Uint16 masked_bit_fault2;//!<Слово аварий после маскирования + + Uint16 mask_fault1;//!<Маска аварий 1 + Uint16 mask_fault2;//!<Маска аварий 2 + + Uint16 bit_fault_written1; + Uint16 bit_fault_written2; + + long Imax_protect; //!<Уставка максимально-токовой защиты + long Umax_protect; //!<Уставка защиты max напряжения на ЗПТ + long Umin_protect;//!<Уставка защиты min напряжения на ЗПТ + long speed_max;//!<Уставка максимальной скорости + long T_max; + + int E;//!<Флаг первого вхождения + Uint16 Main_ErrorCode;//!< //листающийся код аварии + Uint32 Main_Flags;//!< //Флаг аварийной блокировки блока + Uint16 powered_okCounter;//!< Счетчик для ожидания включеня модуля защит после инециализации + void (*init)(struct SSM_Protect*); /* Pointer to the init funcion */ + void (*slow_calc)(struct SSM_Protect*); /* Pointer to the calc funtion */ + void (*fast_calc)(struct SSM_Protect*); /* Pointer to the calc funtion */ + void (*ms_calc)(struct SSM_Protect*); /* Pointer to the calc funtion */ + } ; + typedef struct SSM_Protect TSM_Protect; + + //!Инициализатор по умолчанию +#define SM_PROTECT_DEFAULTS {0,0,\ + 0,0,\ + 0,0,\ + 0,0,\ + 0,0,\ + 0,0,\ + 0,0,0,0,0,\ + 0,0,0,0,\ + SM_Protect_Init,\ + SM_Protect_Slow_Calc,\ + SM_Protect_Fast_Calc,\ + SM_Protect_ms_Calc,\ + } + +//! \memberof TSM_Protect + void SM_Protect_Init(TSM_Protect*); +//! \memberof TSM_Protect + void SM_Protect_Slow_Calc(TSM_Protect*); +//! \memberof TSM_Protect + void SM_Protect_Fast_Calc(TSM_Protect*); +//! \memberof TSM_Protect + void SM_Protect_ms_Calc(TSM_Protect*); + +#ifdef __cplusplus +} +#endif + +#endif + +/*@}*/ + + + + + + diff --git a/Vinclude/SM_Sys.h b/Vinclude/SM_Sys.h new file mode 100644 index 0000000..ef6522a --- /dev/null +++ b/Vinclude/SM_Sys.h @@ -0,0 +1,90 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file SMSys.h + \brief Модуль-обертка для расчета остальных модулей. (см. TSM_Sys) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup SMSys Модуль-обертка для расчета остальных модулей. (см. TSM_Sys) + @{ +*/ + +#ifndef SM_Sys_H +#define SM_Sys_H + +#ifdef __cplusplus +extern "C" +{ +#endif + + //! Система в инициализации + #define SYS_INIT 0 + //! Система проинициализирована + #define SYS_READY 1 + + +/*! \class TSM_Sys + \brief Модуль-обертка для расчета остальных модулей. + + Класс \a TSM_Sys, основанный на структуре SSMSys, является модулем, + внутри методов которого происходит вызов большинства остальных. Например, + функция быстрого расчета данного модуля вызывает функции быстрого расчета + остальных модулей. Кроме того, в инициализации данного модуля настраиваются прерывания + контроллера. + */ + +//! см. TSM_Sys + struct SSM_Sys + { + int state;//!< Состояние + int state_prev;//!< Состояние предыдущее + int E;//!<Флаг первого вхождения + void (*init)(struct SSM_Sys*); /* Pointer to the init funcion */ + void (*slow_calc)(struct SSM_Sys*); /* Pointer to the calc funtion */ + void (*fast_calc)(struct SSM_Sys*); /* Pointer to the calc funtion */ + void (*ms_calc)(struct SSM_Sys*); /* Pointer to the calc funtion */ + } ; + + typedef struct SSM_Sys TSM_Sys; + +//!Инициализатор по умолчанию +#define SM_Sys_DEFAULTS {0,0,0,\ + SM_Sys_Init,\ + SM_Sys_Slow_Calc,\ + SM_Sys_Fast_Calc,\ + SM_Sys_ms_Calc,\ + } + + //! \memberof TSM_Sys + void SM_Sys_Init(TSM_Sys*); + //! \memberof TSM_Sys + void SM_Sys_Slow_Calc(TSM_Sys*); + //! \memberof TSM_Sys + void SM_Sys_Fast_Calc(TSM_Sys*); + //! \memberof TSM_Sys + void SM_Sys_ms_Calc(TSM_Sys*); + +#ifdef __cplusplus +} +#endif + +#endif + +/*@}*/ + + + + diff --git a/Vinclude/V_AutoOffset.h b/Vinclude/V_AutoOffset.h new file mode 100644 index 0000000..515e7f4 --- /dev/null +++ b/Vinclude/V_AutoOffset.h @@ -0,0 +1,72 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_AutoOffset.h (IQ version) + \brief Автоматический расчет смещения для АЦП + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + + + + Данное программное обеспечение распространяется "как есть", и Вы, + его пользователь, принимаете на себя все риски, связанные с его использованием. + ООО "НПФ Вектор" не несет никакой ответственности за возможные убытки, + связанные с его использованием. + +*/ + + +#ifndef V_AUTO_OFFSET_H +#define V_AUTO_OFFSET_H + +#ifdef __cplusplus +extern "C" +{ +#endif +#include "DSP.h" + + struct SAutoOffset + { + _iq FilterK;//!< Коэффициент фильтра (темп изменения смещения) + int32 IA_int; //!< Интегратор для тока фазы A + int32 IB_int; //!< Интегратор для тока фазы B + int32 IC_int; //!< Интегратор для тока фазы C + int Enabled; //!< Включено/выключено + void (*init)(volatile struct SAutoOffset *); + void (*ms_calc)(volatile struct SAutoOffset *); + void (*slow_calc)(volatile struct SAutoOffset *); + }; + + typedef volatile struct SAutoOffset TAutoOffset; + + +#define AUTO_OFFSET_DEFAULTS {\ + _IQ(0.0001),\ + 0,0,0,\ + 0,\ + AutoOffset_init,\ + AutoOffset_calc,\ + AutoOffset_slow_calc} + + void AutoOffset_init(TAutoOffset *); + void AutoOffset_calc(TAutoOffset *); + void AutoOffset_slow_calc(TAutoOffset *); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/Vinclude/V_CANtoRS.h b/Vinclude/V_CANtoRS.h new file mode 100644 index 0000000..9df3a86 --- /dev/null +++ b/Vinclude/V_CANtoRS.h @@ -0,0 +1,110 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file v_CANtoRS.h + \brief Преобразователь посылок CAN в RS/USB и обратно. Работает +совместно с драйвером CANOpen + + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 3.0 08/08/2017 + +*/ + +#ifndef V_CAN_TO_RS_H +#define V_CAN_TO_RS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#define CANTORS_BUFSIZE 20 +#define CANTORS_TRANSM_TIME_OUT 10 +#define CANTORS_READ_DATA_MAX_LEN 10 +#define CANTORS_HEART_COUNTER_MAX 1000 + + +#define CANTORS_ACTIVE 0x1 +#define CANTOUSB_ACTIVE 0x2 + +#include "DSP.h" +#include "CANOpen_drv.h" + +struct SCANtoRS { + Uint16 lastActiveConnection; // Определяет, какой интерфейс был активен в последний раз - USB или RS + Uint8 tempBuf[13]; // Временный буфер для данных + Uint16 test_dbg; //для отладки + Uint16 APIpacketMode; + int16 HeartBeatGo;//пропустите сердцебиение! + Uint16 callback_go; //флаг для вызова callback + Uint16 TransmBusy; //флаг занятости передатчика + Uint16 PacketInWait; //флаг если есть что-то в буфере отправки + Uint16 HeartCounter; //счетчик для отправки HeartBeat + Uint16 TransmBusyTimeCount; //счетчик таймаута занятости передатчика + Uint16 ReadPackDataCounter; //счетчик данных в пакете + Uint16 ReadCRCCounter; //счетчик данных в пакете + Uint16 SendTimeoutCounter; + Uint16 all_len; //transmit buf len + Uint16 tr_counter; //transmit counter + Uint16 MessDrop1; + Uint16 MessDrop2; + Uint16 MessDrop3; + Uint16 CounterWrongCRC; + Uint16 CounterRes; + Uint16 CounterSended; + void (*init)(volatile struct SCANtoRS *); /* Pointer to the init function */ + void (*calc)(volatile struct SCANtoRS *); /* Pointer to the calc function */ + void (*receive)(volatile struct SCANtoRS *); + Uint16 (*write)(TZCanMsg* MSG,volatile struct SCANtoRS *); + void (*callback)(TCo_OdVars* ppc, TZCanMsg* p); + unsigned char buf_out[CANTORS_BUFSIZE]; + Uint16 temp_buf[CANTORS_BUFSIZE]; + TZCanMsg MSG; + TZCanMsg bufMSG; + Uint16 ReadPackData[CANTORS_BUFSIZE]; //буфер для API посылки + Uint16 ReadCRC[2]; //буфер для СRC + Uint16 TempData[10]; + Uint16* nodeID; + UART_TypeDef *UART;//!Указатель на используемый модуль UART + }; + +typedef volatile struct SCANtoRS TCANtoRS; + + +void CANtoRS_init(TCANtoRS*); +void CANtoRS_calc(TCANtoRS*); +void CANtoRS_Receive(TCANtoRS*); +Uint16 CANtoRS_SendP(Uint16* Data, int16 len,TCANtoRS *p); +Uint16 CANtoRS_Write(TZCanMsg* MSG,TCANtoRS *p); +Uint16 CANtoRS_WriteHelper(TZCanMsg* MSG,TCANtoRS *p); +void CANtoRS_HeartBeat(TCANtoRS *p); +Uint16 CANtoRS_C_CRC(TCANtoRS *p,Uint16 *Data,Uint16 len); +void CANtoRS_Analysis(TCANtoRS*); + + +//если добавляем в струкуру переменные то добавляем значения по умолчанию +#define CAN_TO_RS_DEFAULTS { .init = CANtoRS_init,\ + .calc = CANtoRS_calc,\ + .receive = CANtoRS_Receive,\ + .write = CANtoRS_WriteHelper} + +#ifdef __cplusplus +} +#endif + +#endif + + + + diff --git a/Vinclude/V_CurPar.h b/Vinclude/V_CurPar.h new file mode 100644 index 0000000..d300179 --- /dev/null +++ b/Vinclude/V_CurPar.h @@ -0,0 +1,101 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_CurPar.h + \brief Расчет наблюдаемых текущих параметров (см. TCurPar) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup V_CurPar Расчет наблюдаемых текущих параметров (см. TCurPar) + + @{ +*/ + + +#ifndef V_CURPAR_H +#define V_CURPAR_H + +#include "filter.h" + +#ifdef __cplusplus +extern "C" { +#endif + + + /*! \class TCurPar + \brief Расчет наблюдаемых текущих параметров + + Класс \a TCurPar, основанный на структуре SCurPar, содержит + ряд разрозненных вычислений для отображения текущих параметров привода. + Например, расчет действующих токов фаз, текущей мощности и т.п. + */ + +//! см. TCurPar +struct SCurPar{ + long speed; //!< Текущая частота вращения + long power; //!< Текущая мощность + long Is; //!< Текущая ток статора амплитудный мгновенный + long ThetaRefCurr; //!< Заданное угловое положение + long ThetaCurr; //!< Текущее угловое положение + + long IsRef; //!< Ток статора заданный + long Ialpha; //!< Ток по оси альфа + long Ibeta; //!< Ток по оси бетта + + long Ualpha; //!< Напряжение по оси альфа + long Ubeta; //!< Напряжение по оси бетта + long PowerK; //!< Служебный параметр для масштабирования мощности + + TFilter fPower; //!< Фильтр мощности + + void (*init)(volatile struct SCurPar*);//!< процедура инициализации + void (*calc)(volatile struct SCurPar*);//!<расчет + void (*slow_calc)(volatile struct SCurPar*);//!<медленный расчет +}; + +typedef volatile struct SCurPar TCurPar; + + +//!инициализатор по-умолчанию +#define TCUR_PAR_DEFAULTS \ +{\ + 0,0,0,0,0,\ + 0,0,0,\ + 0,0,0,\ + FILTER_DEFAULTS,\ + &CurPar_init, \ + &CurPar_calc, \ + &CurPar_slow_calc, \ +} + + +//! \memberof TCurPar +void CurPar_init(TCurPar*); +//! \memberof TCurPar +void CurPar_calc(TCurPar*); +//! \memberof TCurPar +void CurPar_slow_calc(TCurPar*); + + + +#ifdef __cplusplus +} +#endif // extern "C" + +#endif // V_UF_H + +/*@}*/ + + diff --git a/Vinclude/V_DPR_eCAP.h b/Vinclude/V_DPR_eCAP.h new file mode 100644 index 0000000..c4d69c7 --- /dev/null +++ b/Vinclude/V_DPR_eCAP.h @@ -0,0 +1,226 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_DPR_eCAP.h + \brief Модуль расчёта скорости и положения по трём датчикам на элементах Холла. + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + +*/ + +#ifndef V_DPR_ECAP_H +#define V_DPR_ECAP_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +struct SDPReCAPFLG1_BITS // bits + { +Uint16 AngleMode: + 1; // 0 Режим расчета угла: 0 - 6 секторов, 1 - интерполяция +Uint16 SpeedMode: + 1; // 1 Режим расчета скорости: 0 - по каждому датчику, 1 - по каждой метке +Uint16 Dir: + 1; // 2 Направление движения: 0 - по часовой, 1 - против. +Uint16 PrevDir: + 1; // 3 Направление движения: 0 - по часовой, 1 - против. +Uint16 CAPnumber: + 2; // 4-5 Номер eCAP, по которому было предыдущее прерывание. +Uint16 ZeroFLG: + 1; // 6 Флаг обнуления скорости +Uint16 SpeedMinFLG: + 1; // 7 + +Uint16 firstlaunch1:1; //!< 1 FLAG: первое попадание в прерывание eCAP1. +Uint16 firstlaunch2:1; //!< 2 FLAG: первое попадание в прерывание eCAP2. +Uint16 firstlaunch3:1; //!< 3 FLAG: первое попадание в прерывание eCAP3. +Uint16 rsvd: + 5; // 8-15 reserved; + }; + + union SDPReCAP_FLG1 + { + Uint16 all; + struct SDPReCAPFLG1_BITS bit; + }; + + struct SDPReCAP + { + int16 enabled; + int16 initialized; + int16 HallCode; //Текущий код положения по датчикам Холла + Uint32 Ts; // Период для расчёта интерполированного угла + Uint32 Tspeed; // Период для расчёт скорости + Uint32 TsNom; // Период, соответсвующий номинальной скорости + Uint32 TsNomMilsec; // Период, соответсвующий номинальной скорости при тактировании 1 мс + Uint32 PrevTs; // Предыдущая величина периода для расчёта угла. + _iq speed; // Расчитанная скорость + + _iq speedMIN; // Уставка минимальной скорости + _iq speedMinREF; // Скорость, соответствующая уставке для обнуления скорости + _iq Angle; // Расчитанный интерполированный угол + _iq Angle6; // Расчитанный декодированный угол + _iq AnglePrev; // Расчитанный декодированный угол предыдущий + + Uint32 cnt; // Счётчик числа прерываний с момента пуска (дальше 2 не считает). + Uint32 cnt2; // Счётчик прерываний смомента реверса. + Uint32 milsec; // Время в мс с момента прихода прошлой метки + Uint32 milsecFIX; // Переститанная уставка для обнуления скорости + Uint32 milsecREF; // Уставка для обнуления скорости + Uint32 milsecPrevREF; // Предыдущее значение уставки для обнуления скорости + + Uint32 PrevTspeed; // Предыдущая величина периода для расчёта скорости + Uint32 PrevTspeed1; // Предыдущая величина периода для расчёта скорости по датчику А. + Uint32 PrevTspeed11; + Uint32 PrevTspeed2; // Предыдущая величина периода для расчёта скорости по датчику B. + Uint32 PrevTspeed22; + Uint32 PrevTspeed3; // Предыдущая величина периода для расчёта скорости по датчику C. + Uint32 PrevTspeed33; + + int16 CAPCalcEna1; + int16 CAPCalcEna2; + int16 CAPCalcEna3; + + int16 CAP_WrongEdgeCnt; + int16 CAP_WrongEdgeCnt1; + int16 CAP_WrongEdgeCnt2; + int16 CAP_WrongEdgeCnt3; + int16 CAP_WrongEdgeCntPrev; + + Uint16 WrongCodeCounter; + Uint16 WrongCodeCounterPerSec; + Uint16 WrongCodeCounterLimitPerSec; + int32 AngleOffset; + + + int16 ErrorLevel; + int16 ErrorLevelCounter; + int16 ErrorLevelTimeCounterBig; + int16 ErrorLevelTimeCounter; + int16 SensorFault; + Uint16 UserDirection;//пользовательская инверсия направления + + float SimulatorOmega2IQ_factor; + + union SDPReCAP_FLG1 DPReCAP_FLG1; + + void (*Init)(volatile struct SDPReCAP*); + void (*AngleCalc)(volatile struct SDPReCAP*); + void (*Angle6Calc)(volatile struct SDPReCAP*); + void (*AngleErrorCalc)(volatile struct SDPReCAP*); + void (*SpeedCalc)(volatile struct SDPReCAP*); + void (*CAP1Calc)(volatile struct SDPReCAP*); + void (*CAP2Calc)(volatile struct SDPReCAP*); + void (*CAP3Calc)(volatile struct SDPReCAP*); + void (*HelpCalc)(volatile struct SDPReCAP*); + void (*slow_calc)(volatile struct SDPReCAP*); + void (*ms_calc)(volatile struct SDPReCAP*); + void (*calc_10k)(volatile struct SDPReCAP*); + }; + typedef volatile struct SDPReCAP TDPReCAP; + + /****************************************************************************** + Инициализация структуры по умолчанию + ******************************************************************************/ +#define DPRECAP_DEFAULTS \ + {\ + 0,0,0,0,0,0,0,0,0, \ + 0,0,0,0,0, \ + 0,0,0,0,0,0, \ + 0,0,0,0,0,0,0,\ + 0,0,0,\ + 0,0,0,0,0,\ + 0,0,0,0,\ + 0,0,0,0,0,0,\ + 0,0,\ + &DPReCAP_Init, \ + &DPReCAP_AngleCalc, \ + &DPReCAP_Angle6Calc, \ + &DPReCAP_AngleErrorCalc, \ + &DPReCAP_SpeedCalc, \ + &DPReCAP_CAP1Calc, \ + &DPReCAP_CAP2Calc, \ + &DPReCAP_CAP3Calc, \ + &DPReCAP_HelpCalc, \ + &DPReCAP_SlowCalc, \ + &DPReCAP_msCalc, \ + &DPReCAP_calc_10k\ + } + + /****************************************************************************** + Процедура инициализации. + ******************************************************************************/ + void DPReCAP_Init(TDPReCAP*); + + /****************************************************************************** + Процедура расчёта угла. + ******************************************************************************/ + void DPReCAP_Angle6Calc(TDPReCAP*); + + /****************************************************************************** + Процедура вычисления факта ошибочного изменения угла. + ******************************************************************************/ + void DPReCAP_AngleErrorCalc(TDPReCAP*); + + /****************************************************************************** + Процедура расчёта интерполированного угла. + ******************************************************************************/ + void DPReCAP_AngleCalc(TDPReCAP*); + + /****************************************************************************** + Процедура расчёта скорости. + ******************************************************************************/ + void DPReCAP_SpeedCalc(TDPReCAP*); + + /****************************************************************************** + Расчёт прерывания 1 + ******************************************************************************/ + void DPReCAP_CAP1Calc(TDPReCAP*); + + /****************************************************************************** + Расчёт прерывания 2 + ******************************************************************************/ + void DPReCAP_CAP2Calc(TDPReCAP*); + + /****************************************************************************** + Расчёт прерывания 3 + ******************************************************************************/ + void DPReCAP_CAP3Calc(TDPReCAP*); + + /****************************************************************************** + Вспомогательные расчёт, общий для всех прерываний + ******************************************************************************/ + void DPReCAP_HelpCalc(TDPReCAP*); + + + /****************************************************************************** + Вспомогательные расчёт в фоне + ******************************************************************************/ + void DPReCAP_SlowCalc(TDPReCAP*); + + /****************************************************************************** + Миллисекундный расчет + ******************************************************************************/ + void DPReCAP_msCalc(TDPReCAP*); + + + void DPReCAP_calc_10k(TDPReCAP* p); +#ifdef __cplusplus +} +#endif // extern "C" + +#endif // V_DPR_ECAP_H diff --git a/Vinclude/V_IQmath.h b/Vinclude/V_IQmath.h new file mode 100644 index 0000000..571ddda --- /dev/null +++ b/Vinclude/V_IQmath.h @@ -0,0 +1,337 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_IQmath.h + \brief Библиотека функций целочисленной математики + \author ООО "НПФ Вектор". Все права защищены. http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup V_IQmath Библиотека функций целочисленной математики + + \addtogroup V_IQmath +@{*/ + + +#ifndef V_IQ_MATH_H +#define V_IQ_MATH_H + + + +#ifdef __cplusplus +extern "C" { +#endif + +#include "DSP.h" + + +static const int32 fix16_max = 0x7FFFFFFF; /*!< the maximum value of int32 */ +static const int32 fix16_min = 0x80000000; /*!< the minimum value of int32 */ +static const int32 fix16_overflow = 0x80000000; /*!< the value used to indicate overflows when FIXMATH_NO_OVERFLOW is not specified */ + + +static const int32 fix16_pi = 205887; +static const int32 fix16_e = 178145; +static const int32 fix16_one = 0x00010000; +#define _PI 3.1415926535f +typedef int32 _iq; + + +//Преобразование данных в формате с плавающей точкой в целочисленные форматы от IQ1 до IQ30. +#define _IQ30(A) (long) ((A) * 1073741824.0f) +#define _IQ29(A) (long) ((A) * 536870912.0f) +#define _IQ28(A) (long) ((A) * 268435456.0f) +#define _IQ27(A) (long) ((A) * 134217728.0f) +#define _IQ26(A) (long) ((A) * 67108864.0f) +#define _IQ25(A) (long) ((A) * 33554432.0f) +#define _IQ24(A) (long) ((A) * 16777216.0f) +#define _IQ23(A) (long) ((A) * 8388608.0f) +#define _IQ22(A) (long) ((A) * 4194304.0f) +#define _IQ21(A) (long) ((A) * 2097152.0f) +#define _IQ20(A) (long) ((A) * 1048576.0f) +#define _IQ19(A) (long) ((A) * 524288.0f) +#define _IQ18(A) (long) ((A) * 262144.0f) +#define _IQ17(A) (long) ((A) * 131072.0f) +#define _IQ16(A) (long) ((A) * 65536.0f) +#define _IQ15(A) (long) ((A) * 32768.0f) +#define _IQ14(A) (long) ((A) * 16384.0f) +#define _IQ13(A) (long) ((A) * 8192.0f) +#define _IQ12(A) (long) ((A) * 4096.0f) +#define _IQ11(A) (long) ((A) * 2048.0f) +#define _IQ10(A) (long) ((A) * 1024.0f) +#define _IQ9(A) (long) ((A) * 512.0f) +#define _IQ8(A) (long) ((A) * 256.0f) +#define _IQ7(A) (long) ((A) * 128.0f) +#define _IQ6(A) (long) ((A) * 64.0f) +#define _IQ5(A) (long) ((A) * 32.0f) +#define _IQ4(A) (long) ((A) * 16.0f) +#define _IQ3(A) (long) ((A) * 8.0f) +#define _IQ2(A) (long) ((A) * 4.0f) +#define _IQ1(A) (long) ((A) * 2.0f) + +//по умолчанию формат IQ24 +#define _IQ(A) _IQ24(A) +#define _IQmpy(A,B) _IQ24mpy(A,B) +#define _IQmpyI32(A,B) _IQ24mpyI32(A,B) +#define _IQdiv(A,B) _IQ24div(A,B) +#define _IQsqrt(A) _IQ24sqrt(A) +#define _IQsinPU(A) _IQ24sinPU(A) +#define _IQcosPU(A) _IQ24cosPU(A) +#define _IQsin(A) _IQ24sin(A) +#define _IQcos(A) _IQ24cos(A) +#define _IQtanPU(A) _IQ24tanPU(A) +#define _IQatan2PU(A,B) _IQ24atan2PU(A,B) +#define _IQmag(A,B) _IQ24mag(A,B) +#define _IQtoF(A) _IQ24toF(A) + + +int32 _IQ24sinPU(int32 inAngle); +int32 _IQ24atan2PU(int32 inY , int32 inX); +int32 _IQ24sinPU_accurate(int32 inAngle); +int32 _IQ24sqrt(int32 inValue); +int32 _IQ16div(int32 a, int32 b); +int32 _IQ24div(int32 a, int32 b); +int32 _IQ21div(int32 a, int32 b); +int32 _IQ10div(int32 a, int32 b); +int32 _IQ24mag(int32 a, int32 b); + +//! Преобразует из целочисленного 8.24 в формат float +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline float _IQ24toF(int32_t a) { + return (float)(a)*(1.0/16777216.0f); +} + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline float _IQ21toF(int32_t a) { + return (float)(a)*(1.0/2097152.0f); +} + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline float _IQ12toF(int32_t a) { + return (float)(a)*(1.0/4096.0f); +} + +//! Преобразует из целочисленного 22.10 в формат float + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline float _IQ10toF(int32_t a) { + return (float)(a)*(1.0/1024.0f); +} + +//! Преобразует из целочисленного 26.6 в формат float + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline float _IQ6toF(int32_t a) { + return (float)(a)*(1.0/64.0f); +} + +//! Умножение двух чисел в формате 8.24 + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ24mpy(int32 inArg0, int32 inArg1) { + return (int32)(((int64_t)inArg0 * inArg1)>> 24); +} + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ18mpy(int32 inArg0, int32 inArg1) { + return (int32)(((int64_t)inArg0 * inArg1)>> 18); +} + + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ20mpy(int32 inArg0, int32 inArg1) { + return (int32)(((int64_t)inArg0 * inArg1)>> 20); +} + + + +//! Умножение двух чисел в формате 32.0 + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ24mpyI32(int32 inArg0, int32 inArg1) { + return (inArg0 * inArg1); +} + +//! Умножение двух чисел в формате 16.16 + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ16mpy(int32 inArg0, int32 inArg1) { + int64_t product = (int64_t)inArg0 * inArg1; + int32 result = product >> 16; +// result += (product & 0x8000) >> 15; //Непонтяно для чего. Написано для округления + return result; +} + +//! Умножение двух чисел в формате 28.4 + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ4mpy(int32 inArg0, int32 inArg1) { + return (int32)(((int64_t)inArg0 * inArg1)>> 4); +} + + +//! Функция косинуса, вызывает функцию синуса + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ24cosPU(int32 inAngle) { + return _IQ24sinPU(inAngle + _IQ24(0.25)); +} + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ18sinPU(int32 inAngle) { + return _IQ24sinPU(inAngle<<6)>>6; +} + + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ18cosPU(int32 inAngle) { + return _IQ24sinPU((inAngle<<6) + _IQ24(0.25))>>6; +} + + +//! Функция тангенса, вызывает функции синуса и косинуса. + +//! \memberof V_IQmath +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ24tanPU(int32 inAngle) { + return _IQ24div(_IQ24sinPU(inAngle), _IQ24sinPU(inAngle)); +} + +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ16toIQ(int32 a){ + return (a << 8); +} + +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ24cos(int32 x){ + x = _IQmpy(x, _IQ(0.15915494309189533576)); + return _IQsinPU(x + _IQ24(0.25)); +} + +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQ24sin(int32 x){ + x = _IQmpy(x, _IQ(0.15915494309189533576)); + return _IQsinPU(x); +} + +#if defined (__GNUC__) +__attribute__((always_inline)) +#elif defined (__CMCPPARM__) +__STATIC_INLINE +#endif +inline int32 _IQabs(int32 x){ + if (x<0) + return -x; + return x; +} + +#ifdef __CMCPPARM__ +#define fabs(x) fabsf(x) +#endif /* __CMCPPARM__ */ + + + +#ifdef __cplusplus +} +#endif + +#endif + +/*@}*/ diff --git a/Vinclude/V_MBVarsConv.h b/Vinclude/V_MBVarsConv.h new file mode 100644 index 0000000..167245b --- /dev/null +++ b/Vinclude/V_MBVarsConv.h @@ -0,0 +1,90 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file v_MBVarsConv.h + \brief Модуль преобразования данных Modbus + \author ООО "НПФ ВЕКТОР" + \version v.1.1. 02/03/2017 + + \addtogroup v_ModBus + + @{ +*/ + + + +#ifndef V_MBVARSCONV_H +#define V_MBVARSCONV_H + +#ifdef __cplusplus + extern "C" { +#endif + +#include "DSP.h" + +/*! \class TMBVarsConv + \brief Модуль преобразования данных Modbus + + Класс \a TMBVarsConv, основанный на структуре SMBVarsConv, предназначен + для преобразования данных из формата 16 разрядов Modbus в формат системы управления (IQ 24). +*/ + + +struct SMBVars{ + int Command; + int CommandPrev; + int speed_ref; + int CurIs; + int CurSpeed; + int Main_ErrorCode; + int Umax_protect; + }; +//!см. TMBVarsConv MBVars +#define SMBVARS_DEFAULTS {0,0,0,0,0,0} + + +struct SMBVarsConv{ + struct SMBVars Vars; + Uint16 NeedForSave; + void (*init)(volatile struct SMBVarsConv*); + void (*calc)(volatile struct SMBVarsConv*); + void (*slow_calc)(volatile struct SMBVarsConv*); + }; + +typedef volatile struct SMBVarsConv TMBVarsConv; + +//!Инициализатор по умолчанию +#define MBVARSCONV_DEFAULTS { SMBVARS_DEFAULTS,\ + 0,\ + MBVarsConv_init,\ + MBVarsConv_calc,\ + MBVarsConv_slow_calc\ + } + +//! \memberof TMBVarsConv +void MBVarsConv_init(TMBVarsConv *p); +//! \memberof TMBVarsConv +void MBVarsConv_calc(TMBVarsConv *p); +//! \memberof TMBVarsConv +void MBVarsConv_slow_calc(TMBVarsConv *p); + + +#ifdef __cplusplus +} +#endif + +#endif + +/*@}*/ diff --git a/Vinclude/V_ModBus.h b/Vinclude/V_ModBus.h new file mode 100644 index 0000000..69edddd --- /dev/null +++ b/Vinclude/V_ModBus.h @@ -0,0 +1,126 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_ModBus.h + \brief Драйвер ModBus (см. TModBus) + \author Alecksey Anuchin + \version v 1.1 24/03/2017 + \defgroup V_ModBus Драйвер ModBus (см. TModBus) + @{ +*/ + +#ifndef V_MODBUS_H +#define V_MODBUS_H + +#ifdef __cplusplus + extern "C" { +#endif + +#include "mbod.h" + + +#define MODBUS_MAX_RX_COUNT 10 + +/*! \class TModBus + \brief Драйвер ModBus + + Класс \a TModBus, основанный на структуре SModBus, обрабатывает + входящие посылки по RS-485 как посылки ModBus (RTU). */ + +//! см. TModBus + + + //! Структура modbus для хранения внутренних данных + typedef struct {volatile Uint16 In[MODBUS_MAX_RX_COUNT];//!<Массив для принятия данных + volatile Uint16 InCount;//!<Счетчик для массива принятых данных + volatile MB_Record /*const*/ *Addr;//!<Указатель на словарь + volatile Uint16 TimeOut;//!<Текущий таймаут, который надо выдерживать + volatile Uint16 TimeOut1_5;//!<Рассчитанный таймаут 1,5 длины переданного байта + volatile Uint16 TimeOut2_5;//!<Рассчитанный таймаут 2,5 длины переданного байта + volatile Uint16 ToSend;//!<Данные для отправки + volatile Uint16 NumOfHRs;//!<Количество Holding Registers + volatile Uint16 MiddleOfHRs;//!<Середина Holding Registers + volatile Uint16 InitialStepOfHRs;//!<Шаг Holding Registers + volatile Uint16 NumOfIRs;//!<Количество Input Registers + volatile Uint16 MiddleOfIRs;//!<Середина Input Registers + volatile Uint16 InitialStepOfIRs;//!<Шаг Input Registers + volatile Uint16 NumOfCs;//!<Количество Coils + volatile Uint16 MiddleOfCs;//!<Середина Coils + volatile Uint16 InitialStepOfCs;//!<Шаг Coils + volatile Uint16 NumOfDIs;//!<Количество Discrete Inputs + volatile Uint16 MiddleOfDIs;//!<Середина Discrete Inputs + volatile Uint16 InitialStepOfDIs;//!<Шаг Discrete Inputs + volatile Uint16 RxCRC;//!<Принимаемая контрольная сумма + volatile Uint16 TxCRC;//!<Передаваемая контрольная сумма + volatile Uint16 MagicNumber;//!<Эм... + volatile int16 TxState;//!<Состояние передачи + volatile Uint16 temp;//!< + volatile int16 RecievedCounter;//!<Счетчик для отсчиывания таймаута по приему + UART_TypeDef *UART;//!Указатель на используемый модуль UART + } MODBUS_INT; + + #define MODBUS_INT_DEFAULTS {{0},0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,\ + 0xFFFF,0xFFFF, 0xA001,-1, 0,0, \ + } + +struct SModBus{Uint32 BaudRate;//!<Скорость работы по RS + Uint16 ExecutionFreq;//!< Частота тактирования модуля + Uint16 RSNodeID; //!< Номер узла в сети + Uint16 Enabled; //!< Разрешение изменения параметров привода через ModBus + Uint16 Refresh; //!< Флаг изменения параметров по Modbus + int16 error; + int16 errorCode; + int16 AutoRestart; + int16 clear_error; + Uint16 received_data; + Uint16 GPIOsValue; + Uint16 isOnline;//!< В сети мы или нет (идут ли пакеты) + Uint32 OfflineCounter;//!< Счетчик инкрементируется с частотой вызова процедуры ModBus_Execute и обнуляется, если в сети есть пакеты + Uint32 OfflineCounterMax;//!< Таймаут отсутствия пакетов в сети (в единицах счёта OfflineCounter) + Uint16 ReceiveByteCounter;//!< Счетчик принятых байт + Uint16 ReceivePacketCounter;//!< Счетчик принятых посылок + MODBUS_INT MBInternals;//!< Служебные переменные для работы драйвера (не для пользователя) + void (*Init)(volatile struct SModBus*); + void (*Execute)(volatile struct SModBus*); + }; + + +typedef volatile struct SModBus TModBus; + + +#define MODBUS_DEFAULTS {9600,10000, 0x01, 1, 0,\ + 0,0,0,0,0,0,0,0,0,0,0,\ + MODBUS_INT_DEFAULTS,\ + ModBus_Init, \ + ModBus_Execute,\ + } + + +//! \memberof TModBus +void ModBus_Init(TModBus *p); +//! \memberof TModBus +void ModBus_Execute(TModBus *p); +//! \memberof TModBus +int16 ModBus_FindVocAddr(TModBus *p,volatile MB_Record Table[], Uint16 TableSize, int16 Type, Uint16 Index, int16 NumOfIndexs, int16 Mid, int16 Step); + + + +#ifdef __cplusplus +} +#endif + +#endif + +/*@}*/ diff --git a/Vinclude/V_PWM_Module.h b/Vinclude/V_PWM_Module.h new file mode 100644 index 0000000..33e89e6 --- /dev/null +++ b/Vinclude/V_PWM_Module.h @@ -0,0 +1,173 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_PWM_Module.h + \brief Модуль реализации векторной ШИМ (см. TPWM_Module) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup V_PWM_Module Модуль реализации векторной ШИМ (см. TPWM_Module) + @{*/ + +#ifndef _V_PWM_Module_ +#define _V_PWM_Module_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +#define _1_SQRT3 _IQ(0.5773503) +#define _2_SQRT3 _IQ(1.1547005) + +//! Ограничения частоты ШИМ (кГц) min +#define PWM_FREQ_MIN _IQ10(2) +//! Ограничения частоты ШИМ (кГц) max +#define PWM_FREQ_MAX _IQ10(100.0) + +//!Векторная 6-ти секторная ШИМ +#define PWM_TYPE_6SECT_NO_SV 0 +//!Синусоидальная ШИМ +#define PWM_TYPE_SIN_PWM 1 +//!Векторная 12-ти секторная ШИМ +#define PWM_TYPE_12SECT_NO_SV 2 +//!ШИМ методом вычисления фазных потенциалов +#define PWM_TYPE_FLY_12SECT 3 +//!ШИМ для управления ДПТ +#define PWM_TYPE_DC_DRIVE 4 +//!ШИМ для управления SRM +#define PWM_TYPE_SRD 5 + +//! Ограничения величины "мёртвого времени", мкс, min +#define DEAD_BAND_MIN _IQ(0) +//! Ограничения величины "мёртвого времени", мкс, max +#define DEAD_BAND_MAX _IQ(10) + +//! Ограничения величины "минимальной скважности", мкс, min +#define GAMMA_LIMIT_MIN _IQ(0) +//! Ограничения величины "минимальной скважности", мкс, max +#define GAMMA_LIMIT_MAX _IQ(10) + +// Константы загрузки регистров AQCTL# и AQCSFRC (ePWM) +// (определяют настройку событий для выходов ШИМ) +#define AQ_EPWM_DISABLE 0x0000 //!< все события запрещены + +//! Флаг разрешения внутренней привязки ШИМ-выходов +#define ENABLE_PULLUP 0 + +//!что делать при аппаратной аварии с ножками +#define TZ_STATE TZ_HIZ + +/*! \class TPWM_Module + \brief Модуль реализации ШИМ + + Класс \a TPWM_Module, основанный на структуре SPWM_Module, реализует + векторную и скалярную широтно-импульсную модуляцию для управления + шестиключевым инвертором. Имеет настройки мертвого времени, + частоты, коррекцию в зависимости от напряжения ЗПТ, + компенсацию мертвого времени. + Задание напряжения происходит по двум перпендикулярным осям альфа и бетта. + При этом ось альфа сонаправлена с осью А трехфазной системы координат. Для задания нового напряжения нужно + поместить задание в UalphaRef, UbetaRef и вызвать update. В зависимости от того, + какой тип ШИМ выбран в настройках (настраивается пользователем в переменной PWM_type), + функция PWM_Module_Update вызовет нужную функцию, реализующую требуемый тип ШИМ. + В результате этого на трех фазах инвертора в среднем за период ШИМ будет реализован + такой вектор напряжения, который задан в UalphaRef, UbetaRef. Чтобы создать переменное + синусоидальное напряжение, требуется вращать вектор задания внешней по отношению к модулю ШИМ программой. + */ + +//! см. TPWM_Module +struct SPWM_Module { + int16 Enabled; //!< Флаг для чтения - включен ШИМ или выключен. + int32 UalphaRef; //!<Задание по оси асьфа (задается) + int32 UbetaRef; //!<Задание по оси бетта (задается) + + int32 UPhARef; //!<Задание по фазе A (задается) + int32 UPhBRef; //!<Задание по фазе B (задается) + int32 UPhCRef; //!<Задание по фазе c (задается) + + int32 k_pwm; //!< Период таймера ШИМ, для чтения. + int32 U_mag; //!< Текущая амплитуда напряжения, для чтения. + int32 U_lim; //!< Ограничение вектора напряжения, задается + + int32 GammaA; //!< Скважность фазы А в размерности таймера ШИМ, для чтения. + int32 GammaB; //!< Скважность фазы B в размерности таймера ШИМ, для чтения. + int32 GammaC; //!< Скважность фазы C в размерности таймера ШИМ, для чтения. + + int16 PWM_type; //!< Тип ШИМ. Принимает значения констант с префиквом PWM_TYPE_. Задается. + int16 PWM_typeOld; //!< Предыдущее значения типа ШИМ, служебная переменная. + int16 sector; //!< Текущий сектор в векторном типе ШИМ. Для чтения. + + int32 UalphaNorm; //!< Нормированное задание, служебная переменная. + int32 UbetaNorm; //!< Нормированное задание, служебная переменная. + int32 UdCorTmp; //!<Служебная переменная для корректировки выходного напряжения в зависимости от напряжения ЗПТ + int32 UdCompK; //!< Коэффициент корректировки выходного напряжения инвертора в зависимости от изменения напряжения ЗПТ от номинального. Задается. + int32 UdCompEnable; //!< Разрешение корректировки выходного напряжения инвертора в зависимости от изменения напряжения ЗПТ от номинального. Задается. + int16 ULimitation; //!< флаг о том, что идет ограничение напряжения - выходное напряжение меньше заданного. Для чтения. + _iq Frequency; //!< Частота ШИМ в кГц. Формат 22.10! Задается. + _iq FreqPrev; //!< Предудущая частота ШИМ, служебная переменная. + int32 DeadBand; //!< величина "мёртвого времени", мкс, задается. + int32 MinGammaLimit; //!< минимальная скважность на ключе, задается. + int PDP_Fault; //!< Флаг о том, что моудлем ШИМ зафиксирована аппаратная авария от инвертора. Для чтения. По ней необходима реакция модуля защит! + int ChargingMode; //!< Режем заряда будстрепных конденсаторов. Должен выставляться в еденицу на время 2-10 мс внешней программой перед запуском ШИМ. + void (*init)(volatile struct SPWM_Module*); /* Pointer to the init function */ + void (*update)(volatile struct SPWM_Module*); /* Pointer to the update function */ + void (*slow_calc)(volatile struct SPWM_Module*); + void (*On)(volatile struct SPWM_Module*); //!< процедура включения (разрешения) ШИМ-выходов + void (*Off)(volatile struct SPWM_Module*); //!< процедура отключения (запрещения) ШИМ-выходов +}; + +typedef volatile struct SPWM_Module TPWM_Module; + +//! Инициализатор по-умолчанию. +#define PWM_Module_DEFAULTS {\ + 0,0,0, \ + 0,0,0, \ + 0, \ + 0, \ + _IQ(0.866),0, \ + 0,0,\ + 0,0,\ + 0,\ + 0,0,0,0,0,0,0x1400,0,0,0,0,0,\ + PWM_Module_Init, \ + PWM_Module_Update, \ + PWM_Module_SlowCalc, \ + PWM_Module_On, \ + PWM_Module_Off, \ + } + +//! \memberof TPWM_Module +void PWM_Module_Init(TPWM_Module *); +//! \memberof TPWM_Module +void PWM_Module_Update(TPWM_Module *); +//! \memberof TPWM_Module +void PWM_Module_SlowCalc(TPWM_Module *); +//! \memberof TPWM_Module +void PWM_Module_On(TPWM_Module *); +//! \memberof TPWM_Module +void PWM_Module_Off(TPWM_Module *); + +//векторные функции из библиотеки +void PWM_Module_No_SV_Update(TPWM_Module *); + +#ifdef __cplusplus +} +#endif + +#endif + +/*@}*/ + diff --git a/Vinclude/V_QEP.h b/Vinclude/V_QEP.h new file mode 100644 index 0000000..943cedb --- /dev/null +++ b/Vinclude/V_QEP.h @@ -0,0 +1,251 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_QEP.h + \brief Модуль оценки скорости и положения при помощи eQEP (см. TposspeedEqep) + \author ООО "НПФ Вектор". Все права защищены. http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup V_QEP Модуль оценки скорости и положения при помощи eQEP (см. TposspeedEqep) + + \addtogroup V_QEP +@{*/ + + +#include "V_IQmath.h" +#include "filter.h" +#ifndef V_POSSPEED_EQEP_H +#define V_POSSPEED_EQEP_H + +#ifdef __cplusplus +extern "C" { + #endif + + + struct SPOSSPEEDCTL_BITS { // bits +Uint16 InitType: + 2; // 0:1 INPUT: режим инициализации положения при пуске: + // 0 - всё выставляется вручную + // 1 - выставляем вектор тока, далее пуск в векторном режиме(исходное положение - 0 электрических градусов); + // 2 - пуск в векторном режиме(исходное положение - последнее сохранённое) +Uint16 index_en: + 1; // 2 INPUT: наличие репера + // 0 - репер отсутствует + // 1 - репер подключён; +Uint16 dir: + 1; // 3 INPUT: направление движения(в случае неправильного направления); + // 0 - (по умолчанию)прямое включение; + // 1 - инверсия; +Uint16 CmdInit: + 1; // 4 INPUT: для режима инициализации +Uint16 Min_clk: + 4; // 5:8 INPUT: минимальное число меток для захвата на низкой скорости - НЕ МЕНяТЬ!!!!! + // Min_clk=2 - 4 метки + // 3 - 8 меток - по умолчанию + // 4 - 16 меток + // 5 - 32 метки + // 6 - 64 метки + // 7 - 128 меток + // 8 - 256 меток + // 9 - 512 меток + // 10 - 1024 метки +Uint16 rsvd: + 7; // 9:15 reserved; + }; + + union SPOSSPEED_CTL { + Uint16 all; + struct SPOSSPEEDCTL_BITS bit; + }; + + struct SPOSSPEEDFLG1_BITS { // bits +Uint16 UTO_tmp: + 1; // 0 TEMPORARY FLAG: флаг time-out; +Uint16 PCO_tmp: + 1; // 1 TEMPORARY FLAG: флаг положительного переполнения счётчика; +Uint16 PCU_tmp: + 1; // 2 TEMPORARY FLAG: флаг отрицательного переполнения счётчика; +Uint16 UPPS_tmp: + 4; // 3:6 TEMPORARY: значение текущего кванта перемещения для захвата; +Uint16 CCPS_tmp: + 3; // 7:9 TEMPORARY: значение текущего коэффициента деления; +Uint16 first_launch: + 2; // 10:11 FLAG: инициализация первого запуска; +Uint16 accuracy: + 2; // 12:13 FLAG: флаг переключения алгоритмов; +Uint16 first_theta: + 1; // 14 FLAG: флаг первого расчёта углового преращения; +Uint16 transit: + 1; // 15 FLAG: флаг перехода на алгоритм высоких скоростей; + + }; + + union SPOSSPEED_FLG1 { + Uint16 all; + struct SPOSSPEEDFLG1_BITS bit; + }; + + struct SPOSSPEEDFLG2_BITS { // bits +Uint16 pos_ident: + 1; // 0 FLAG: флаг точной идентификации абсолютного положения ротора; +Uint16 UTO_tmp2: + 1; // 1 TEMPORARY FLAG: флаг time-out; +Uint16 PCO_tmp2: + 1; // 2 TEMPORARY FLAG: флаг положительного переполнения счётчика; +Uint16 PCU_tmp2: + 1; // 3 +Uint16 lost_UTO: + 1; // 4 +Uint16 Dir_prev: + 1; // 5 +Uint16 Cdef: + 1; // 6 +Uint16 Delay_flux: + 1; // 7 +Uint16 first_index: + 1; // 8 +Uint16 rsvd: + 8; // 9:15 reserved; + }; + + union SPOSSPEED_FLG2 { + Uint16 all; + struct SPOSSPEEDFLG2_BITS bit; + }; + + + +/*! \class TposspeedEqep + \brief Модуль обработки квадратурного декодера (ДПР типа "энкодер") + + Класс \a TposspeedEqep, основанный на структуре SposspeedEqep, + является модулем для определения углового положения и скорости ротора + двигателя по данным от квадратурного энкодера. Для работы с датчиком + используется периферийный модуль процессора EQEP. Положение вала theta_elec определяется + по аппаратному счетчику QPOSCNT, который увеличивает и уменьшает + свое значение автоматически при вращении вала. После включения процессора + абсолютное угловое положение вала не может быть оперелено, пока не произойдет + событие индексации (сработает реперная метка). Модуль возводит флаг Posspeed_FLG2.bit.pos_ident, + как только это происходит. До этого момента значение углового положения не валидное и не должно использоваться + системой управления. Для калибровки датчика положения (смещения нулевого положения) + используется переменная AngleOffset. + Для вычисления скорости speed_elec используется аппаратный счетчик QCPRD, + который измеряет время между заданным количеством меток датчика. Для обеспечения приемлемой + точности на высоких и низких скоростях "заданное" количество меток переключается на ходу при помощи + делителя UPPS. Так как скорость на малых скоростях вращения пульсирует, + имеется инерционный фильтр скорости первого порядка, значение которого, + speed.output, может быть выведено пользователю. + */ + +//! см. TposspeedEqep + struct SposspeedEqep { + Uint32 resol; //!Wcounter&=0xFF; Где FF - маска (символизирует 256 точек) +#define NUMBER_SAMPLES 256 + + /*! \class TDataLog + \brief 4-х канальный логгер длЯ осциллографированиЯ в реальном времени + + Класс \a TDataLog, основанный на структуре SDataLog, позволЯет записывать выбранные 4 переменных в массивы + из 255 точек с заданной дискретизацией по времени. Кроме того, имеет + свЯзь с драйвером CANOpen длЯ автоматизации указаниЯ этих переменных: можно + "зарЯдить" в даталоггер любой существующий элемент словарЯ.*/ + +//! см. TDataLog + struct SDataLog + { + type_data buff[(NUMBER_SAMPLES*4)]; //4 массива для отснятых осциллограмм, слепленные в один большой +#if DLOG_DATA_SIZE == 16 + type_data *dlog_iptr1; //!< указатели на переменные для записи (например. ток фазы A, скорость и т.д.) + type_data *dlog_iptr2; //!< Input: Second input pointer (Q15) + type_data *dlog_iptr3; + type_data *dlog_iptr4; +#endif + int dlog_cntr_max; //!< Parameter: Maximum number of samples + Uint16 Wcounter; //!< Счетчик по массиву длЯ записи + Uint16 Rcounter; //!< Счетчик по массиву длЯ чтениЯ + type_data* dl_buffer1_adr; //!< Указатели на массивы, где лежат отснятые осциллограммы + type_data* dl_buffer2_adr; //!< Parameter: Buffer starting address 2 + type_data* dl_buffer3_adr; + type_data* dl_buffer4_adr; + + type_data upload_buff[NUMBER_SAMPLES]; //массив для отправки осциллограммы в юникон. Сюда копируется осциллограмма из одного из четырех массивов buff со смещением, чтобы начало осциллограммы было в начале массива. + type_data* dl_upload_buffer_adr; //указатель на массив для отправки. + Uint32 trig_shift; //сдвиг первой точки после срабатывания триггера. Используется, чтобы задать, сколько точек предыстории сохранять. + Uint16 trig_shift_int; //то же, переведенное в точки + Uint16 first_point_written; //первая точка, относящаяся к записываемой осциллограмме с учетом длины предыстории и точки срабатывания триггера + Uint16 prehistory_length; //длина записанной предыстории (если даталоггер переинициализировался кнопкой "обновить", она обнуляется) + Uint16 valid_points_num; //счетчик валидных точек предыстории, записанных после переинициализации кнопкой "обновить" в юниконе + + /*! Режимов работы четыре:\n + 0 - стоп\n + 1 - однократнаЯ запись\n + 2 - запись по кругу без остановки\n + 3 - однократнаЯ запись одной переменной во все 4 массива последовательно, длЯ получениЯ длинной осциллограммы.\n + Устанавливать переменную надо только вызовом функции set_mode! */ + Uint16 mode_reset; //!< задаетсЯ режим работы + Uint16 mode_reset_prev; //!< предыдущий режим работы + int E; // флаг энтри + + /*! "control" имеет 32 разрЯда. Первые 16 бит - флаги, последние 16 бит - установка разреживания.\n + 9 8 7 6 5 4 3 2 1 0\n + | x | x | x | x | x | x | x | x | x | x |\n + | | | | | | первые 4 бита - какие из 4х переменых интересуют (какие адреса обновлЯть, какие данные записывать)\n + | | | | 2 бита - желаемый режим даталоггера: 0, 1, 2\n + | | | бит "данные готовы" - устанавливаетсЯ контроллером\n + | | бит "поддерживается блочная передача"\n + | бит "32-битные данные"\n + резерв */ + long control; //!< управление даталоггером через внешние программы + + unsigned int WriteDelimiter; //!<делитель данных при записи + unsigned int WriteDelimiterCounter; //!<Счетчик длЯ делителЯ + long ind_subind1; //!<записываетсЯ индекс и подындекс длЯ словарЯ + long ind_subind2; + long ind_subind3; + long ind_subind4; + unsigned long next_value_var; //!<через эту переменную выдвигаютсЯ записанные значениЯ при считывании: + //!<биты 0-15: значение точки + //!<биты 16-23: Rcounter (отдаваемая точка) + //!<биты 24-25: buff_num + //!<бит 26: флаг, что в поле "значение" - старшие 16 бит точки (используется при DLOG_DATA_SIZE = 32) + //!<бит 27: флаг, что переменная 16-разрядная (используется при DLOG_DATA_SIZE = 32) + Uint16 StartBits; + int buff_num; //!<номер массива, из которого идет выдвижение значений в next_value_var + int ResetAfterStart; //!<флаг обнулениЯ счетчика записи при запуске + Uint16 OneShotOperation; //!<флаг синхронизации осциллографа только по первому событию (переход в 1 возможен только из 2) + TCo_OdVars *pco_vars; //!<адрес структуры драйвера CANopen +#if DLOG_DATA_SIZE == 32 + int highPartOfValue; //!<флаг выдачи старшей части + TObjectInfo object1Info; //!<информация о записываемом объекте №1 + TObjectInfo object2Info; //!<информация о записываемом объекте №2 + TObjectInfo object3Info; //!<информация о записываемом объекте №3 + TObjectInfo object4Info; //!<информация о записываемом объекте №4 +#endif + void (*update)(volatile struct SDataLog *); //! / chip / K1921VK01T / GCC / USB / CDC_VCP / + + \author ООО "НПФ Вектор". http://motorcontrol.ru, НИИЭТ http://niiet.ru + \version v 1.0 08/08/2017 + +*/ + +#ifndef VINCLUDE_V_USBLIB_H_ +#define VINCLUDE_V_USBLIB_H_ + +int USB_init_hardware(void); +void USB_enable_peripheral (void); +void SystemInit (void); + +extern Uint8 usbActiveFlag; +#endif /* VINCLUDE_V_USBLIB_H_ */ diff --git a/Vinclude/V_watchdog.h b/Vinclude/V_watchdog.h new file mode 100644 index 0000000..e35225c --- /dev/null +++ b/Vinclude/V_watchdog.h @@ -0,0 +1,32 @@ +/* + * V_watchdog.h + * + * Created on: 12 июл. 2018 г. + * Author: Dmitry + */ + +#ifndef V_WATCHDOG_H_ +#define V_WATCHDOG_H_ + +struct Swdog; +typedef volatile struct Swdog Twdog; + +struct Swdog { + void (*enable)(); + void (*disable)(); + void (*feed)(); + void (*resetCPU)(); +}; + +void WDog_Enable(); +void WDog_Disable(); +void WDog_Feed(); +void WDog_ResetSystem(); + +#define WDOG_DEFAULTS {.enable = WDog_Enable,\ + .disable = WDog_Disable,\ + .feed = WDog_Feed,\ + .resetCPU = WDog_ResetSystem} + +extern Twdog Watchdog; +#endif /* V_WATCHDOG_H_ */ diff --git a/Vinclude/X_CANFlashProgData.h b/Vinclude/X_CANFlashProgData.h new file mode 100644 index 0000000..d8e341a --- /dev/null +++ b/Vinclude/X_CANFlashProgData.h @@ -0,0 +1,51 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file X_CANFlashProgData.h + \brief Бинарный файл прошивальщика - грузится в ОЗУ и ему передается управление, далее по CANopen можно обновить программу по flash. + \author Алямкин Д. + \version v 1.0 30/05/2017 + + \defgroup X_CANFlashProgData */ +/*@{*/ + + + +#ifndef X_CANFLASHPROGDATA_H +#define X_CANFLASHPROGDATA_H + +#ifdef __cplusplus +extern "C" +{ +#endif +//адрес структуры настроек +extern Uint32 const FPSettingsAddr; +//адрес начала программы прошивальщика +extern Uint32 const FPStartAddr; +//количество адресов в массиве FPAddrs +extern Uint16 const FPNumOfAddrs; +//адреса начала частей прошивальщика +extern Uint32 const FPAddrs[]; +//длина частей прошивальщика +extern Uint16 const FPPartsLength[]; +//данные прошивальщика +extern Uint16 const FPData[]; +#ifdef __cplusplus +} +#endif + +#endif + +/*@}*/ diff --git a/Vinclude/X_CANFlashProgStarter.h b/Vinclude/X_CANFlashProgStarter.h new file mode 100644 index 0000000..4d78dc7 --- /dev/null +++ b/Vinclude/X_CANFlashProgStarter.h @@ -0,0 +1,82 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file X_CANFlashProgStarter.h + \brief Инициализирует процесс прожига по CANу + \author Алямкин Д. + \version v 1.0 30/05/2017 + + \defgroup TCANFlashProgStarter */ +/*@{*/ + + + +#ifndef X_CANFLASHPROGSTARTER_H +#define X_CANFLASHPROGSTARTER_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +//#define FP_DEVICE_2810 +//#define FP_DEVICE_28335 +//#define FP_DEVICE_28035 +//#define FP_DEVICE_28069 +#define FP_DEVICE_M4F + +//ПереопределЯемые пользователем макросы +#define FP_BLOCK_PWM pwm.Off(&pwm); //выключение ШИМ +#define FP_CTRL_STOP sm_ctrl.state=CTRL_STOP +#define FP_FAULT_SET sm_prot.bit_fault2|= F_FLASH_PROGRAM + + +struct SFlashProgSettings{ + Uint16 magic_number; + Uint16 CANa_nodeID; //2000.0 номер данного узла + Uint16 CANa_bitRate; //2001.0 + Uint16 CANa_enable; + Uint16 CANb_nodeID; //2000.0 номер данного узла + Uint16 CANb_bitRate; //2001.0 + Uint16 CANb_enable; +}; +typedef volatile struct SFlashProgSettings TFlashProgSettings; + +extern TFlashProgSettings FPsettings; + +/* + struct SFlashProgStarter + { + Uint16 input; + void(*start)(volatile struct SFlashProgStarter*); + }; + + typedef volatile struct SFlashProgStarter TFlashProgStarter; + +#define TFLASHPROGSTARTER_DEFAULTS {0,\ + StartFlashProgrammer,\ + } +*/ +void StartFlashProgrammer(); +extern long swu_vars; + + +#ifdef __cplusplus +} +#endif + +#endif + +/*@}*/ diff --git a/Vinclude/build.h b/Vinclude/build.h new file mode 100644 index 0000000..89aff8b --- /dev/null +++ b/Vinclude/build.h @@ -0,0 +1,117 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file build.h + \brief Конфигурационный заголовочный файл + Содержит глобальные макроопределения, используемые во всем проекте. + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 3.0 30/05/2017 + + @{ +*/ + +// Разрешить сторожевой таймер +//#define WATCHDOG_ON +//Выбор типа аппаратной части + +//Для UART, выбирается чем его занять - MODBUS или CANtoRS драйвером +//#define MODBUS_ENA +#define CANTORS_ENA + +// Также можно задействовать USB для CANopen +#define CANTOUSB_ENA + +//!Режимы работы (состояния ДА sm_ctrl) +//! Режим останов +#define CTRL_STOP 0 +//! Режим запуска (включение ШИМ, переход в другой желаемый режим работы) +#define CTRL_RUN 1 +//! Режим намагничивание (постоянный ток), работает контур тока +#define CTRL_FLUXING 2 +//! Режим скалярного управления по кривой U(f) без контуров тока +#define CTRL_RUN_U2F 3 +//! Режим вращения вектора тока +#define CTRL_RUN_I2F 4 +//! Векторная структура управления двухконтурная с датчиком для синхронной машины +#define CTRL_RUN_VECTOR_SM 5 +//! Векторная структура управления с энкодером и с контуром положения для синхронной машины +#define CTRL_RUN_VECTOR_SM_ENCODER_POS 10 + +//! Векторное управление для асинхронного двигателя с энкодером. +#define CTRL_RUN_VECTOR_IM_ENCODER 55 + +//! Режим калибровки датчика положения +#define CTRL_AUTO_SENSOR_TUNING 29 + +//! Режим автокоммутации для SRM +#define CTRL_RUN_SRM_AUTOCOMMUTATION 101 + +//! Режим измерения задержки между ШИМ и датчиками тока +#define CTRL_RUN_LATENCY_TEST 31 + + + + +//Флаги аварий для модуля защит + +//bit_fault1 +#define F_CTRL_LOW_UDC 0x1 +#define F_CTRL_HI_UDC 0x2 +#define F_ENCODER_FAULT 0x4 +#define F_MODEL_FAULT 0x8 +#define F_FLASH_PROGRAM 0x10 +//#define F_RESERVED 0x20 +//#define F_RESERVED 0x40 +//#define F_RESERVED 0x80 +#define F_PROGRAM_1K 0x100 +#define F_PROGRAM_10K 0x200 +#define F_PROGRAM_40K 0x400 +//#define F_RESERVED 0x800 +#define F_PDPINT 0x1000 +//#define F_RESERVED 0x2000 +//#define F_RESERVED 0x4000 +//#define F_RESERVED 0x8000 + +//bit_fault2 +//#define F_RESERVED 0x1 +//#define F_RESERVED 0x2 +//#define F_RESERVED 0x4 +//#define F_RESERVED 0x8 +#define F_CTRL_MAX_I_PH_A 0x10 +#define F_CTRL_MAX_I_PH_B 0x20 +#define F_CTRL_MAX_I_PH_C 0x40 +//#define F_RESERVED 0x80 +//#define F_RESERVED 0x100 +#define F_CTRL_SPEED_MAX 0x200 +//#define F_RESERVED 0x400 +//#define F_RESERVED 0x800 +//#define F_RESERVED 0x1000 +//#define F_RESERVED 0x2000 +//#define F_RESERVED 0x4000 +//#define F_RESERVED 0x8000 + + +#define POS_SENSOR_TYPE_NO_SENSOR 0 +#define POS_SENSOR_TYPE_ENCODER 1 +#define POS_SENSOR_TYPE_HALL 2 +#define POS_SENSOR_TYPE_ENC_HALL 3 +#define POS_SENSOR_TYPE_SSI 4 +#define POS_SENSOR_TYPE_SENSORLESS 5 + +//!Время дискретизации быстрого расчета (прерывание, которое обычно 10кГц) +#define FAST_CALC_TS _IQ(0.0001) + + +/*@}*/ diff --git a/Vinclude/clarke.h b/Vinclude/clarke.h new file mode 100644 index 0000000..40b11d3 --- /dev/null +++ b/Vinclude/clarke.h @@ -0,0 +1,71 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file clarke.h + \brief Модуль фазных преобразований (см. TClarke) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup clarke Модуль фазных преобразований (см. Tclarke) + + @{ +*/ + +#ifndef CLARKE_H +#define CLARKE_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/*! \class TClarke + \brief Фазные преобразования + + Класс \a TClarke, основанный на структуре SClarke, обеспечивает + преобразование величины из трефазной системы координат в двухфазную. + Так, для преобразования токов фаз входным переменным as и bs необходимо + присвоить значение токов фаз A и B, вызвать функцию calc, после чего в выходных + переменных ds, qs будет значение вектора тока во взаимно перпендикулярных осях + альфа, бетта (в англоязычной литературе оси d,q).*/ + +//! см. TClarke +struct SClarke{ long as; //!< Input: phase-a stator variable + long bs;//!< Input: phase-b stator variable + long ds; //!< Output: stationary d-axis stator variable + long qs; //!< Output: stationary q-axis stator variable + void (*calc)(struct SClarke*); //!< Pointer to calculation function + }; + +typedef struct SClarke TClarke; + + //! инициализатор по-умолчанию +#define CLARKE_DEFAULTS { 0, \ + 0, \ + 0, \ + 0, \ + clarke_calc } + + //! \memberof TClarke +void clarke_calc(TClarke*); + +#ifdef __cplusplus +} +#endif + + +#endif + +/*@}*/ diff --git a/Vinclude/co_ODvars.h b/Vinclude/co_ODvars.h new file mode 100644 index 0000000..b5338f2 --- /dev/null +++ b/Vinclude/co_ODvars.h @@ -0,0 +1,867 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file co_ODvars.h + \brief Объявляет некоторые служебные структуры для драйвера CANOpen + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.3 28/06/2019 + + \defgroup CANOpen_drv Драйвер CANOpen + @{ +*/ + +#ifndef CO_OD_VARS_H +#define CO_OD_VARS_H +#ifdef __cplusplus +extern "C" { +#endif + +#include "DSP.h" + +//**************************************************************************************************************************************** +//! Начальный адрес для сохранения в SPI памяти словаря 1-го CAN +#define CO1_SPI_START_ADDR 0 +//! Начальный адрес для сохранения в SPI памяти словаря 2-го CAN +#define CO2_SPI_START_ADDR 3500 + + +// количество "замеппированных" объектов для каждого PDO +#define RPDO1NUMOFPARAMS 4 +#define RPDO2NUMOFPARAMS 4 +#define RPDO3NUMOFPARAMS 4 +#define RPDO4NUMOFPARAMS 4 +#define RPDO5NUMOFPARAMS 4 +#define RPDO6NUMOFPARAMS 4 +#define RPDO7NUMOFPARAMS 4 +#define RPDO8NUMOFPARAMS 4 + +#define TPDO1NUMOFPARAMS 4 +#define TPDO2NUMOFPARAMS 4 +#define TPDO3NUMOFPARAMS 4 +#define TPDO4NUMOFPARAMS 4 +#define TPDO5NUMOFPARAMS 4 +#define TPDO6NUMOFPARAMS 4 +#define TPDO7NUMOFPARAMS 4 +#define TPDO8NUMOFPARAMS 4 + + + +//структура с таблицами параметров для настройки скорости CAN (для каждого микроконтроллера настройки свои) +typedef struct { + Uint16 co_DIV8[6]; + Uint16 co_BRP[6]; + Uint16 co_TSEG1[6]; + Uint16 co_TSEG2[6]; + Uint16 co_SJW[6]; +} TCANSpeedTableOptions; + +//структура пользовательских настроек драйвера +struct S_CANOPEN_DRV_SETTINGS +{ + Uint16 LoadParamsFromUserMemory_ena; //Загружать параметры из пользовательской памяти при инициализации + Uint16 CAN_ISR_priority; //Приоритет прерываний CAN + + Uint16 MultiPDO_ena; /* //разрешение принимать PDO от любых устройств в сети: + //для каждого RPDO доступны 8 диапазонов принимаемых идентификаторов: + // 0x181-0x1FF + // 0x200-0x27F + // 0x280-0x2FF + // ... + // 0x480-0x4FF + // 0x500-0x57F + //Каждому RPDO должен быть сопоставлен свой диапазон идентификаторов. + //Для сопоставления данному RPDO диапазона идентификаторов необходимо присвоить + //соответствующему RPDOxCOBID любой идентификатор требуемого диапазона. + //Двум RPDO одного устройства не может быть сопоставлен один и тот же диапазон идентификаторов - + //в этом случае поведение непредсказуемо. */ + + Uint16 RX_PDO_Callback_ena; /*//разрешение вызова CallBack при приеме PDO. (может использоваться как в обычном режиме, так и в режиме МультиPDO). + //Если дефайн объявлен, то после каждого приема узлом PDO будет вызываться соответствующая CallBack функция + //(ф-ии описаны в файле CANOpenCallbacks.c) вида: void co_RPDOx_Callback(Uint16 nodeID) + //Где x = 1,2,..8 при приеме RPDO1, RPDO2,..RPDO8 соответственно. + //В качестве параметра в функцию передается только номер узла (nodeID) от которого принято PDO, + //а принятая информация находится по соответствующему(-им) мэппингу данного PDO адресу(-ам).*/ + + Uint16 AutoBusON_ena; /*//разрешение CAN устройству оставаться в работе даже при наличии большого количества ошибок на линии CAN. + //С одной стороны разрешение позволяет работать устройству в сильно зашумленной линии, но с другой - + //при отказе в устройстве, например rx, устройство забьет всю сеть, пытаясь отправить свою посылку...*/ + + Uint16 BlockTransfer_ena; //разрешение использования в драйвере функций блочной передачи + + Uint32 BaseAdressCanRegisters; //адрес в памяти, с которого начинаются CAN-регистры. Нужно для унификация библиотеки драйвера CANOpen для разных + //микроконтроллеров фирмы НИИЭТ + + Uint16 CAN_IRQn; //номер перечисления прерывания CAN из таблицы прерываний. Нужно для унификация библиотеки драйвера CANOpen для + //разных микроконтроллеров фирмы НИИЭТ + + TCANSpeedTableOptions *speedCANTablePointer;//указатель на массив структур с таблицами параметров для настройки скорости CAN для разных микроконтроллеров. + + void (*resetCPU)(void); //указатель на функцию перезагрузки микроконтроллера. Нужна, потому как для разных микроконтроллеров фирмы НИИЭТ + //используются разные функции для ресета. +}; + +// Тип доступа к параметру (согласно формату) +typedef enum EObjAccess +{ + OBJ_ACCESS_READONLY, // read-only + OBJ_ACCESS_RW, // read/write + OBJ_ACCESS_WP, // read/writeable protected + OBJ_ACCESS_SWP, // read/secret writeable protected +} TObjAccess; + +// Тип параметра (согласно формату) +typedef enum EObjType +{ + OBJ_TYPE_UNKNOWN, + OBJ_TYPE_ROOT, + OBJ_TYPE_U8, + OBJ_TYPE_U16, + OBJ_TYPE_QU16, + OBJ_TYPE_I8, + OBJ_TYPE_I16, + OBJ_TYPE_QI16, + OBJ_TYPE_U32, + OBJ_TYPE_QU32, + OBJ_TYPE_I32, + OBJ_TYPE_QI32, + OBJ_TYPE_BIT_FIELD, + OBJ_TYPE_FLOAT_ABS, + OBJ_TYPE_FLOAT_PU, +} TObjType; + +// Структура, содержащая различную информацию об объекте. +typedef struct +{ + void* varAddr; // адрес переменной в ОЗУ + int varSize; // размер переменной в битах (16/32) + TObjAccess access; // тип доступа к объекту + TObjType type; // тип объекта + Uint16 subIndNum; // число подындексов (для ROOT) + Uint16 scaleNum; // номер масштабирующего коэффициента (для QU16, QI16, QU32, QI32, FLOAT_PU) + Uint16 Q; // число разрядов дробной части (для QU16, QI16, QU32, QI32) + Uint16 bitOffset; // смещение битового поля (для BIT_FIELD) + Uint16 bitNum; // размер битового поля (для BIT_FIELD) + Uint16 precision; // число знаков, отображаемых после запятой (для FLOAT_ABS) + Uint16 prefix; // префикс размерности (для FLOAT_ABS) + Uint16 units; // размерность (для FLOAT_ABS) +} TObjectInfo; + + +typedef volatile struct S_CANOPEN_DRV_SETTINGS T_CANOPEN_DRV_SETTINGS; + +//!Конфигурирование полей SDO +struct SDOcommSpecifier { + Uint16 s:1; //!< 0 - если s=1, то размер передаваемых данных известен и указан + Uint16 e:1; //!< 1 - expedited или нет + Uint16 n:2; //!< 3:2 - количество байт данных не содержащих данных + Uint16 X:1; //!< 4 - reserved + Uint16 cs:3;//!< 7:5 - SDO команда + Uint16 reserved:8;// +}; + +//! Нулевой байт мейл-бокса +union MBOXByte0{ + struct SDOcommSpecifier SDO_Spicifier; + Uint16 byte0; +}; +//! Байты мейл-бокса, используемого для альтернативной CAN связи (ZigBee, USB) +typedef struct { + union MBOXByte0 MByte0; + Uint16 byte1; + Uint16 byte2; + Uint16 byte3; + Uint16 byte4; + Uint16 byte5; + Uint16 byte6; + Uint16 byte7; + Uint16 senderNodeID; +}Z_MBytes; + +typedef struct { + Uint32 id; + Uint8 data[8]; + Uint8 dlc; +} TZCanMsg; + + +///сообщение в виде полей SDO + struct SDOmsg + { Uint32 s:1; //!< 0 - если s=1, то размер передаваемых данных известен и указан + Uint32 e:1; //!< 1 - expedited или нет + Uint32 n:2; //!< 3:2 - количество байт данных не содержащих данных + Uint32 X:1; //!< 4 - reserved + Uint32 cs:3;//!< 7:5 - SDO команда + Uint32 index:16; + Uint32 subindex:8; + Uint32 data:32; + }; +//сообщение в виде байтов + struct MBOX_bytes + { Uint16 byte0:8; + Uint16 byte1:8; + Uint16 byte2:8; + Uint16 byte3:8; + Uint16 byte4:8; + Uint16 byte5:8; + Uint16 byte6:8; + Uint16 byte7:8; + }; +//сообщение в виде слов + struct MBOX_words + { Uint16 word0; + Uint16 word1; + Uint16 word2; + Uint16 word3; + }; +//сообщение в виде MDRL, MDRH + struct MBOX_Uint32 + { Uint32 MDRL; + Uint32 MDRH; + }; +//все представления накладываем друг на друга + union MBOX_data { + struct MBOX_Uint32 u32; + struct MBOX_words u16; + struct MBOX_bytes u8; + struct SDOmsg SDO; + }; + typedef volatile union MBOX_data TMBOX_data; + + struct MID_bits + { Uint32 rsvd1:18; //пока не используем + Uint32 senderNodeID:7; //номер узла + Uint32 rsvd2:7; //пока не используем + }; + union MID_data { + Uint32 all; + struct MID_bits bit; + }; +// мейл-бокс + struct MData + { + union MBOX_data data; + union MID_data MID; + }; + typedef volatile struct MData TCo_MOData; + +//! Сборник данных всех мейл-боксов + struct CO_MBOXDATA + { + struct MData MBOX_0; + struct MData MBOX_1; + struct MData MBOX_2; + struct MData MBOX_3; + struct MData MBOX_4; + struct MData MBOX_5; + struct MData MBOX_6; + struct MData MBOX_7; + struct MData MBOX_8; + struct MData MBOX_9; + struct MData MBOX_10; + struct MData MBOX_11; + struct MData MBOX_12; + struct MData MBOX_13; + struct MData MBOX_14; + struct MData MBOX_15; + struct MData MBOX_16; + struct MData MBOX_17; + struct MData MBOX_18; + struct MData MBOX_19; + struct MData MBOX_20; + struct MData MBOX_21; + struct MData MBOX_22; + struct MData MBOX_23; + struct MData MBOX_24; + struct MData MBOX_25; + struct MData MBOX_26; + struct MData MBOX_27; + struct MData MBOX_28; + struct MData MBOX_29; + struct MData MBOX_30; + struct MData MBOX_31; + }; + + typedef volatile struct CO_MBOXDATA TCo_MboxData; + +//**************************************************************************************************************************************** +//структуры модуля блочной передачи +#define BT_FIFO_SIZE 8 //8 сообщений должно хватить для 1Мбит/с, если обработка производится в 1мс +//внутримодульные дефайны +#define BT_FIFO_SUCCESSFUL 0 +#define BT_FIFO_EMPTY 1 +#define BT_FIFO_FULL 2 +#define BT_FIFO_BUSY 3 + +struct S_BT_FIFO +{ +Uint16 busy_flag; //флаг занятости ФИФО, показывает количество инстанций, использующих ФИФО в данный момент +Uint16 size; +Uint16 number_of_msgs; +Uint16 read_ptr; +Uint16 write_ptr; +TMBOX_data msg_array[BT_FIFO_SIZE]; +Uint16(*read)(volatile struct S_BT_FIFO*,TMBOX_data*); +Uint16(*write)(volatile struct S_BT_FIFO*,TMBOX_data*); +Uint16(*clear)(volatile struct S_BT_FIFO*); +}; + +typedef volatile struct S_BT_FIFO T_BT_FIFO; + +#define T_BT_FIFO_DEFAULTS {0,\ + BT_FIFO_SIZE,\ + 0,0,0,\ + {0},\ + BT_FIFO_Read,\ + BT_FIFO_Write,\ + BT_FIFO_Clear} + +Uint16 BT_FIFO_Read(T_BT_FIFO*,TMBOX_data*); +Uint16 BT_FIFO_Write(T_BT_FIFO*,TMBOX_data*); +Uint16 BT_FIFO_Clear(T_BT_FIFO* p); + +#define CANBT_STATE_FREE 0 +#define CANBT_STATE_RX 1 +#define CANBT_STATE_TX 2 + +#define CANBT_STATUS_IDLE 0 +#define CANBT_STATUS_BUSY 1 +#define CANBT_STATUS_SUCCESSFUL 2 +#define CANBT_STATUS_TIMEOUT 3 +#define CANBT_STATUS_CRC_ERR 4 +#define CANBT_STATUS_ANY_ERR 5 + +struct SBlockTransfer +{ Uint16 state; //Состояние. + Uint16 state_shadow;//Теневое состояние. + Uint16 state_prev; //Предыдущее состояние (на один такт) + Uint16 E; //Флаг первого вхождения. + Uint32 state_time; //время нахождения в текущем состоянии, в мс. + Uint16 RX_block_size; //размер принимаемого блока (определяется пользователем перед приемом) + Uint16 TX_block_size; //размер отправляемого блока (определяется пользователем перед отправкой) + Uint16 firstTXmsg; //флаг, показывающий, что 1-е сообщение блока еще не отправлялось. + Uint16* RX_dest_ptr; + Uint16* TX_source_ptr; + int RX_index; + int TX_index; + T_BT_FIFO RXmsgFIFO; + T_BT_FIFO TXmsgFIFO; + Uint16 blockCRC; + Uint16 rx_status; //обратная связь для внешней программы использующей блочную передачу + Uint16 tx_status; // + Uint32 timeout; +}; + +typedef volatile struct SBlockTransfer TBlockTransfer; + +#define TBLOCK_TRANSFER_DEFAULTS {CANBT_STATE_FREE,\ + CANBT_STATE_FREE,0xff,1,\ + 0,\ + 0,0,0,0,0,0,0,\ + T_BT_FIFO_DEFAULTS,T_BT_FIFO_DEFAULTS,\ + 0,\ + CANBT_STATUS_IDLE,CANBT_STATUS_IDLE,\ + ((Uint32)500)/*500мс*/,\ + } + + +//**************************************************************************************************************************************** +//структура работы с пользовательской памятью для сохранения и восстановления параметров словаря объектов +struct S_UserMemoryContext +{ + Uint16 MemStartAddr; //!Адрес в пользовательской памяти (побайтовый доступ) + Uint16 *MCUStartAddr; //!Указатель на массив с данными в MCU + Uint16 data_length; //!длина данных (в байтах) +}; +typedef volatile struct S_UserMemoryContext T_UserMemoryContext; +//**************************************************************************************************************************************** + +//Структура с данными драйвера CANOpen +//Помимо служебных и пользоваельских данных, необходимых для работы драйвера, +//в данную структуру входят стандартные переменные словаря CANOpen + +struct SCo_OdVars{ + Uint32 co_deviceType; //1000.0 + Uint16 co_errorRegister; //1001.0 Регистр ошибки + Uint32 co_deviceState; //1002.0 + Uint32 co_emcyCOBID; //1014.0 + Uint32 co_CHBT; //1016.1 Consumer heartbeat time + Uint32 co_PHBT ; //1017.0 Producer heartbeat time + Uint32 co_vendorID; //1018.1 + Uint32 co_productCode; //1018.2 + Uint32 co_revisionNumber; //1018.3 + Uint32 co_serialNumber; //1018.4 + Uint32 co_csrxCOBID; //1200.1 + Uint32 co_sctxCOBID; //1200.2 + Uint32 co_cstxCOBID; //1280.1 + Uint32 co_scrxCOBID; //1280.2 + Uint16 co_ssNODEID; //1280.3 + Uint32 co_RPDO1COBID; //1400.1 + Uint16 co_transType; //1400.2 , 1401.2 , 1402.2 , 1403.2 + Uint32 co_RPDO2COBID; //1401.1 + Uint32 co_RPDO3COBID; //1402.1 + Uint32 co_RPDO4COBID; //1403.1 + Uint32 co_RPDO5COBID; //1404.1 rwp + Uint32 co_RPDO6COBID; //1405.1 rwp + Uint32 co_RPDO7COBID; //1406.1 rwp + Uint32 co_RPDO8COBID; //1407.1 rwp +// + Uint32 co_RPDO1_1Mapping; //1600.1 + Uint32 co_RPDO1_2Mapping; //1600.2 + Uint32 co_RPDO1_3Mapping; //1600.3 + Uint32 co_RPDO1_4Mapping; //1600.4 + Uint32 co_RPDO2_1Mapping; //1601.1 + Uint32 co_RPDO2_2Mapping; //1601.2 + Uint32 co_RPDO2_3Mapping; //1601.3 + Uint32 co_RPDO2_4Mapping; //1601.4 + Uint32 co_RPDO3_1Mapping; //1602.1 + Uint32 co_RPDO3_2Mapping; //1602.2 + Uint32 co_RPDO3_3Mapping; //1602.3 + Uint32 co_RPDO3_4Mapping; //1602.4 + Uint32 co_RPDO4_1Mapping; //1603.1 + Uint32 co_RPDO4_2Mapping; //1603.2 + Uint32 co_RPDO4_3Mapping; //1603.3 + Uint32 co_RPDO4_4Mapping; //1603.4 +//2007_03_14 + Uint32 co_RPDO5_1Mapping; //1604.1 rwp + Uint32 co_RPDO5_2Mapping; //1604.2 rwp + Uint32 co_RPDO5_3Mapping; //1604.3 rwp + Uint32 co_RPDO5_4Mapping; //1604.4 rwp + Uint32 co_RPDO6_1Mapping; //1605.1 rwp + Uint32 co_RPDO6_2Mapping; //1605.2 rwp + Uint32 co_RPDO6_3Mapping; //1605.3 rwp + Uint32 co_RPDO6_4Mapping; //1605.4 rwp + Uint32 co_RPDO7_1Mapping; //1606.1 rwp + Uint32 co_RPDO7_2Mapping; //1606.2 rwp + Uint32 co_RPDO7_3Mapping; //1606.3 rwp + Uint32 co_RPDO7_4Mapping; //1606.4 rwp + Uint32 co_RPDO8_1Mapping; //1607.1 rwp + Uint32 co_RPDO8_2Mapping; //1607.2 rwp + Uint32 co_RPDO8_3Mapping; //1607.3 rwp + Uint32 co_RPDO8_4Mapping; //1607.4 rwp +// + Uint32 co_TPDO1COBID; //1800.1 + Uint16 co_TPDO1ITime; //1800.3 rw + Uint16 co_compatEntry; //1800.4 rw + Uint16 co_TPDO1EventTimer; //1800.5 rw + Uint32 co_TPDO2COBID; //1801.1 + Uint16 co_TPDO2ITime; //1801.3 rw + Uint16 co_TPDO2EventTimer; //1800.5 rw + Uint32 co_TPDO3COBID; //1802.1 + Uint16 co_TPDO3ITime; //1802.3 rw + Uint16 co_TPDO3EventTimer; //1800.5 rw + Uint32 co_TPDO4COBID; //1803.1 + Uint16 co_TPDO4ITime; //1803.3 rw + Uint16 co_TPDO4EventTimer; //1800.5 rw + Uint32 co_TPDO5COBID; //1804.1 r + Uint16 co_TPDO5ITime; //1804.3 rw + Uint16 co_TPDO5EventTimer; //1804.5 rw + Uint32 co_TPDO6COBID; //1805.1 r + Uint16 co_TPDO6ITime; //1805.3 rw + Uint16 co_TPDO6EventTimer; //1805.5 rw + Uint32 co_TPDO7COBID; //1806.1 r + Uint16 co_TPDO7ITime; //1806.3 rw + Uint16 co_TPDO7EventTimer; //1806.5 rw + Uint32 co_TPDO8COBID; //1807.1 r + Uint16 co_TPDO8ITime; //1807.3 rw + Uint16 co_TPDO8EventTimer; //1807.5 rw +// + Uint32 co_TPDO1_1Mapping; //1A00.1 + Uint32 co_TPDO1_2Mapping; //1A00.2 + Uint32 co_TPDO1_3Mapping; //1A00.3 + Uint32 co_TPDO1_4Mapping; //1A00.4 + Uint32 co_TPDO2_1Mapping; //1A01.1 + Uint32 co_TPDO2_2Mapping; //1A01.2 + Uint32 co_TPDO2_3Mapping; //1A01.3 + Uint32 co_TPDO2_4Mapping; //1A01.4 + Uint32 co_TPDO3_1Mapping; //1A02.1 + Uint32 co_TPDO3_2Mapping; //1A02.2 + Uint32 co_TPDO3_3Mapping; //1A02.3 + Uint32 co_TPDO3_4Mapping; //1A02.4 + Uint32 co_TPDO4_1Mapping; //1A03.1 + Uint32 co_TPDO4_2Mapping; //1A03.2 + Uint32 co_TPDO4_3Mapping; //1A03.3 + Uint32 co_TPDO4_4Mapping; //1A03.4 + Uint32 co_TPDO5_1Mapping; //1A04.1 rwp + Uint32 co_TPDO5_2Mapping; //1A04.2 rwp + Uint32 co_TPDO5_3Mapping; //1A04.3 rwp + Uint32 co_TPDO5_4Mapping; //1A04.4 rwp + Uint32 co_TPDO6_1Mapping; //1A05.1 rwp + Uint32 co_TPDO6_2Mapping; //1A05.2 rwp + Uint32 co_TPDO6_3Mapping; //1A05.3 rwp + Uint32 co_TPDO6_4Mapping; //1A05.4 rwp + Uint32 co_TPDO7_1Mapping; //1A06.1 rwp + Uint32 co_TPDO7_2Mapping; //1A06.2 rwp + Uint32 co_TPDO7_3Mapping; //1A06.3 rwp + Uint32 co_TPDO7_4Mapping; //1A06.4 rwp + Uint32 co_TPDO8_1Mapping; //1A07.1 rwp + Uint32 co_TPDO8_2Mapping; //1A07.2 rwp + Uint32 co_TPDO8_3Mapping; //1A07.3 rwp + Uint32 co_TPDO8_4Mapping; //1A07.4 rwp +// + Uint16 co_nodeID ; //2000.0 номер данного узла + Uint16 co_bitRate; //2001.0 + Uint16 co_specialData1; //2003.1 + Uint16 co_specialData2; //2003.2 + Uint16 co_specialData3; //2003.3 + Uint16 co_specialData4; //2003.4 + Uint32 co_secretCode; //2004.0 + Uint16 co_protectBit; //2005.0 + Uint32 co_devicePresentFlag0; + Uint32 co_devicePresentFlag1; + Uint32 co_devicePresentFlag2; + Uint32 co_devicePresentFlag3; + Uint32 co_deviceGlobalPresent0; + Uint32 co_deviceGlobalPresent1; + Uint32 co_deviceGlobalPresent2; + Uint32 co_deviceGlobalPresent3; + Uint32 co_heartbeatFlag0 ; //2010.1 Флаги heartbeat с 0 по 31-е устройство + Uint32 co_heartbeatFlag1 ; //2010.2 Флаги heartbeat с 32 по 63-е устройство + Uint32 co_heartbeatFlag2 ; //2010.3 Флаги heartbeat с 64 по 95-е устройство + Uint32 co_heartbeatFlag3 ; //2010.4 Флаги heartbeat с 96 по 127-е устройство + Uint32 co_heartbeatMask0 ; //2011.1 Маски heartbeat с 0 по 31-е устройство (0110b) + Uint32 co_heartbeatMask1 ; //2011.2 Маски heartbeat с 32 по 63-е устройство + Uint32 co_heartbeatMask2 ; //2011.3 Маски heartbeat с 64 по 95-е устройство + Uint32 co_heartbeatMask3 ; //2011.4 Маски heartbeat с 96 по 127-е устройство + Uint16 co_heartbeatAutoStart ; //2012.0 Параметр, определяющий возможен ли автозапуск сети + Uint16 co_heartbeatAutoRecovery ; //2014.0 Параметр, определяющий возможен ли перезапуск системы из состояния STOPPED + Uint16 co_nodeState ; //2015.0 состояние данного узла - вначале BOOTUP + Uint16 co_emergencyErrorCode ; //2016.0 Код аварии + Uint32 co_deviceErrorState ; //2017.0 Статусный регистр ошибок производителя + Uint16 co_ODCommand; //2080.1 + Uint16 co_currentODIndex; //2080.2 + Uint16 co_currentODSubIndex; //2080.3 + Uint16 co_currentODEText; //2080.4 + Uint16 co_currentODEFormat; //2080.5 + Uint16 co_currentODEMin; //2080.6 + Uint16 co_currentODEMax; //2080.7 + Uint16 co_currentODEDefault; //2080.8 + Uint16 co_currentODEMinLow; //2080.9 + Uint16 co_currentODEMaxLow; //2080.10 + Uint16 co_currentODEDefaultLow; //2080.11 + Uint16 co_currentODEAddrHigh; //2080.12 + Uint16 co_currentODEAddrLow; + Uint16 co_currentODEType; + Uint16 co_odIndexSize; + Uint32 co_defaultIndex1; //2082.1 rw + Uint32 co_defaultIndex2; //2082.2 rw + Uint16 co_maskElement01; //2083.1,2 rw + Uint16 co_maskElement23; //2083.3,4 rw + Uint16 co_maskElement45; //2083.5,6 rw + Uint16 co_maskElement67; //2083.7,8 rw + Uint16 co_maskElement89; //2083.9,A rw + Uint16 co_maskElementAB; //2083.B,C rw + Uint16 co_maskElementCD; //2083.D,E rw + Uint16 co_maskElementEF; //2083.F,10 rw + Uint16 co_profileAccessMask; //2081.0 rw + Uint16 co_scaleNum0; //2100.1 + Uint16 co_scaleNum0Format; //2100.2 + Uint16 co_scaleNum1; //2101.1 + Uint16 co_scaleNum1Format; //2101.2 + Uint16 co_scaleNum2; //2102.1 + Uint16 co_scaleNum2Format; //2102.2 + Uint16 co_scaleNum3; //2103.1 + Uint16 co_scaleNum3Format; //2103.2 + Uint16 co_scaleNum4; //2104.1 + Uint16 co_scaleNum4Format; //2104.2 + Uint16 co_scaleNum5; //2105.1 + Uint16 co_scaleNum5Format; //2105.2 + Uint16 co_scaleNum6; //2106.1 + Uint16 co_scaleNum6Format; //2106.2 + Uint16 co_scaleNum7; //2107.1 + Uint16 co_scaleNum7Format; //2107.2 + Uint16 co_scaleNum8; //2108.1 + Uint16 co_scaleNum8Format; //2108.2 + Uint16 co_scaleNum9; //2109.1 + Uint16 co_scaleNum9Format; //2109.2 + Uint16 co_scaleNumA; //210A.1 + Uint16 co_scaleNumAFormat; //210A.2 + Uint16 co_scaleNumB; //210B.1 + Uint16 co_scaleNumBFormat; //210B.2 + Uint16 co_scaleNumC; //210C.1 + Uint16 co_scaleNumCFormat; //210C.2 + Uint16 co_scaleNumD; //210D.1 + Uint16 co_scaleNumDFormat; //210D.2 + Uint16 co_scaleNumE; //210E.1 + Uint16 co_scaleNumEFormat; //210E.2 + Uint16 co_scaleNumF; //210F.1 + Uint16 co_scaleNumFFormat; //210F.2 + Uint16 co_scaleNum10; //2110.1 + Uint16 co_scaleNum10Format; //2110.2 + Uint16 co_scaleNum11; //2111.1 + Uint16 co_scaleNum11Format; //2111.2 + Uint16 co_scaleNum12; //2112.1 + Uint16 co_scaleNum12Format; //2112.2 + Uint16 co_scaleNum13; //2113.1 + Uint16 co_scaleNum13Format; //2113.2 + Uint16 co_scaleNum14; //2114.1 + Uint16 co_scaleNum14Format; //2114.2 + Uint16 co_scaleNum15; //2115.1 + Uint16 co_scaleNum15Format; //2115.2 + Uint16 co_scaleNum16; //2116.1 + Uint16 co_scaleNum16Format; //2116.2 + Uint16 co_scaleNum17; //2117.1 + Uint16 co_scaleNum17Format; //2117.2 + Uint16 co_scaleNum18; //2118.1 + Uint16 co_scaleNum18Format; //2118.2 + Uint16 co_scaleNum19; //2119.1 + Uint16 co_scaleNum19Format; //2119.2 + Uint16 co_scaleNum1A; //211A.1 + Uint16 co_scaleNum1AFormat; //211A.2 + Uint16 co_scaleNum1B; //211B.1 + Uint16 co_scaleNum1BFormat; //211B.2 + Uint16 co_scaleNum1C; //211C.1 + Uint16 co_scaleNum1CFormat; //211C.2 + Uint16 co_scaleNum1D; //211D.1 + Uint16 co_scaleNum1DFormat; //211D.2 + Uint16 co_scaleNum1E; //211E.1 + Uint16 co_scaleNum1EFormat; //211E.2 + Uint16 co_scaleNum1F; //211F.1 + Uint16 co_scaleNum1FFormat; //211F.2 + + Uint16 co_blockTransferCommand; //2700 + + //Указатели + Uint16 *co_currentWordODTbl1 ;//данные указатели ипользуются для работы интерпретатора + Uint16 *co_currentWordODTbl2 ;//команд в прерывании ШИМ (для обработки быстрых команд) + Uint16 co_currentAccessMask; //маска доступа индекса на который указывает co_currentWordODTbl1 + + Uint16 *co_shadow_currentWordODTbl1 ;//данные указатели ипользуются для работы интерпретатора + Uint16 *co_shadow_currentWordODTbl2 ;//команд в фоновой программе (для обработки медленных команд) + + Uint16 *co_SDOcurrentWordODTbl1; + Uint16 *co_SDOcurrentWordODTbl2; + + //ExternalInterface + Uint16 *Z_co_SDOcurrentWordODTbl1; + Uint16 *Z_co_SDOcurrentWordODTbl2; + + Uint16 *co_PDOcurrentWordODTbl1; + Uint16 *co_PDOcurrentWordODTbl2; + Uint16 *co_PDOMAPcurrentWordODTbl1; + Uint16 *co_PDOMAPcurrentWordODTbl2; + + Uint16 *co_endODTbl1 ;//указывает на последний элемент индекс в таблице ODTbl1 + + Uint32 co_MailboxMDRL; + Uint32 co_MailboxMDRH; + Uint32 co_MailboxMID; + + Uint32 co_flagBackUp0;// + Uint32 co_flagBackUp1;// предыдущие состояния флагов + Uint32 co_flagBackUp2;// + Uint32 co_flagBackUp3;// + + Uint32 co_backupEEC; // Предыдущее состояние кода аварии + Uint32 co_backupER; // Предыдущее состояние регистра ошибки + Uint32 co_backupDES; // Предыдущее состояние статусного регистра ошибок производителя + + Uint32 co_consHBTimeCounter;// изначально должен быть равен co_CHBT + Uint32 co_prodHBTimeCounter;// изначально должен быть равен co_PHBT + Uint32 co_emcyNewState; // Состояние в которое перешел узел после ошибки + Uint32 co_msDevisor; // делитель частоты для получения 1мс - используется для отправки Heartbeat + + Uint16 co_shadow_currentODIndex; + Uint16 co_shadow_currentODSubIndex; + Uint16 co_shadow_currentODEText; + Uint16 co_shadow_currentODEFormat; + Uint16 co_shadow_currentODEMin; + Uint16 co_shadow_currentODEMax; + Uint16 co_shadow_currentODEDefault; + Uint16 co_shadow_currentODEMinLow; + Uint16 co_shadow_currentODEMaxLow; + Uint16 co_shadow_currentODEDefaultLow; + Uint16 co_shadow_currentODEAddrLow; + Uint16 co_shadow_currentODEAddrHigh; + Uint16 co_shadow_currentODEType; + //переменные необходимые для работы SDO служб + Uint16 co_SDOrequestIndex; + Uint16 co_SDOrequestSubIndex; + Uint16 co_SDOrequestData; + Uint16 co_SDOrequestDataH; + Uint16 co_SDOrequestStatus; + Uint16 co_SDOrequestFlag; + Uint16 co_SDOSuspendedSend; + TMBOX_data SDOMsgData; + + //временная переменная защиты секретных параметров от несанкционированного доступа + Uint16 co_secretProtectBit; + + //переменные необходимые для работы PDO служб + Uint16 co_PDOMappingFlags;//RRRR RRRR TTTT TTTT - "T" - TPDO;- "R" - RPDO + + Uint16 co_PDO1Devisor; // делитель для получения заданной скорости передачи PDO1 + Uint16 co_PDO2Devisor; + Uint16 co_PDO3Devisor; + Uint16 co_PDO4Devisor; + Uint16 co_PDO5Devisor; + Uint16 co_PDO6Devisor; + Uint16 co_PDO7Devisor; + Uint16 co_PDO8Devisor; + // + Uint16 co_NumOfNextPDO; + Uint16 co_PDOTransmitFlags;//0000 0000 TTTT TTTT + Uint16 co_PDOTransmitEna; //0000 0000 TTTT TTTT + Uint16 co_PDOReceiveEna; //0000 0000 RRRR RRRR + + Uint16 co_my_PDO1TransmitFlags; + Uint16 co_my_PDO2TransmitFlags; + Uint16 co_my_PDO3TransmitFlags; + Uint16 co_my_PDO4TransmitFlags; + Uint16 co_my_PDO5TransmitFlags; + Uint16 co_my_PDO6TransmitFlags; + Uint16 co_my_PDO7TransmitFlags; + Uint16 co_my_PDO8TransmitFlags; + + + Uint32 co_RPDO1_addr[RPDO1NUMOFPARAMS]; + Uint32 co_RPDO2_addr[RPDO2NUMOFPARAMS]; + Uint32 co_RPDO3_addr[RPDO3NUMOFPARAMS]; + Uint32 co_RPDO4_addr[RPDO4NUMOFPARAMS]; + Uint32 co_RPDO5_addr[RPDO5NUMOFPARAMS]; + Uint32 co_RPDO6_addr[RPDO6NUMOFPARAMS]; + Uint32 co_RPDO7_addr[RPDO7NUMOFPARAMS]; + Uint32 co_RPDO8_addr[RPDO8NUMOFPARAMS]; + // + + Uint16 co_RPDO1_startBit[RPDO1NUMOFPARAMS]; + Uint16 co_RPDO2_startBit[RPDO2NUMOFPARAMS]; + Uint16 co_RPDO3_startBit[RPDO3NUMOFPARAMS]; + Uint16 co_RPDO4_startBit[RPDO4NUMOFPARAMS]; + Uint16 co_RPDO5_startBit[RPDO5NUMOFPARAMS]; + Uint16 co_RPDO6_startBit[RPDO6NUMOFPARAMS]; + Uint16 co_RPDO7_startBit[RPDO7NUMOFPARAMS]; + Uint16 co_RPDO8_startBit[RPDO8NUMOFPARAMS]; + // + + Uint16 co_RPDO1_numOfBits[RPDO1NUMOFPARAMS]; + Uint16 co_RPDO2_numOfBits[RPDO2NUMOFPARAMS]; + Uint16 co_RPDO3_numOfBits[RPDO3NUMOFPARAMS]; + Uint16 co_RPDO4_numOfBits[RPDO4NUMOFPARAMS]; + Uint16 co_RPDO5_numOfBits[RPDO5NUMOFPARAMS]; + Uint16 co_RPDO6_numOfBits[RPDO6NUMOFPARAMS]; + Uint16 co_RPDO7_numOfBits[RPDO7NUMOFPARAMS]; + Uint16 co_RPDO8_numOfBits[RPDO8NUMOFPARAMS]; + // + + Uint32 co_TPDO1_addr[TPDO1NUMOFPARAMS]; + Uint32 co_TPDO2_addr[TPDO2NUMOFPARAMS]; + Uint32 co_TPDO3_addr[TPDO3NUMOFPARAMS]; + Uint32 co_TPDO4_addr[TPDO4NUMOFPARAMS]; + Uint32 co_TPDO5_addr[TPDO5NUMOFPARAMS]; + Uint32 co_TPDO6_addr[TPDO6NUMOFPARAMS]; + Uint32 co_TPDO7_addr[TPDO7NUMOFPARAMS]; + Uint32 co_TPDO8_addr[TPDO8NUMOFPARAMS]; + // + + Uint16 co_TPDO1_startBit[TPDO1NUMOFPARAMS]; + Uint16 co_TPDO2_startBit[TPDO2NUMOFPARAMS]; + Uint16 co_TPDO3_startBit[TPDO3NUMOFPARAMS]; + Uint16 co_TPDO4_startBit[TPDO4NUMOFPARAMS]; + Uint16 co_TPDO5_startBit[TPDO5NUMOFPARAMS]; + Uint16 co_TPDO6_startBit[TPDO6NUMOFPARAMS]; + Uint16 co_TPDO7_startBit[TPDO7NUMOFPARAMS]; + Uint16 co_TPDO8_startBit[TPDO8NUMOFPARAMS]; + // + + Uint16 co_TPDO1_numOfBits[TPDO1NUMOFPARAMS]; + Uint16 co_TPDO2_numOfBits[TPDO2NUMOFPARAMS]; + Uint16 co_TPDO3_numOfBits[TPDO3NUMOFPARAMS]; + Uint16 co_TPDO4_numOfBits[TPDO4NUMOFPARAMS]; + Uint16 co_TPDO5_numOfBits[TPDO5NUMOFPARAMS]; + Uint16 co_TPDO6_numOfBits[TPDO6NUMOFPARAMS]; + Uint16 co_TPDO7_numOfBits[TPDO7NUMOFPARAMS]; + Uint16 co_TPDO8_numOfBits[TPDO8NUMOFPARAMS]; + + //данные для работы с энергонезависимой памятью + T_UserMemoryContext UM; + + Uint16 ParamRestorationError; + Uint16 co_requestCANInit; + Uint16 co_callbackTag; //передается в колбэк функции драйвера (соответствует 1 для 1го CAN и 2 для 2го CAN) + Uint32 ISRDroppingCounter; + //данные из coodedit-а + //Uint16 co_numOfInd; + int16* OD_TBL1; + Uint16* OD_TBL2; + int32* OD_TBL3; + Uint16* TYPE_DEF_TABLE; + int32* OD_CALLBACK_TBL; + + Uint16 co_SPIrange1rw; + Uint16 co_SPIrange1rwCRC; + Uint16 co_SPIrange1rwp; + Uint16 co_SPIrange1rwpCRC; + Uint16 co_SPIrange1rwps; + Uint16 co_SPIrange1rwpsCRC; + Uint16 co_SPIrange2rw; + Uint16 co_SPIrange2rwCRC; + Uint16 co_SPIrange2rwp; + Uint16 co_SPIrange2rwpCRC; + Uint16 co_SPIrange2rwps; + Uint16 co_SPIrange2rwpsCRC; + Uint16 co_SPIrange3rw; + Uint16 co_SPIrange3rwCRC; + Uint16 co_SPIrange3rwp; + Uint16 co_SPIrange3rwpCRC; + Uint16 co_SPIrange3rwps; + Uint16 co_SPIrange3rwpsCRC; + Uint16 co_SPIrange4rw; + Uint16 co_SPIrange4rwCRC; + Uint16 co_SPIrange4rwp; + Uint16 co_SPIrange4rwpCRC; + Uint16 co_SPIrange4rwps; + Uint16 co_SPIrange4rwpsCRC; + Uint16 co_SPIrange5rw; + Uint16 co_SPIrange5rwCRC; + Uint16 co_SPIrange5rwp; + Uint16 co_SPIrange5rwpCRC; + Uint16 co_SPIrange5rwps; + Uint16 co_SPIrange5rwpsCRC; + Uint16 co_first1000; + Uint16 co_first2000; + Uint16 co_first3000; + Uint16 co_first4000; + Uint16 co_first5000; + //указатели для работы с регистрами и функциями, привязанными к аппаратной части + _CAN_Node_TypeDef* CAN_NODE_REGS; + CAN_TypeDef* CAN_REGS; + Uint16 CAN_NODE_MO_OFFSET; + Uint16 CAN_NODE_LIST; + Uint16 CAN_MO_ISR_LINE; + Uint16 CAN_NVIC_ISR_LINE; + void (*GpioInit)(); + void (*CANINTDisable)(); + void (*CANINTEnable)(); + TBlockTransfer* BT; //указатель делаем чтоб легко инициализировать структуру TBlockTransfer + T_CANOPEN_DRV_SETTINGS settings; +}; + +typedef volatile struct SCo_OdVars TCo_OdVars; + +extern TCo_OdVars co1_vars; +extern TCo_OdVars co2_vars; +extern TBlockTransfer CAN1BlockTransfer; +extern TBlockTransfer CAN2BlockTransfer; + +//*************************************************************************************************************************************************** +#ifdef __cplusplus +} +#endif +#endif + + + +/*@}*/ + diff --git a/Vinclude/cood1.h b/Vinclude/cood1.h new file mode 100644 index 0000000..31bbdce --- /dev/null +++ b/Vinclude/cood1.h @@ -0,0 +1,78 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file cood2.h + \brief Объявляет некоторые служебные переменные, соторые должны быть определены в cood2.c + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 1.0 2017_01_25 + + @{ +*/ + +#include "DSP.h" + +//******************************************************************************************************** +//глобальные переменные 1-го CAN-а +extern int16 const CO1_OD_TBL1[]; +extern Uint16 const CO1_OD_TBL2[]; +extern long const CO1_OD_TBL3[]; +extern Uint16 const CO1_TYPE_DEF_TABLE[]; +extern long const CO1_OD_CALLBACK_TBL[]; + +extern Uint16 const co1_first1000; +extern Uint16 const co1_first2000; +extern Uint16 const co1_first3000; +extern Uint16 const co1_first4000; +extern Uint16 const co1_first5000; + +extern Uint16 const co1_SPIrange1rw; +extern Uint16 const co1_SPIrange1rwCRC; +extern Uint16 const co1_SPIrange1rwp; +extern Uint16 const co1_SPIrange1rwpCRC; +extern Uint16 const co1_SPIrange1rwps; +extern Uint16 const co1_SPIrange1rwpsCRC; + +extern Uint16 const co1_SPIrange2rw; +extern Uint16 const co1_SPIrange2rwCRC; +extern Uint16 const co1_SPIrange2rwp; +extern Uint16 const co1_SPIrange2rwpCRC; +extern Uint16 const co1_SPIrange2rwps; +extern Uint16 const co1_SPIrange2rwpsCRC; + +extern Uint16 const co1_SPIrange3rw; +extern Uint16 const co1_SPIrange3rwCRC; +extern Uint16 const co1_SPIrange3rwp; +extern Uint16 const co1_SPIrange3rwpCRC; +extern Uint16 const co1_SPIrange3rwps; +extern Uint16 const co1_SPIrange3rwpsCRC; + +extern Uint16 const co1_SPIrange4rw; +extern Uint16 const co1_SPIrange4rwCRC; +extern Uint16 const co1_SPIrange4rwp; +extern Uint16 const co1_SPIrange4rwpCRC; +extern Uint16 const co1_SPIrange4rwps; +extern Uint16 const co1_SPIrange4rwpsCRC; + +extern Uint16 const co1_SPIrange5rw; +extern Uint16 const co1_SPIrange5rwCRC; +extern Uint16 const co1_SPIrange5rwp; +extern Uint16 const co1_SPIrange5rwpCRC; +extern Uint16 const co1_SPIrange5rwps; +extern Uint16 const co1_SPIrange5rwpsCRC; + +extern Uint16 const co1_numOfInd; + +/*@}*/ + diff --git a/Vinclude/cood2.h b/Vinclude/cood2.h new file mode 100644 index 0000000..643813c --- /dev/null +++ b/Vinclude/cood2.h @@ -0,0 +1,78 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file cood2.h + \brief Объявляет некоторые служебные переменные, соторые должны быть определены в cood2.c + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 1.0 2017_01_25 + + @{ +*/ + +#include "DSP.h" + +//******************************************************************************************************** +//глобальные переменные 2-го CAN-а +extern int16 const CO2_OD_TBL1[]; +extern Uint16 const CO2_OD_TBL2[]; +extern long const CO2_OD_TBL3[]; +extern Uint16 const CO2_TYPE_DEF_TABLE[]; +extern long const CO2_OD_CALLBACK_TBL[]; + +extern Uint16 const co2_first1000; +extern Uint16 const co2_first2000; +extern Uint16 const co2_first3000; +extern Uint16 const co2_first4000; +extern Uint16 const co2_first5000; + +extern Uint16 const co2_SPIrange1rw; +extern Uint16 const co2_SPIrange1rwCRC; +extern Uint16 const co2_SPIrange1rwp; +extern Uint16 const co2_SPIrange1rwpCRC; +extern Uint16 const co2_SPIrange1rwps; +extern Uint16 const co2_SPIrange1rwpsCRC; + +extern Uint16 const co2_SPIrange2rw; +extern Uint16 const co2_SPIrange2rwCRC; +extern Uint16 const co2_SPIrange2rwp; +extern Uint16 const co2_SPIrange2rwpCRC; +extern Uint16 const co2_SPIrange2rwps; +extern Uint16 const co2_SPIrange2rwpsCRC; + +extern Uint16 const co2_SPIrange3rw; +extern Uint16 const co2_SPIrange3rwCRC; +extern Uint16 const co2_SPIrange3rwp; +extern Uint16 const co2_SPIrange3rwpCRC; +extern Uint16 const co2_SPIrange3rwps; +extern Uint16 const co2_SPIrange3rwpsCRC; + +extern Uint16 const co2_SPIrange4rw; +extern Uint16 const co2_SPIrange4rwCRC; +extern Uint16 const co2_SPIrange4rwp; +extern Uint16 const co2_SPIrange4rwpCRC; +extern Uint16 const co2_SPIrange4rwps; +extern Uint16 const co2_SPIrange4rwpsCRC; + +extern Uint16 const co2_SPIrange5rw; +extern Uint16 const co2_SPIrange5rwCRC; +extern Uint16 const co2_SPIrange5rwp; +extern Uint16 const co2_SPIrange5rwpCRC; +extern Uint16 const co2_SPIrange5rwps; +extern Uint16 const co2_SPIrange5rwpsCRC; + +extern Uint16 const co2_numOfInd; + +/*@}*/ + diff --git a/Vinclude/filter.h b/Vinclude/filter.h new file mode 100644 index 0000000..96f94dd --- /dev/null +++ b/Vinclude/filter.h @@ -0,0 +1,74 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file filter.h + \brief Инерционное звено в IQ математике (см. TFilter) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup filter Инерционный фильтр (см. TFilter) + + @{ +*/ + + +#ifndef FILTER_H +#define FILTER_H + +#ifdef __cplusplus +extern "C" +{ +#endif + + +/*! \class TFilter + \brief Инерционное звено в IQ математике + + Класс \a TFilter, основанный на структуре SFilter, представляет из себя + инерционное звено в терминах ТАУ, а именно W(p)=1/(Tfiltra*p+1). + Обычно оно используется в качестве инерционно фильтра, на вход которого + подается зашумленный сигнал, а на выходе оказывается отфильтрованный.*/ + +//! см. TFilter + struct SFilter + { + long input;//! Вход + long output;//! Выход + long T; //! T=Ts/Tfiltra где - Tfiltra постоянная времени фильтра + void (*calc)(volatile struct SFilter*);//указатель на функцию расчета + }; + + typedef volatile struct SFilter TFilter; + + //! инициализатор по-умолчанию +#define FILTER_DEFAULTS {0,0,_IQ(0.01), \ + TFilter_Calc} + + //! \memberof TFilter +void TFilter_Calc(TFilter*); + +#ifdef __cplusplus +} +#endif + + +#endif + +/*@}*/ + + + + + diff --git a/Vinclude/ipark.h b/Vinclude/ipark.h new file mode 100644 index 0000000..065236f --- /dev/null +++ b/Vinclude/ipark.h @@ -0,0 +1,69 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file ipark.h + \brief Модуль инверсных координатных преобразований координат (см. TIPark) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup IPark Инверсные координатные преобразования (см. TIPark) + @{ +*/ + +#ifndef IPARK_H +#define IPARK_H + +#ifdef __cplusplus +extern "C" { +#endif + + /*! \class TIPark + \brief Инверсные координатные преобразования + + Класс \a TIPark, основанный на структуре SIPark, обеспечивает + поворот вектора, заданного в ортогональных осях, на требуемый угол + поворота ang. Инверсия заключается в обратном угле поворота по сравнению + с модулем TPark.*/ + +//! см. TIPark +struct SIPark{ _iq ds;//!< Output: stationary d-axis stator variable + _iq qs;//!< Output: stationary q-axis stator variable + _iq ang;//!< Input: rotating angle (pu) + _iq de;//!< Input: rotating d-axis stator variable + _iq qe;//!< Input: rotating q-axis stator variable + void (*calc)(struct SIPark*); //!< Pointer to calculation function + }; + +typedef struct SIPark TIPark; + + //! инициализатор по-умолчанию +#define IPARK_DEFAULTS { 0, \ + 0, \ + 0, \ + 0, \ + 0, \ + ipark_calc } + + //! \memberof TIPark +void ipark_calc(TIPark*); + +#ifdef __cplusplus +} +#endif + +#endif + +/*@}*/ + diff --git a/Vinclude/main.h b/Vinclude/main.h new file mode 100644 index 0000000..af29581 --- /dev/null +++ b/Vinclude/main.h @@ -0,0 +1,192 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file main.h + \brief Главный заголовочный файл проекта. +Подключает в себе все заголовочные файлы всех модулей, +Содержит объявления (extern) всех наиболее важных +глобальных структур и переменных. + + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup MAIN Главный файл проекта + +@{*/ + +#ifndef MAIN_H +#define MAIN_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "DSP.h" +#include "build.h" +#include "V_common.h" +#include //для labs +#include "V_IQmath.h" +#include "SM_Sys.h" +#include "SM_Net.h" +#include "co_ODvars.h" +#include "CANOpen_drv.h" +#include "V_data_log.h" +#include "SM_Protect.h" +#include "V_bits_to_enum_numbers.h" +#include "SM_Ctrl.h" +#include "SM_CmdLogic.h" +#include "V_RTC_Clock.h" +#include "clarke.h" +#include "park.h" +#include "ipark.h" +#include "V_pid_reg3.h" +#include "V_pid_reg3_pos.h" +#include "V_rmp_ctrl.h" +#include "V_adc.h" +#include "V_PWM_Module.h" +#include "V_CurPar.h" +#include "V_hzprof.h" +#include "V_DPR_eCAP.h" +#include "V_QEP.h" +#include "V_led.h" +#include "V_AutoOffset.h" +#include "V_CANtoRS.h" +#include "V_SSI_Encoder.h" +#include "V_UserMemory.h" +#include "V_rotor_observer.h" +#include "V_relay_reg.h" +#include "DRV_INTERFACE.h" +#include "V_event_log.h" +#include "Global_time.h" +#include "V_fifo.h" +#include "V_usblib.h" +#include "V_watchdog.h" + +extern TClarke clarke; +extern TPark park; +extern TIPark ipark; +extern TPidReg3 pid_id; +extern TPidReg3 pid_iq; +extern TPidReg3 pid_ia; +extern TPidReg3 pid_spd; +extern TPidReg3_pos pid_pos; +extern TSM_Sys sm_sys; +extern Uint16 disp_group_number; +extern TDataLog dlog; +extern TSM_Protect sm_prot; +extern TCmd cmd; +extern TDrvStatus drv_status; +extern TBitsToEnumNums pult_faults_lister; +extern TSM_Ctrl sm_ctrl; +extern TSM_CmdLogic sm_cmd_logic; +extern TRefs refs; +extern TSM_Net sm_net; +extern TRMPCtrl rmp; +extern TDrvParams drv_params; +extern TAdcDrv adc; +extern TPWM_Module pwm; +extern TCurPar cur_par; +extern TVhzProf vhz; +extern TDPReCAP DPReCAP; +extern TposspeedEqep posspeedEqep; +extern TRTCClock RTCclock; +extern TAutoOffset AutoOffset; +extern TSSI_Encoder SSI_Encoder; +extern TRotorObserver RotorObserver; +extern TCANtoRS CANtoRS; +extern TDrvInterface drv_interface; +extern TLogger FaultLog; +extern TGlobalTime global_time; + +extern Uint16 msCounter; +extern Uint16 FastCounter; +extern Uint16 LoopCounter; +extern Uint16 TIsr10; +extern Uint16 TIsr1; +extern int drv_status_code; +extern Uint32 VendorToken; + +volatile extern long Debug1; +volatile extern long Debug2; +volatile extern Uint16 Debug3; +volatile extern Uint16 Debug4; +volatile extern long DebugW1; +volatile extern long DebugW2; +volatile extern long DebugW3; +volatile extern long DebugW4; +volatile extern float DebugF1; +volatile extern float DebugF2; +volatile extern float DebugF3; +volatile extern float DebugF4; + +//Счетчики прерываний модуля захвата +extern Uint16 CounterCAP_isr; +extern Uint16 cap0_counter; +extern Uint16 cap1_counter; +extern Uint16 cap2_counter; + +extern unsigned long CpuTimerIsr1; +extern TSysSwitches sw; + +extern TUserMemory UserMem; +extern Tled leds; +//extern TCanBTInterface Can1BTInterface; +//extern TCanBTInterface Can2BTInterface; +extern TCANSpeedTableOptions canSpeedTable; + +void callback_dlog(Uint16 par, Uint16 tag_CANnum); +void callback_RTC(Uint16 par, Uint16 tag_CANnum); +void propReset(void); + +// Объявление ISR-ов. В CodeMaster-ском и GCC-шном стартапе они назиываются по-разному +#if defined (__GNUC__) +void TIM1_IRQHandler(void); +void TIM0_IRQHandler(void); +void EPWM_TZ_0_IRQHandler(void); +void ECAP0_IRQHandler(void); +void ECAP1_IRQHandler(void); +void ECAP2_IRQHandler(void); +void EQEP1_IRQHandler(void); +#elif defined (__CMCPPARM__) +void TIM1_IRQHandler(void); +void TIM0_IRQHandler(void); +void PWM0_TZ_IRQHandler(void); +void CAP0_IRQHandler(void); +void CAP1_IRQHandler(void); +void CAP2_IRQHandler(void); +void QEP1_IRQHandler(void); +#endif + +#if defined(TRUE) && (TRUE != 1) +#error "TRUE previously defined not equal to 1" +#endif +#if defined(FALSE) && (FALSE != 0) +#error "FALSE previously defined not equal to 0" +#endif +#ifndef TRUE +#define TRUE (1) +#endif +#ifndef FALSE +#define FALSE (0) +#endif + +#ifdef __cplusplus +} +#endif + +#endif +/*@}*/ + diff --git a/Vinclude/mbod.h b/Vinclude/mbod.h new file mode 100644 index 0000000..410a919 --- /dev/null +++ b/Vinclude/mbod.h @@ -0,0 +1,44 @@ +/* Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \author ООО "НПФ Вектор". http://motorcontrol.ru +*/ + +#ifndef MBOD_H +#define MBOD_H + +#include "DSP.h" + + + +#define MB_VAR_WRITE 1 // признак записи в ModBus-переменную +#define MB_VAR_READ 2 // признак чтения из ModBus-переменной + +typedef struct +{ + Uint16 index; // ModBus-адрес + Uint16 type_or_acc; // номер бита для битовых переменных или признак записи/чтения + // для HR/IR-переменных (должен сбрасываться пользователем): + // 1 - произошла запись + // 2 - произошло чтение + Uint32 addr; // адрес переменной в контроллере +} MB_Record; + +extern volatile MB_Record mbodHR[]; +extern volatile MB_Record mbodIR[]; +extern volatile MB_Record mbodC[]; +extern volatile MB_Record mbodDI[]; + +#endif + diff --git a/Vinclude/park.h b/Vinclude/park.h new file mode 100644 index 0000000..dbd8f59 --- /dev/null +++ b/Vinclude/park.h @@ -0,0 +1,68 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file park.h + \brief Модуль координатных преобразований координат (см. TPark) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \defgroup Park Координатные преобразования (см. TPark) + @{ +*/ +#ifndef PARK_H +#define PARK_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "V_IQmath.h" + + /*! \class TPark + \brief Координатные преобразования + + Класс \a TPark, основанный на структуре SPark, обеспечивает + поворот вектора (ds,qs), заданного в ортогональных осях, на требуемый угол + поворота ang. Выходной повернутый вектор сохраняется в переменных de,qe. */ + +//! см. TPark +struct SPark{ _iq ds; //!< Input: stationary d-axis stator variable + _iq qs; //!< Input: stationary q-axis stator variable + _iq ang; //!< Input: rotating angle (pu) + _iq de; //!< Output: rotating d-axis stator variable + _iq qe; //!< Output: rotating q-axis stator variable + void (*calc)(struct SPark*);//!< Pointer to calculation function + }; + +typedef struct SPark TPark; + +//! инициализатор по-умолчанию +#define PARK_DEFAULTS { 0, \ + 0, \ + 0, \ + 0, \ + 0, \ + park_calc } + + //! \memberof TPark +void park_calc(TPark*); + +#ifdef __cplusplus +} +#endif + +#endif + +/*@}*/ diff --git a/Vsrc/CANOpenUDfuncs.c b/Vsrc/CANOpenUDfuncs.c new file mode 100644 index 0000000..4f12b2c --- /dev/null +++ b/Vsrc/CANOpenUDfuncs.c @@ -0,0 +1,400 @@ +/* ================================================================================== + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + +//File name: CANOpenUDfuncs.c + +//Description: В файл вынесены функции драйвера CANOpen определяемые пользователем (колбэк функции, функции инициализации и т.п.) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 1.0 2017_02_08 + +//=====================================================================================*/ +#include "DSP.h" +#include "co_ODvars.h" +#include "CANOpen_drv.h" +#include "main.h" + +//! Таблица с настройками скоростей CAN для микроконтроллеров фирмы НИИЭТ. Раскомментить нужное. + +// Вносить изменениЯ в нижеописанные переменные и массивы ЗАПРЕЩЕНО!!! + +//! Микроконтроллер К1921ВК01Т +/* +// kb/s: 125 50 125 250 500 1000 +TCANSpeedTableOptions canSpeedTable = { {1, 1, 1, 0, 0, 0 }, \ + {9, 24, 9, 39, 19, 9 }, \ + {6, 6, 6, 6, 6, 6 }, \ + {1, 1, 1, 1, 1, 1 }, \ + {1, 1, 1, 1, 1 , 1 }, \ + }; +// ^- настройка на 125, т.к. 10 kb/s не реализуемо +*/ +//! Микроконтроллер К1921ВК028 +/* +// kb/s: 125 50 125 250 500 1000 +TCANSpeedTableOptions canSpeedTable = { {1, 1, 1, 1, 0, 0 }, \ + {19, 49, 19, 9, 39, 19}, \ + {6, 6, 6, 6, 6, 6 }, \ + {1, 1, 1, 1, 1, 1 }, \ + {1, 1, 1, 1, 1 , 1 }, \ + }; +// ^- настройка на 125, т.к. 10 kb/s не реализуемо +*/ +//! Микроконтроллер К1921ВК035 +// kb/s: 125 50 125 250 500 1000 +TCANSpeedTableOptions canSpeedTable = { {1, 1, 1, 0, 0, 0 }, \ + {9, 24, 9, 39, 19, 9 }, \ + {6, 6, 6, 6, 6, 6 }, \ + {1, 1, 1, 1, 1, 1 }, \ + {1, 1, 1, 1, 1 , 1 }, \ + }; +// ^- настройка на 125, т.к. 10 kb/s не реализуемо + +//********************************************************************************************************************************************************************************************************** +//функция инициализации Gpio CAN1 +#ifdef CAN_1_ENABLE +void co_CAN1GpioInit() +{ + //переводим ГПИО на выполнение функции CAN + GPIOB->ALTFUNCSET = (1 << 14) + (1 << 15); //CAN_TX[0], CAN_RX[0] + GPIOB->DENSET = (1 << 14) + (1 << 15); +} +#endif //CAN_1_ENABLE + +//функция инициализации Gpio CAN2 +#ifdef CAN_2_ENABLE +void co_CAN2GpioInit() +{ +// //выбираем альтернативную функцию ГПИО +//#if defined HW_VECTOR_MK_40_4 +// NT_COMMON_REG->GPIOPCTLC_bit.PIN1 = 1; //CAN_TX[1] +// NT_COMMON_REG->GPIOPCTLC_bit.PIN2 = 1; //CAN_RX[1] +// +// //переводим ГПИО на выполнение функции CAN +// NT_GPIOC->ALTFUNCSET = (1 << 1) + (1 << 2); //CAN_TX[0], CAN_RX[0] +// +//#else +// NT_COMMON_REG->GPIOPCTLF_bit.PIN14 = 0; //CAN_TX[1] +// NT_COMMON_REG->GPIOPCTLF_bit.PIN15 = 0; //CAN_RX[1] +// +// //переводим ГПИО на выполнение функции CAN +// NT_GPIOF->ALTFUNCSET = (1 << 14) + (1 << 15); //CAN_TX[0], CAN_RX[0] +//#endif +// + +} +#endif //CAN_2_ENABLE +//********************************************************************************************************************************************************************************************************** +//Функции работы с энергонезависимой памятью (в качестве памяти может использоваться как пользовательская флэш на борту MCU, +// так и внешне подключаемая, например через SPI, eeprom). +//Функции используются драйвером CANopen при сохранении и восстановлении параметров словаря объектов +//С точки зрения драйвера CANOpen функции реализуют побайтовое чтение и запись из/в ЭнОЗУ +void co_UserMemoryRead (const T_UserMemoryContext *p) +{ +// UserMem.MemStartAddr = p->MemStartAddr; +// UserMem.MCUStartAddr = p->MCUStartAddr; +// UserMem.data_length = p->data_length; +// UserMem.read(&UserMem); +} + +void co_UserMemoryWrite (const T_UserMemoryContext *p) +{ +// UserMem.MemStartAddr = p->MemStartAddr; +// UserMem.MCUStartAddr = p->MCUStartAddr; +// UserMem.data_length = p->data_length; +// UserMem.write(&UserMem); +} +//********************************************************************************************************************************************************************************************************** + +//функция, которая вызывается драйвером CANOpen при необходимости отправки CAN сообщения во внешний интерфейс +//внутрь функции пользователем должен быть вставлен вызов соответствующей функции, осуществляющей передачу CAN пакета +void co_CANToExtInterface_Send(TZCanMsg* MSG, Uint16 tag_CANnum) +{ + CANtoRS.write(MSG,&CANtoRS); +} + + + +//колбэки по приему PDO +void co_RPDO1_Callback(Uint16 nodeID, Uint16 tag_CANnum) +{ + /* + switch(nodeID) + { + case 1: + { + //обрабатываем как-нибудь... + break; + } + case 2: + { + PDO_cntr2++; + //обрабатываем как-нибудь... + break; + } + default: + break; + } + */ +} + +void co_RPDO2_Callback(Uint16 nodeID, Uint16 tag_CANnum) +{ + /* + switch(nodeID) + { + case 1: + { + //обрабатываем как-нибудь... + break; + } + default: + break; + } + */ +} + +void co_RPDO3_Callback(Uint16 nodeID, Uint16 tag_CANnum) +{ + /* + switch(nodeID) + { + case 1: + { + //обрабатываем как-нибудь... + break; + } + default: + break; + } + */ +} + +void co_RPDO4_Callback(Uint16 nodeID, Uint16 tag_CANnum) +{ + /* + switch(nodeID) + { + case 1: + { + //обрабатываем как-нибудь... + break; + } + default: + break; + } + */ +} + +void co_RPDO5_Callback(Uint16 nodeID, Uint16 tag_CANnum) +{ + /* + switch(nodeID) + { + case 1: + { + //обрабатываем как-нибудь... + break; + } + default: + break; + } + */ +} + +void co_RPDO6_Callback(Uint16 nodeID, Uint16 tag_CANnum) +{ + /* + switch(nodeID) + { + case 1: + { + //обрабатываем как-нибудь... + break; + } + default: + break; + } + */ +} + +void co_RPDO7_Callback(Uint16 nodeID, Uint16 tag_CANnum) +{ + /* + switch(nodeID) + { + case 1: + { + //обрабатываем как-нибудь... + break; + } + default: + break; + } + */ +} + +void co_RPDO8_Callback(Uint16 nodeID, Uint16 tag_CANnum) +{ + /* + switch(nodeID) + { + case 1: + { + //обрабатываем как-нибудь... + break; + } + default: + break; + } + */ +} + + + +//!Обращение по CANopen к часам реального времени. + +//!Если происходит запись в параметр [5139h.01h] Текущ. знач.Часы реального времени, +//то вызывается callback_RTC - там устанавливается запрос на коррекцию часов. + +void callback_RTC(Uint16 par, Uint16 tag_CANnum) { + if (par == 1) { + RTCclock.setTimeFlag = 1; //произошла запись в часы + + } +} + +//!Обращение к переменной dlog.next_value_var с данными цифрового осциллографа. + +//!Существует специальный интерфейс, позволяющий автоматизировать считывание оссциллографируемых переменных +//!модуля TDataLog. Эта функция вызывается при обращении к переменной, через которую возможно считать записанные +//!осциллограммы. Запись в эту переменную устанавливает требуемый номер буфера (один и 4х) и номер извлекаемой точки. +//!При чтении же в эту переменную выдвигатются сами отосциллограффированные данные. + +void callback_dlog(Uint16 par, Uint16 tag_CANnum) { + //если запись, то установим буфер на нужную точку + if (par == 1) { + //в переменную next_value_var записываетсЯ желаемое смещение, номер буфера, из которого хотим читать, + //а так же разреживание + dlog.buff_num = (long)((dlog.next_value_var >> 24) & 3); //извлекаетсЯ номер буфера +#if DLOG_DATA_SIZE == 32 + dlog.highPartOfValue = (int)((dlog.next_value_var >> 26) & 1); // отдавать старшую часть 32-битного значения? +#endif + dlog.Rcounter = (dlog.next_value_var >> 16) & 0xFF; //какую точку надо отдавать + +// //проверЯем хотЯт ли использовать блочную передачу +// if ((dlog.next_value_var & 0xffff) == 1) { +// //хотЯт, говорим об этом интерфейсу блочной передачи +//#ifdef CAN_1_ENABLE +// if (co1_vars.co_blockTransferCommand == CANBT_INTERFACE_FREE) +// co1_vars.co_blockTransferCommand = CANBT_INTERFACE_DATALOG1; +//#endif +//#ifdef CAN_2_ENABLE +// if (co2_vars.co_blockTransferCommand == CANBT_INTERFACE_FREE) +// co2_vars.co_blockTransferCommand = CANBT_INTERFACE_DATALOG1; +//#endif +// } +//#if DLOG_DATA_SIZE == 32 +// if ((dlog.next_value_var & 0xffff) == 2) { +//#ifdef CAN_1_ENABLE +// if (co1_vars.co_blockTransferCommand == CANBT_INTERFACE_FREE) +// co1_vars.co_blockTransferCommand = CANBT_INTERFACE_DATALOG2; +//#endif +//#ifdef CAN_2_ENABLE +// if (co2_vars.co_blockTransferCommand == CANBT_INTERFACE_FREE) +// co2_vars.co_blockTransferCommand = CANBT_INTERFACE_DATALOG2; +//#endif +// } +//#endif // DLOG_DATA_SIZE == 32 + + } + + //выдвигаем данные: +#if DLOG_DATA_SIZE == 16 + switch (dlog.buff_num) { //текущий номер буфера + case 0: { + dlog.next_value_var = dlog.dl_buffer1_adr[(dlog.Rcounter + dlog.first_point_written) & 0xFF]; + break; + } + case 1: { + dlog.next_value_var = dlog.dl_buffer2_adr[(dlog.Rcounter + dlog.first_point_written) & 0xFF]; + break; + } + case 2: { + dlog.next_value_var = dlog.dl_buffer3_adr[(dlog.Rcounter + dlog.first_point_written) & 0xFF]; + break; + } + case 3: { + dlog.next_value_var = dlog.dl_buffer4_adr[(dlog.Rcounter + dlog.first_point_written) & 0xFF]; + break; + } + default: { //если в buff_num что-то не то, по-дефолту пусть первый буфер + dlog.next_value_var = dlog.dl_buffer1_adr[(dlog.Rcounter + dlog.first_point_written) & 0xFF]; + break; + } + } + //данные только в нижней части + dlog.next_value_var &= 0xFFFF; + dlog.next_value_var |= (((unsigned long) dlog.Rcounter) << 16); //в верхней части слова Rcounter длЯ контролЯ + dlog.next_value_var |= (((unsigned long) dlog.buff_num) << 24); //в верхней части слова (еще выше) buff_num длЯ контролЯ + + dlog.Rcounter++; //какую точку отдаем. инкрементируетсЯ само после чтениЯ текущей точки. + dlog.Rcounter &= 0xFF; //по кругу. ничего страшного, перед чтением обнулЯю. см. запись +#endif +#if DLOG_DATA_SIZE == 32 + int32 val32; + int varSizeIs16; + switch (dlog.buff_num) { //текущий номер буфера + default: + case 0: { + val32 = dlog.dl_buffer1_adr[(dlog.Rcounter + dlog.first_point_written) & 0xFF]; + varSizeIs16 = (int)(dlog.object1Info.varSize == 16); + break; + } + case 1: { + val32 = dlog.dl_buffer2_adr[(dlog.Rcounter + dlog.first_point_written) & 0xFF]; + varSizeIs16 = (int)(dlog.object2Info.varSize == 16); + break; + } + case 2: { + val32 = dlog.dl_buffer3_adr[(dlog.Rcounter + dlog.first_point_written) & 0xFF]; + varSizeIs16 = (int)(dlog.object3Info.varSize == 16); + break; + } + case 3: { + val32 = dlog.dl_buffer4_adr[(dlog.Rcounter + dlog.first_point_written) & 0xFF]; + varSizeIs16 = (int)(dlog.object4Info.varSize == 16); + break; + } + } + dlog.next_value_var = (dlog.highPartOfValue != 0 ? val32 >> 16 : val32) & 0x0000FFFF; + dlog.next_value_var |= ((Uint32)dlog.Rcounter) << 16; + dlog.next_value_var |= ((Uint32)dlog.buff_num) << 24; + dlog.next_value_var |= ((Uint32)dlog.highPartOfValue) << 26; + dlog.next_value_var |= ((Uint32)varSizeIs16) << 27; + + if ((dlog.highPartOfValue != 0) || varSizeIs16) + { + // При следующем запросе отдадим младшую часть следующей точки. + dlog.Rcounter++; + dlog.Rcounter &= 0xFF; + dlog.highPartOfValue = 0; + } + else + { + // При следующем запросе отдадим старшую часть этой же точки. + dlog.highPartOfValue = 1; + } +#endif +} diff --git a/Vsrc/DRV_INTERFACE.c b/Vsrc/DRV_INTERFACE.c new file mode 100644 index 0000000..17ed2b8 --- /dev/null +++ b/Vsrc/DRV_INTERFACE.c @@ -0,0 +1,108 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file DRV_INTERFACE.c + \brief Через данные модуль обеспечиваетсЯ работа с банком аварий (чтение, очистка). + //ПредполагаетсЯ, что модуль может расширЯть функциональность (скачивать каие-то другие данные)... + //ПРИМЕЧАНИЕ для программиста: + 1.для команд работающих по сети с автоматизированными системами (Юникон,, пульты и т.д.) после выполнения команды поле ans_data должно быть установлено значением запроса: + p->ans_data = temp; + что сообщит внешней системе, что запрос обработан. В этом случае поле p->ans_data обнуляется внешней автоматизированной системой после сбора информации с полей + p->data_Low + p->data_High + 2.для внутренних вызовов поле p->ans_data трогать не нужно + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.1 2017_07_24 + + */ + + +#include "main.h" +void DRV_INTERFACE_Calc(TDrvInterface *p) { + TEvent event; + + long temp = (p->req_data); //принЯтие запроса + + p->INTERFACE_delta_time_sec = global_time.relative_time1.second_counter - p->INTERFACE_time_sec; + // проверка "ухода" ответа + if ((p->ans_data != 0) && (p->INTERFACE_delta_time_sec < DRV_INTERFACE_RESET_TIME)) + return; + + //раз сюда попали значит либо таймаут длЯ анса истек, либо он нулевой + //в любом случае его обнулЯем + p->ans_data = 0; + //запрос обнулЯем только после выполнениЯ, чтобы внешние устройства могли контролить выполнение запроса + switch ((temp) >> 16) + { + case DATA_REQUEST_READ_FAULT: //запрос на чтение ошибки + { + FaultLog.read(&FaultLog, (temp & 0x0FFFF), &event); + //формируем ответ + p->data_Low = (((Uint32) (event.ev_num)) << 16) + event.ev_code; + p->data_High = event.ev_time; + + p->ans_data = temp; //говорим Юникону, что команда обработана + //фиксируем времЯ ответа + p->INTERFACE_time_sec = global_time.relative_time1.second_counter; + break; + } + case DATA_REQUEST_WRITE_FAULT: //запрос на запись ошибки + { + //!!! + //пока через интерфейс писать ошибку нельзЯ + break; + } + case DATA_REQUEST_WRITE_WORK_TIME: //запрос на запись work_time + { + global_time.relative_time1.relative_date.hour = 0; + global_time.relative_time1.relative_date.minute = 0; + global_time.WtiteSPI_flag = 1; + + break; + } + case DATA_REQUEST_READ_WORK_TIME: //запрос на чтение work_time + { + //Ma][: Бу! + break; + } + case DATA_REQUEST_WRITE_OPER_TIME: { //запрос на запись oper_time + global_time.relative_time2.relative_date.hour = 0; + global_time.relative_time2.relative_date.minute = 0; + global_time.WtiteSPI_flag = 1; + + break; + } + case DATA_REQUEST_READ_OPER_TIME: //запрос на чтение ошибки + { + //Ma][: Бу! + break; + } + case DATA_REQUEST_CLEAR_ALL: //запрос на очистку банка аварий + { + FaultLog.clear(&FaultLog); + //формируем ответ + p->data_High = 0; + p->data_Low = 0; + + p->ans_data = temp; //говорим Юникону, что команда обработана + //фиксируем времЯ ответа + p->INTERFACE_time_sec = global_time.relative_time1.second_counter; + break; + } + } + + p->req_data = 0;//обнулЯем поле запроса, чтобы не выполнить его повторно +} + diff --git a/Vsrc/SM_CmdLogic.c b/Vsrc/SM_CmdLogic.c new file mode 100644 index 0000000..2182aef --- /dev/null +++ b/Vsrc/SM_CmdLogic.c @@ -0,0 +1,109 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file SMCmdLogic.c + \brief Обработка команд и заданий, поступающих из различных источников. (см. TSM_CmdLogic) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup SMCmdLogic + @{*/ + +#include "DSP.h" +#include "V_IQmath.h" +#include "main.h" + +//!Инициализация + +//!Всякие обнуления... +//! \memberof TSM_CmdLogic +void SM_CmdLogicInit(TSM_CmdLogic *p) { + p->state = 0; + p->state_prev = 0xFF; + cmd.all = 0; + +} + +//!Медленный расчет + +//! \memberof TSM_CmdLogic +void SM_CmdLogicSlow_Calc(TSM_CmdLogic *p) { + +} + +//!1кГц расчет + +//!Обработка различных источников команд и расчет ДА, +//!который переключает глобально режимы РАБОТА и ОСТАНОВ. +//! \memberof TSM_CmdLogic +void SM_CmdLogicms_Calc(TSM_CmdLogic *p) { + + //Стандартная обработка дискретного автомата + if (p->state_prev != p->state) + p->E = 1; + else + p->E = 0; + p->state_prev = p->state; + + + //определяем режим работы + switch (p->state) { + case CMD_LOGIC_TURNED_OFF: { //состояние 0- ОТКЛЮЧЕН + if (p->E == 1) { + /*ENTRY*/ + sm_ctrl.state = CTRL_STOP; + drv_status.bit.ready = 1; + drv_status.bit.running = 0; + } + + if (sm_prot.state == PROT_ON_OK) {//если ДА защит включился, обрабатываем команды включения + if ((cmd.bit.start == 1) && (sm_sys.state == SYS_READY))//есть битовая команда старта + p->state = CMD_LOGIC_TURNED_ON; //поехали + } + + //дискретный автомат со структурами управления в СТОПе всегда тоже принудительно переводим в стоп + sm_ctrl.state = CTRL_STOP; + //всегда сбрасываем битовые команды управления + cmd.bit.stop = 0; + cmd.bit.start = 0; + break; + } + + case CMD_LOGIC_TURNED_ON: { //состояние - РАБОТА + if (p->E == 1) { + /*ENTRY*/ + drv_status.bit.ready = 1; + drv_status.bit.running = 1; + sm_ctrl.state = CTRL_RUN;//поехали + } + //если АВАРИя или КОМАНДА СТОП то состояние стоп + if ((sm_prot.state == PROT_FAIL) || (cmd.bit.stop == 1) + || (sm_ctrl.state == CTRL_STOP)){ + p->state = CMD_LOGIC_TURNED_OFF; + } + + //всегда сбрасываем команду управления + cmd.bit.stop = 0; + cmd.bit.start = 0; + break; + } + + default: + break; + + } // конец switch(p->state) +} + +/*@}*/ diff --git a/Vsrc/SM_Ctrl.c b/Vsrc/SM_Ctrl.c new file mode 100644 index 0000000..28f0040 --- /dev/null +++ b/Vsrc/SM_Ctrl.c @@ -0,0 +1,783 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file SMCtrl.c + \brief Основной ДА переключения систем управления (см. TSM_Ctrl) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + */ + +/** \addtogroup SMCtrl */ +/*@{*/ + +#include "DSP.h" +#include "V_IQmath.h" +#include "main.h" + + +//!Инициализация +//!Всякие обнуления +//! \memberof TSM_Ctrl +void SM_Ctrl_Init(TSM_Ctrl *p) { + p->state_prev = 0xff; + p->state = 0x00; +} + +//!Фоновый расчет + +//! \memberof TSM_Ctrl +void SM_Ctrl_Slow_Calc(TSM_Ctrl *p) { + +} + +//!Миллисекундный расчет + +//! \memberof TSM_Ctrl +void SM_Ctrl_ms_Calc(TSM_Ctrl *p) { + +} + +//!Быстрый расчет + +//!Реализует все структуры управления (режимы работы), такие как +//!Векторное управление, скалярное, режим постоянного тока и т.п. +//!Здесь реализован основной ДА переключения систем управления. +//!Кроме того, происходит расчет некоторых вспомогательных модулей. +//!Можно сказать, здесь находится "ядро" всей системы управления, +//!и именно в этой функции происходит непосредственное управление двигателем с +//!использованием всех остальных модулей. + +//! \memberof TSM_Ctrl +void SM_Ctrl_Fast_Calc(TSM_Ctrl *p) { + +//если система находится в перееинициализации, +//то пропускаем контур управления + if (sm_sys.state == SYS_INIT) { + return; + } + +//если команда остановить, то переходим +//в режим ОСТАНОВЛЕН + if (cmd.bit.stop == 1) + p->state = CTRL_STOP; +// если есть авария, то переходим в стоп + if (sm_prot.state == PROT_FAIL) + p->state = CTRL_STOP; + +//считаем дискретный автомат + if (p->state_prev != p->state) + p->E = 1; + else + p->E = 0; +//нужно для дискретного автомата, определение +//первого вхождения + p->state_prev = p->state; + + switch (p->state) { + case CTRL_STOP: { //Состояние ОСТАНОВ + if (p->E == 1) { //Если первое вхождение в состояние + cmd.bit.start = 0; + DPReCAP.speed = 0; + DPReCAP.Ts = 0; + DPReCAP.Tspeed = 0; + global_time.WtiteSPI_flag = 1; //записать времЯ работы + //при переходе в стоп и работающем + //осциллографе переводим его в режим + //однократной записи, чтобы зафиксир. возможную аварию. + if (dlog.StartBits & (1 << 8)) //Если пользователь задал этот бит + dlog.set_mode(1, &dlog); //запускаем осциллограф по этому событию + + if (sm_prot.state==PROT_FAIL)//если мы перешли в стоп, а модуль защит в аварии + if (dlog.mode_reset==2)//и даталоггер крутился + dlog.mode_reset=1;//то остановим осц, пусть будет осца аварии + } + pwm.Off(&pwm); //Выкл ШИМ + // refs.theta_elec=0; + + //Обнуление всего опасного + pwm.UalphaRef = 0; + pwm.UbetaRef = 0; + pwm.update(&pwm); + pid_id.reset(&pid_id); + pid_iq.reset(&pid_iq); + pid_ia.reset(&pid_ia); + pid_spd.reset(&pid_spd); + pid_pos.reset(&pid_pos); + cur_par.Is = 0; + cur_par.power = 0; + cur_par.speed = 0; + // cur_par.ThetaRefCurr=0; + + /* Конец */ + break; + } + + case CTRL_RUN: { //Состояние запуска + if (p->E == 1) { + /*ENTRY START*/ + drv_status.bit.running = 1; + pwm.On(&pwm);//Включение модуля ШИМ + p->ctrl_counter = 0; + if (dlog.StartBits & (1 << 0)) //Если пользователь задал этот бит + dlog.set_mode(1, &dlog); //запускаем осциллограф по этому событию + /*ENTRY END*/ + } + /*DO START*/ + + p->ctrl_counter++; + + + if (p->run_mode == CTRL_RUN_U2F) {//скалярный режим + p->state = CTRL_RUN_U2F; + } + if (p->run_mode == CTRL_FLUXING) {//режим удержания (постоянный ток) + p->state = CTRL_FLUXING; + } + if (p->run_mode == CTRL_RUN_I2F) {//частотно-токовый режим (вращение вектора тока) + p->state = CTRL_RUN_I2F; + } + if (p->run_mode == CTRL_RUN_VECTOR_SM) {//векторная СУ синхронной машины с двумя контурами + p->state = CTRL_RUN_VECTOR_SM; + } + if (p->run_mode == CTRL_RUN_VECTOR_SM_ENCODER_POS) {//векторная СУ синхронной машины с обратной связью по энкодеру и контуром положения + p->state = CTRL_RUN_VECTOR_SM_ENCODER_POS; + } + if (p->run_mode == CTRL_RUN_VECTOR_IM_ENCODER) {//векторная СУ синхронной машины с обратной связью по энкодеру и контуром положения + p->state = CTRL_RUN_VECTOR_IM_ENCODER; + } + if (p->run_mode == CTRL_AUTO_SENSOR_TUNING) {//автоматическая настройка смещений в ДПР (частотно-токовая+доп. логика) + p->state = CTRL_AUTO_SENSOR_TUNING; + } + + if (p->run_mode == CTRL_RUN_LATENCY_TEST) { // Режим измерения задержки между ШИМ и датчиками тока + p->state = CTRL_RUN_LATENCY_TEST; + } + + /*DO END*/ + break; + } + + case CTRL_FLUXING: { //Режим постоянный ток + if (p->E == 1) { + /*ENTRY START*/ + pwm.On(&pwm); + pid_id.ui_reg3 = 0; //сбрасывем интегральные каналы + pid_iq.ui_reg3 = 0; //чтобы не накапливались + pid_spd.ui_reg3 = 0; + refs.theta_elec = 0;//заданный угол - 0. Но он есть в группе Задания, его можно менять на ходу! + + if (dlog.StartBits & (1 << 1)) + dlog.set_mode(1, &dlog); + /*ENTRY END*/ + } + /*DO START*/ + + //два тока фаз из АЦП в модуль фазных преобразований + clarke.as = adc.Imeas_a; + clarke.bs = adc.Imeas_b; + clarke.calc(&clarke);//расчет + + //из фазных преобразований в координатные преобразования. + //Поворачиваем вектор на заданный угол refs.theta_elec + park.ds = clarke.ds; + park.qs = clarke.qs; + park.ang = refs.theta_elec; + park.calc(&park); + + //регулятор тока "как бы" оси d (на самом деле эта ось к двигателю к оси d не привязана, это свободная ось) + pid_id.pid_ref_reg3 = refs.i_flux_ref; //задание на ток намагничивания + pid_id.pid_fdb_reg3 = park.de;//обратная связь - то что пришло с фазных преобразований + pid_id.calc(&pid_id); + + //регулятор тока "как бы" оси q (на самом деле эта ось к двигателю к оси q не привязана, это свободная ось) + pid_iq.pid_ref_reg3 = 0;//задание - ноль + pid_iq.pid_fdb_reg3 = park.qe;park.de;//обратная связь - то что пришло с фазных преобразований + pid_iq.calc(&pid_iq); + + //обратные фазные преобразования. + //Крутим вектор напряжения, который выдают регуляторы токов обратно на угол refs.theta_elec + ipark.de = pid_id.pid_out_reg3; + ipark.qe = pid_iq.pid_out_reg3; + ipark.ang = refs.theta_elec; + ipark.calc(&ipark); + + //получившиеся задания напряжения по осям альфа и бета отправляем на модуль ШИМ + pwm.UalphaRef = ipark.ds; + pwm.UbetaRef = ipark.qs; + pwm.update(&pwm); + + //в наблюдаемые переменные - текущий амплитудный ток в статоре (обратная связь регулятора d) + cur_par.Is = pid_id.pid_fdb_reg3; + + break; + } + + case CTRL_RUN_U2F: { //Режим скалярное управление U(f) + if (p->E == 1) { + /*ENTRY START*/ + pwm.On(&pwm); + rmp.output = 0; + + if (dlog.StartBits & (1 << 2)) //Если пользователь задал этот бит осциллографирования + dlog.set_mode(1, &dlog); //запускаем осциллограф по этому событию + + /*ENTRY END*/ + } + /*DO START*/ + //задание скорости на вход задатчика интенсивности + rmp.input = refs.speed_ref; + rmp.calc(&rmp);//расчет задатчика + cur_par.speed = rmp.output; //скорость (частоту вращения) показываем в налюдаемых параметрах, которая задана + + //угол refs.theta_elec - интеграл от скорости rmp.output. + //Константа FAST_CALC_TS - период дискретизации + //drv_params.freq_nom номинальная частота (базовый параметр частоты для относительных единиц измерения) + refs.theta_elec += _IQmpy(_IQmpyI32(drv_params.freq_nom,FAST_CALC_TS), + rmp.output); + refs.theta_elec &= 0x00FFFFFF; //отсечение лишней верхней части, если угол больше единицы в IQ (360 градусов) + //на вход кривой U/f подается текущая скорость (частота) + vhz.freq = rmp.output; + vhz.calc(&vhz); + + //в модуль координатных преоразований подаем заданную амплитуду напряжения vhz.vout с модуля U/f + //Используем фазные преобразования как "крутилку" вектора напряжения + ipark.de = vhz.vout; + ipark.qe = 0; + ipark.ang = refs.theta_elec; + ipark.calc(&ipark); + + //получившиеся задания напряжения по осям альфа и бета отправляем на модуль ШИМ + pwm.UalphaRef = ipark.ds; + pwm.UbetaRef = ipark.qs; + pwm.update(&pwm); + + /*DO END*/ + break; + } + + case CTRL_RUN_I2F: { //Режим частотно-токового управления - вращающийся вектор тока. + if (p->E == 1) { + /*ENTRY START*/ + pid_id.ui_reg3 = 0; //сбрасывем интегральные каналы + pid_iq.ui_reg3 = 0; //чтобы не накапливались + pid_spd.ui_reg3 = 0; + pid_id.pid_ref_reg3 = 0; + pid_iq.pid_ref_reg3 = 0; + + pwm.On(&pwm);//влючение ШИМ + rmp.output = 0; + if (dlog.StartBits & (1 << 3)) + dlog.set_mode(1, &dlog); + /*ENTRY END*/ + } + /*DO START*/ + { + + //два тока фаз из АЦП в модуль фазных преобразований + clarke.as = adc.Imeas_a; + clarke.bs = adc.Imeas_b; + clarke.calc(&clarke); + + //текущий вектор тока - в наблюдаемые параметры (чтобы на него смотреть) + cur_par.Ialpha = clarke.ds; + cur_par.Ibeta = clarke.qs; + + //задание скорости на вход задатчика интенсивности + rmp.input = refs.speed_ref; + rmp.calc(&rmp);//расчет задатчика + + //угол refs.theta_elec - интеграл от скорости rmp.output. + //Константа FAST_CALC_TS - период дискретизации + //drv_params.freq_nom номинальная частота (базовый параметр частоты для относительных единиц измерения) + refs.theta_elec += _IQmpy( + _IQmpyI32(drv_params.freq_nom,FAST_CALC_TS), rmp.output); + cur_par.ThetaRefCurr = refs.theta_elec; + refs.theta_elec &= 0x00FFFFFF;//отсечение лишней верхней части, если угол больше единицы в IQ (360 градусов) + + //текущий угол с датчика положения, переведенный в электрический из механического + //cur_par.ThetaCurr = posspeedEqep.theta_elecContinouos; + + //Текущий угол - заданный угол + cur_par.ThetaCurr = refs.theta_elec; + + //из фазных преобразований в координатные преобразования. + //Поворачиваем вектор на заданный угол refs.theta_elec + park.ds = clarke.ds; + park.qs = clarke.qs; + park.ang = refs.theta_elec; + park.calc(&park); + + //регулятор тока "как бы" оси d (на самом деле эта ось к двигателю к оси d не привязана, это свободная ось) + pid_id.pid_ref_reg3 = refs.i_flux_ref; + pid_id.pid_fdb_reg3 = park.de; + pid_id.calc(&pid_id); + + //регулятор тока "как бы" оси q (на самом деле эта ось к двигателю к оси q не привязана, это свободная ось) + pid_iq.pid_ref_reg3 = 0; + pid_iq.pid_fdb_reg3 = park.qe; + pid_iq.calc(&pid_iq); + + //обратные фазные преобразования. + //Крутим вектор напряжения, который выдают регуляторы токов обратно на угол refs.theta_elec + ipark.de = pid_id.pid_out_reg3; + ipark.qe = pid_iq.pid_out_reg3; + ipark.ang = refs.theta_elec; + ipark.calc(&ipark); + + //получившиеся задания напряжения по осям альфа и бета отправляем на модуль ШИМ + pwm.UalphaRef = ipark.ds; + pwm.UbetaRef = ipark.qs; + pwm.update(&pwm); + + //в наблюдаемые переменные - текущий амплитудный ток в статоре (обратная связь регулятора d) + cur_par.Is = pid_id.pid_fdb_reg3; + //и текущую частоту (скорость) + cur_par.speed = rmp.output; + + + /*DO END*/ + } + break; + } + + case CTRL_RUN_VECTOR_SM: { //Датчиковая СУ для синхронной машины + if (p->E == 1) { + /*ENTRY START*/ + pwm.On(&pwm); //Включение ШИМ + rmp.output = 0; //Обнуление задатчика интенсивности + if (dlog.StartBits & (1 << 4)) //Если пользователь задал этот бит осциллографирования + dlog.set_mode(1, &dlog); //Запуск осциллографа по этому событию + /*ENTRY END*/ + } + /*DO START*/ + { + if (drv_params.sens_type == POS_SENSOR_TYPE_HALL){ //В типе датчика выбран ДПР на элементах Холла + cur_par.speed = DPReCAP.speed; //Текущая скорость - с ДПР + refs.theta_elec = DPReCAP.Angle; //текущее угловое положение - с ДПР + } + if (drv_params.sens_type == POS_SENSOR_TYPE_ENCODER){ //В типе датчика выбран ДПР на элементах Холла + cur_par.speed = posspeedEqep.speed_elec; //Текущая скорость - с ДПР + refs.theta_elec = posspeedEqep.theta_elec; //текущее угловое положение - с ДПР + } + if (drv_params.sens_type == POS_SENSOR_TYPE_SSI){ //В типе датчика выбран ДПР цифровой с SSI интерфейсом + cur_par.speed = SSI_Encoder.speed_elec; //Текущая скорость - с ДПР + refs.theta_elec = SSI_Encoder.theta_elec; //текущее угловое положение - с ДПР + } + + cur_par.Is = pid_iq.pid_fdb_reg3; //Текущий ток статора - ток по оси q + + //Преобразование токов из трехфазной системы координат в двухфазную + clarke.as = adc.Imeas_a; + clarke.bs = adc.Imeas_b; + clarke.calc(&clarke); + cur_par.Ialpha = clarke.ds; + cur_par.Ibeta = clarke.qs; + + // задание скорости от задатчика интенсивности (ЗИ) + rmp.input = refs.speed_ref; + rmp.calc(&rmp);//Расчет ЗИ + + pid_spd.pid_ref_reg3 = rmp.output; //на воход регулятора скорости - выход ЗИ + pid_spd.pid_fdb_reg3 = cur_par.speed; //обратная связь регулятора скорости - скорость ДПР + + + pid_spd.pid_out_max = refs.Iq_ref; //Максимум выхода регулятора скорости - заданный ток + + if (sw.recuperation_ena & 1) //если разрешена рекуперация + pid_spd.pid_out_min = -refs.Iq_ref; //минимум рег. скор. - отрицательный ток + else + //иначе + pid_spd.pid_out_min = 0; //нулевой ток не даст рекупераци при вращении в положительную сторону + pid_spd.calc(&pid_spd); //расчет регулятора скорости + + + cur_par.ThetaRefCurr = refs.theta_elec; + refs.theta_elec &= 0x00FFFFFF; //Ограничение угла на 1.0 в формате 8.24 + + //Поворот токов фаз на угол refs.theta_elec + park.ds = clarke.ds; + park.qs = clarke.qs; + park.ang = refs.theta_elec; + park.calc(&park); //расчет преобразования координат + + //задание рег. тока по оси q (оси момента) - выход регулятора скорости + pid_iq.pid_ref_reg3 = pid_spd.pid_out_reg3; + pid_iq.pid_fdb_reg3 = park.qe; //обратная связь рег. тока оси q - вычисленный ток по фазе q + pid_iq.calc(&pid_iq); //расчет регулятора тока оси q + + pid_id.pid_ref_reg3 = 0; //задание тока по оси d - оси возбудения + pid_id.pid_fdb_reg3 = park.de; //обратная связь рег. тока оси d - вычисленный ток по фазе d + pid_id.calc(&pid_id); //расчет регулятора тока оси d + + //Обратный поворот на угол refs.theta_elec для + //выходов регуляторов тока (напряжений по осям d и q) + ipark.de = pid_id.pid_out_reg3; + ipark.qe = pid_iq.pid_out_reg3; + ipark.ang = refs.theta_elec; + ipark.calc(&ipark); //расчет преобразования координат + + //Задание напряжение на модуль ШИМ после преобразования координат + pwm.UalphaRef = ipark.ds; //Ось альфа + pwm.UbetaRef = ipark.qs; //Ось бета + pwm.update(&pwm); //Расчет модуля ШИМ + /*DO END*/ + } + break; + } + + case CTRL_RUN_VECTOR_SM_ENCODER_POS: { //Датчиковая СУ с энкодером и с контуром положения + if (p->E == 1) { + /*ENTRY START*/ + pwm.On(&pwm); //Включение ШИМ + rmp.output = 0; //Обнуление задатчика интенсивности + if (dlog.StartBits & (1 << 4)) //Если пользователь задал этот бит осциллографирования + dlog.set_mode(1, &dlog); //Запуск осциллографа по этому событию + /*ENTRY END*/ + } + /*DO START*/ + { + cur_par.Is = pid_iq.pid_fdb_reg3; //Текущий ток статора - ток по оси q + cur_par.speed = posspeedEqep.speed_elec; //Текущая скорость - с ДПР фильтрованная + + //Преобразование токов из трехфазной системы координат в двухфазную + clarke.as = adc.Imeas_a; + clarke.bs = adc.Imeas_b; + clarke.calc(&clarke); + cur_par.Ialpha = clarke.ds; + cur_par.Ibeta = clarke.qs; + + +/* //Для демо-режима контура положения сделаем задание положения, изменяющегося по синусу + //Как быстро менять задание - пусть управляется из переменной для отладки DebugW1 + + if (DebugW1!=0){//если какая-то скорость вращения задана + p->AngleDemo+=(DebugW1>>10);//инкрементируем переменную + if (p->AngleDemo>_IQ(2))//период равен 2, что в о.е. дает 360*2 градусов + p->AngleDemo=0; + + //задание угла в контур положения + //пусть будет синус от линейно увеличивающейся переменной, да еще и в 4 раза увеличим + refs.theta_elec=_IQsinPU(p->AngleDemo)<<2; + } +*/ + + /* +//Другой демо-режим контура положения - задавать положение от двигателя датчика, абсолютного энкодера с интерфейсом SSI +//Для работы датчика его нужно, собственно, подключить (в комплект поставки не входит!), +//а также выбрать его в настройках + +#define REVOLUTION_DROP_NUMBER 3 + //чтобы можно было вращать неограниченно в одну сторону и не переполнилась переменная по положению + //но чтобы нельзя было накрутить 100500 оборотов вперед привода и он крутил бы дальше и дальше + //ограничим максимальное расхождение в обототах числом REVOLUTION_DROP_NUMBER + if (labs(SSI_Encoder.RevolutionCounter-posspeedEqep.RevolutionCounter)>REVOLUTION_DROP_NUMBER){ + if (posspeedEqep.RevolutionCounter>SSI_Encoder.RevolutionCounter){ + posspeedEqep.RevolutionCounter=SSI_Encoder.RevolutionCounter+REVOLUTION_DROP_NUMBER; + } + if (SSI_Encoder.RevolutionCounter>posspeedEqep.RevolutionCounter){ + SSI_Encoder.RevolutionCounter=posspeedEqep.RevolutionCounter+REVOLUTION_DROP_NUMBER; + } + } + if ((posspeedEqep.RevolutionCounter>10) || (SSI_Encoder.RevolutionCounter>10)){ + posspeedEqep.RevolutionCounter-=10; + SSI_Encoder.RevolutionCounter-=10; + } + if ((posspeedEqep.RevolutionCounter<-10) || (SSI_Encoder.RevolutionCounter<-10)){ + posspeedEqep.RevolutionCounter+=10; + SSI_Encoder.RevolutionCounter+=10; + } + + //задание угла - от SSI энкодера + refs.theta_elec=SSI_Encoder.theta_elecContinouos; +*/ + + + //текущий угол с датчика положения, переведенный в электрический из механического + cur_par.ThetaCurr = posspeedEqep.theta_elecContinouos; + cur_par.ThetaRefCurr=refs.theta_elec;//заданный угол электрический (продублируем в эту переменную задание для удобства наблюдения) + + //ошибка - разница между заданием и текущим углом. Эта разница обычно считается внутри ПИД регулятора, + //однако в данном случае нужно после расчета произвести ограничение, чтобы в регуляторе ничего не переполнилось + long posRefError=refs.theta_elec - cur_par.ThetaCurr; + + + //ограничим ошибку - чтобы при расчете регулятора внутри него не было переполнения. + if (posRefError>_IQ(1)) + posRefError=_IQ(1); + if (posRefError<-_IQ(1)) + posRefError=-_IQ(1); + + + //обычно на ПИД регулятор подается задание и обратная связь, а внутри считается их разница. + //но разницу мы посчитали выше (и ограничили). Потому пусть задание на регулятор будет всё время нулевым, + //а в обратную связь подадим уже посчитанную и ограниченную ошибку (со знаком минус) + pid_pos.pid_ref_reg3 = 0;//задавать задание на положение надо через refs.theta_elec (группа задания) + pid_pos.pid_fdb_reg3 = -posRefError;//обратная связь + pid_pos.pid_out_max=refs.speed_ref;//ограничение рег. положения - максимум задаваемой скорости + pid_pos.pid_out_min=-refs.speed_ref;//и в минус + pid_pos.saterr_reg3Add=pid_spd.saterr_reg3;//это улучшайзер. Учитывает насыщение рег. скорости и передает его в рег. положения. + pid_pos.calc(&pid_pos); //расчет регулятора положения + + pid_spd.pid_ref_reg3 = pid_pos.pid_out_reg3; //на вход регулятора скорости - выход рег. положения + pid_spd.pid_fdb_reg3 = posspeedEqep.speed_filter.output; //обратная связь регулятора скорости - скорость ДПР + + pid_spd.pid_out_max = refs.Iq_ref; //Максимум выхода регулятора скорости - заданный ток + pid_spd.pid_out_min = -refs.Iq_ref; //минимум рег. скор. - отрицательный ток + pid_spd.calc(&pid_spd); //расчет регулятора скорости + + + //Поворот токов фаз на угол refs.theta_elec + park.ds = clarke.ds; + park.qs = clarke.qs; + park.ang = posspeedEqep.theta_elec; + park.calc(&park); //расчет преобразования координат + + //задание рег. тока по оси q (оси момента) - выход регулятора скорости + pid_iq.pid_ref_reg3 = pid_spd.pid_out_reg3; + pid_iq.pid_fdb_reg3 = park.qe; //обратная связь рег. тока оси q - вычисленный ток по фазе q + pid_iq.calc(&pid_iq); //расчет регулятора тока оси q + + pid_id.pid_ref_reg3 = 0; //задание тока по оси d - оси возбудения + pid_id.pid_fdb_reg3 = park.de; //обратная связь рег. тока оси d - вычисленный ток по фазе d + pid_id.calc(&pid_id); //расчет регулятора тока оси d + + //Обратный поворот на угол refs.theta_elec для + //выходов регуляторов тока (напряжений по осям d и q) + ipark.de = pid_id.pid_out_reg3; + ipark.qe = pid_iq.pid_out_reg3; + ipark.ang = posspeedEqep.theta_elec; + ipark.calc(&ipark); //расчет преобразования координат + + //Задание напряжение на модуль ШИМ после преобразования координат + pwm.UalphaRef = ipark.ds; //Ось альфа + pwm.UbetaRef = ipark.qs; //Ось бета + pwm.update(&pwm); //Расчет модуля ШИМ + + /*DO END*/ + } + break; + } + + + case CTRL_RUN_VECTOR_IM_ENCODER: { //Датчиковая СУ с энкодером + if (p->E == 1) { + /*ENTRY START*/ + pwm.On(&pwm); //Включение ШИМ + RotorObserver.psi_d=0; + RotorObserver.psi_q=0; + rmp.output = 0; //Обнуление задатчика интенсивности + if (dlog.StartBits & (1 << 4)) //Если пользователь задал этот бит осциллографирования + dlog.set_mode(1, &dlog); //Запуск осциллографа по этому событию + /*ENTRY END*/ + } + /*DO START*/ + { + cur_par.Is = _IQmag(pid_iq.pid_fdb_reg3,pid_id.pid_fdb_reg3) ; //Текущий ток статора - амплитуда из токов d и q + cur_par.speed = posspeedEqep.speed_elec; //posspeedEqep.speed.output;//Текущая скорость - с ДПР фильтрованная + + //Преобразование токов из трехфазной системы координат в двухфазную + clarke.as = adc.Imeas_a; + clarke.bs = adc.Imeas_b; + clarke.calc(&clarke); + cur_par.Ialpha = clarke.ds; + cur_par.Ibeta = clarke.qs; + + // задание скорости от задатчика интенсивности (ЗИ) + rmp.input = refs.speed_ref; + rmp.calc(&rmp);//Расчет ЗИ + + pid_spd.pid_ref_reg3 = rmp.output; //на воход регулятора скорости - выход ЗИ + pid_spd.pid_fdb_reg3 = posspeedEqep.speed_elec; //обратная связь регулятора скорости - скорость ДПР + + + pid_spd.pid_out_max = refs.Iq_ref; //Максимум выхода регулятора скорости - заданный ток + + if (sw.recuperation_ena & 1) //если разрешена рекуперация + pid_spd.pid_out_min = -refs.Iq_ref; //минимум рег. скор. - отрицательный ток + else + //иначе + pid_spd.pid_out_min = 0; //нулевой ток не даст рекупераци при вращении в положительную сторону + pid_spd.calc(&pid_spd); //расчет регулятора скорости + + + //Поворот токов фаз на угол refs.theta_elec + park.ds = clarke.ds; + park.qs = clarke.qs; + park.ang = posspeedEqep.theta_elec; + park.calc(&park); //расчет преобразования координат + + RotorObserver.id=park.de;//на наблюдатель ротора АД - токи статора, повернутый на угол ДПРа + RotorObserver.iq=park.qe; + RotorObserver.calc(&RotorObserver); + + refs.theta_elec = RotorObserver.theta_psi_elec+posspeedEqep.theta_elec; //текущее угловое положение - с ДПР и наблюдателя ротора (оси x,y) + refs.theta_elec &= 0x00FFFFFF; //Ограничение угла на 1.0 в формате 8.24 + cur_par.ThetaRefCurr = refs.theta_elec; + + + //Теперь refs.theta_elec - угол потокосцепления ротора. Повторяем векторную систему от синхронной машины для этого угла + park.ds = clarke.ds; + park.qs = clarke.qs; + //второе слагаемое - доворот для устойчивости регуляторов на высокой скорости. Дублироваться второй раз для ipark не должен! + park.ang = refs.theta_elec; + park.calc(&park); + + //регуляторы токов d, q используются для регулирования осей x, y (чтобы не делать разных названий) + //задание рег. тока по оси y (оси момента) - выход регулятора скорости + pid_iq.pid_ref_reg3 = pid_spd.pid_out_reg3; + pid_iq.pid_fdb_reg3 = park.qe; //обратная связь рег. тока оси y - вычисленный ток по фазе y + pid_iq.calc(&pid_iq); //расчет регулятора тока оси y + + pid_id.pid_ref_reg3 = _IQmpy(RotorObserver.FluxCurrentRatio,labs(pid_iq.pid_ref_reg3)); //задание тока по оси x - оси возбудения. Пропорционально амплитуде задания тока статора + if (pid_id.pid_ref_reg3 < RotorObserver.FluxCurrentMin) + pid_id.pid_ref_reg3=RotorObserver.FluxCurrentMin; + pid_id.pid_fdb_reg3 = park.de; //обратная связь рег. тока оси x - вычисленный ток по фазе x + pid_id.calc(&pid_id); //расчет регулятора тока оси x + + + //Обратный поворот на угол refs.theta_elec для + //выходов регуляторов тока (напряжений по осям x и y) + ipark.de = pid_id.pid_out_reg3; + ipark.qe = pid_iq.pid_out_reg3; + ipark.ang = refs.theta_elec; + ipark.calc(&ipark); //расчет преобразования координат + + //Задание напряжение на модуль ШИМ после преобразования координат + pwm.UalphaRef = ipark.ds; //Ось альфа + pwm.UbetaRef = ipark.qs; //Ось бета + pwm.update(&pwm); //Расчет модуля ШИМ + + /*DO END*/ + } + break; + } + + + case CTRL_AUTO_SENSOR_TUNING: { //Авто настройка ДПР + if (p->E == 1) { + /*ENTRY START*/ + pwm.On(&pwm); + rmp.output = 0; + DPReCAP.AngleOffset = 0; + if (dlog.StartBits & (1 << 3)) + dlog.set_mode(1, &dlog); + /*ENTRY END*/ + } + /*DO START*/ + { + //по структуре это тоже самое, что частотно-токовая система управления + cur_par.Is = pid_id.pid_fdb_reg3; + cur_par.speed = rmp.output; + + clarke.as = adc.Imeas_a; + clarke.bs = adc.Imeas_b; + clarke.calc(&clarke); + cur_par.Ialpha = clarke.ds; + cur_par.Ibeta = clarke.qs; + + rmp.input = refs.speed_ref; + rmp.calc(&rmp); + refs.theta_elec += _IQmpy( + _IQmpyI32(drv_params.freq_nom,FAST_CALC_TS), rmp.output); + cur_par.ThetaRefCurr = refs.theta_elec; + refs.theta_elec &= 0x00FFFFFF; + + park.ds = clarke.ds; + park.qs = clarke.qs; + park.ang = refs.theta_elec; + park.calc(&park); + + pid_iq.pid_ref_reg3 = 0; + pid_iq.pid_fdb_reg3 = park.qe; + pid_iq.calc(&pid_iq); + + pid_id.pid_ref_reg3 = refs.i_flux_ref; + pid_id.pid_fdb_reg3 = park.de; + pid_id.calc(&pid_id); + + ipark.de = pid_id.pid_out_reg3; + ipark.qe = pid_iq.pid_out_reg3; + ipark.ang = refs.theta_elec; + ipark.calc(&ipark); + + pwm.UalphaRef = ipark.ds; + pwm.UbetaRef = ipark.qs; + + pwm.update(&pwm); + + //автоматическая настрока смещения для датчика Холла + if (p->AnglePrev != DPReCAP.Angle6) { + if (((DPReCAP.Angle6 == _IQ(5.0 / 6.0)) && (p->AnglePrev == 0)) + || ((p->AnglePrev == _IQ(5.0 / 6.0)) + && (DPReCAP.Angle6 == 0))) { + DPReCAP.AngleOffset = + DPReCAP.AngleOffset + + _IQmpy(_IQ(0.5), + ((refs.theta_elec-DPReCAP.AngleOffset+_IQ(0.5))&0x00FFFFFF)-_IQ(0.5)); + DPReCAP.AngleOffset &= 0x00FFFFFF; + } + p->AnglePrev = DPReCAP.Angle6; + } + + //автоматическая настрока смещения для энкодера + posspeedEqep.AngleOffset = + posspeedEqep.AngleOffset + + _IQmpy(_IQ(0.0001), + ((refs.theta_elec-posspeedEqep.theta_elec+_IQ(0.5))&0x00FFFFFF)-_IQ(0.5)); + posspeedEqep.AngleOffset &= 0x00FFFFFF; + /*DO END*/ + } + break; + } + + case CTRL_RUN_LATENCY_TEST: { //Режим постоянный ток + if (p->E == 1) { + /*ENTRY START*/ + pwm.On(&pwm); + p->ctrl_counter = 0; + + if (dlog.StartBits & (1 << 1)) + dlog.set_mode(1, &dlog); + /*ENTRY END*/ + } + /*DO START*/ + p->ctrl_counter++; + pwm.UalphaRef = 0; + pwm.UbetaRef = 0; + DebugW1++; + if (p->ctrl_counter > 100){ + if (labs(adc.Imeas_a)< refs.i_flux_ref){ + pwm.UalphaRef = _IQ(1); + pwm.UbetaRef = 0; + } else { + p->ctrl_counter = 0; + } + } + + pwm.update(&pwm); + break; + } + + + default: { + break; + } + } + +} + +/*@}*/ + diff --git a/Vsrc/SM_Net.c b/Vsrc/SM_Net.c new file mode 100644 index 0000000..c696357 --- /dev/null +++ b/Vsrc/SM_Net.c @@ -0,0 +1,157 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file SMNet.c + \brief Модуль общего назначения для работы с сетью. (см. TSM_Net) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + */ + +/** \addtogroup SMNet */ +/*@{*/ + +#include "DSP.h" +#include "V_IQmath.h" +#include "main.h" + +//!Инициализация. + +//!Присвоение масштабирующих коэффициентов, инициализация других модулей. +//! \memberof TSM_Net +void SM_Net_Init(TSM_Net *p) { + + p->state = 0; + p->state_prev = 0xff; + + //Настройка драйвера CANOpen + co1_vars.settings.LoadParamsFromUserMemory_ena = 1;//Разрешить загружать значения параметров из ЭНОЗУ + co1_vars.CAN_REGS = (CAN_TypeDef *)CAN_BASE;//Передаем драйверу адрес структуры регистров CAN + co1_vars.settings.CAN_ISR_priority = IRQ_PRIORITY_CAN;//Присвоение приоритета перывания CAN (обработчик внутри библиотеки) + co1_vars.settings.CAN_IRQn = CAN1_IRQn;//Передаем номер прерывания CAN1 из таблицы прерываний в драйвер CANOpen + co1_vars.settings.MultiPDO_ena = 0;//Отключение обработки PDO без учета номера узла (спец. функция) + co1_vars.settings.RX_PDO_Callback_ena = 0; //Не вызывать функции обратного вызова при приеме PDO + co1_vars.settings.AutoBusON_ena = 1; //Автоматически перезапускать CAN при ошибках на линии + co1_vars.settings.BlockTransfer_ena = 1;//Разрешить блочную передачу (нужна для осциллографа) + co1_vars.settings.speedCANTablePointer = &canSpeedTable;//Передаем драйверу параметры для настройки скорости CAN + co1_vars.settings.resetCPU = Watchdog.resetCPU;//Передаем драйверу адрес функции ресета микроконтроллера + co1_Init(&co1_vars); //Инициализация драйвера CANOpen + + //логгер событий: + // размер буфера: 50 + // стартовый адрес в SPI: 3000 + FaultLog.init(&FaultLog, 50, 3000, (Uint32*)&RTCclock.packed_time);//ниже указатель на время может быть переопределен в зависимости от работы часов + + +////Работа с CANopen через UART (параллельно с CAN, нет конфликта) + CANtoRS.nodeID = (Uint16*)&co1_vars.co_nodeID; //Номер узла из CANopen + CANtoRS.callback = Z_co_receiveSDOrequest;//Указатель на функцию обратного вызова из драйвера CANopen по приходу SDO сообщения + CANtoRS.init(&CANtoRS); +} + +//!Медленный расчет. + +//! Присвоение масштабирующих коэффициентов, фоновый расчет некоторых модулей. + +//! \memberof TSM_Net +void SM_Net_Slow_Calc(TSM_Net *p) { + + co1_vars.co_scaleNum0 = 1; //без масштабирования + co1_vars.co_scaleNum1 = 100; // % + co1_vars.co_scaleNum2 = drv_params.freq_nom; //Гц + co1_vars.co_scaleNum3 = drv_params.U_nom;//напряжение фазное номинальное амплитудное + co1_vars.co_scaleNum4 = drv_params.I_nom; //Ток фазный базовый + co1_vars.co_scaleNum5 = 1; + co1_vars.co_scaleNum6 = 1; + co1_vars.co_scaleNum7 = drv_params.Udc_nom; //напряжение ЗПТ базовое + co1_vars.co_scaleNum8 = drv_params.power; //18 в формате 9.6 //Мощность + co1_vars.co_scaleNum9 = 1; + co1_vars.co_scaleNumA = 20; //температура + co1_vars.co_scaleNumB = 1; + co1_vars.co_scaleNumC = 1; + co1_vars.co_scaleNumD = 1; + co1_vars.co_scaleNumE = 1; + co1_vars.co_scaleNumF = 1; + co1_vars.co_scaleNum10 = 1; // + co1_vars.co_scaleNum11 = 1; // + co1_vars.co_scaleNum12 = drv_params.power; //18 в формате 10.6 //Мощность + co1_vars.co_scaleNum13 = 360; // + co1_vars.co_scaleNum14 = drv_params.speed_nom; //номинальная частота вращения + co1_vars.co_scaleNum15 = 1; // + co1_vars.co_scaleNum16 = 1; // + co1_vars.co_scaleNum17 = ((((long) drv_params.Udc_nom) << 6) + / (long) drv_params.I_nom); //Rбаз 10.6 + co1_vars.co_scaleNum18 = 1000; + co1_vars.co_scaleNum19 = 1; + co1_vars.co_scaleNum1A = 1; + co1_vars.co_scaleNum1B = 1; + co1_vars.co_scaleNum1C = 1; + co1_vars.co_scaleNum1D = 1; + co1_vars.co_scaleNum1E = 1; + co1_vars.co_scaleNum1F = 1; + + drv_params.U_nom = 0.5759 * drv_params.Udc_nom;//номинальное фазное напряжение + drv_params.power = ((long) 300) << 6; //приведем к формату 10.6 + drv_params.freq_nom = ((float) drv_params.speed_nom * drv_params.p) / 60 + 0.5; //номин частота + + co_background_calc(&co1_vars); //Расчет драйвера CANOpen фоновый + drv_interface.calc(&drv_interface); + FaultLog.background_calc(&FaultLog); +#ifdef MODBUS_ENA + MBVarsConv.slow_calc(&MBVarsConv); +#endif + + if (RTCclock.ClockOk)//часы работают? + FaultLog.time_ptr = (Uint32*)&RTCclock.packed_time;//время для банка аварий из часов + else + FaultLog.time_ptr = (Uint32*)&global_time.PowerOn_time;//если не работают, то из модуля подсчета времени наработки +} + +//!Быстрый расчет + +//!Быстрый расчет некоторых сетевых модулей, вызов методов "пролистывания" кодов аварий и предупреждений +//! \memberof TSM_Net +void SM_Net_ms_Calc(TSM_Net *p) { + //Перевод битового состояния системы управления в константу. + //По drv_status_code отображается статус привода в UniCON + if (drv_status.bit.ready == 1) + drv_status_code = DRV_STATUS_READY; + if (drv_status.bit.running == 1) + drv_status_code = DRV_STATUS_RUNNING; + if (drv_status.bit.testing == 1) + drv_status_code = DRV_STATUS_TESTING; + if (drv_status.bit.fault == 1) + drv_status_code = DRV_STATUS_FAULT; + if (drv_status.bit.alarm == 1) + drv_status_code |= DRV_STATUS_ALARM; + else + drv_status_code &= ~DRV_STATUS_ALARM; + //функция листания аварий для пульта (UniCON) + pult_faults_lister.calc(&pult_faults_lister); + sm_prot.Main_ErrorCode = 0xFF & pult_faults_lister.output; + + co_1ms_calc(&co1_vars); //Расчет драйвера CANOpen + CANtoRS.calc(&CANtoRS); + +} + +void SM_Net_fast_Calc(TSM_Net *p) { + +#ifdef MODBUS_ENA + ModBus.Execute(&ModBus); +#endif +} + +/*@}*/ diff --git a/Vsrc/SM_Protect.c b/Vsrc/SM_Protect.c new file mode 100644 index 0000000..b0ecd43 --- /dev/null +++ b/Vsrc/SM_Protect.c @@ -0,0 +1,205 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file SMProtect.c + \brief Модуль защит. (см. TSM_Protect) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup SMProtect + @{ */ + +#include "DSP.h" +#include "main.h" +#include "stdlib.h" + +int16 WriteCounter = 0; + +//!Инициализация + +//!Присваивание всяких переменных +//! \memberof TSM_Protect +void SM_Protect_Init(TSM_Protect *p) { + p->state_prev = 0xff; + p->state = 0x00; + GPIOA->DENSET = (1 << 7);//для приема ножки апп. аварии разрешаем работу ножки как цифры +} + +//! Быстрый расчет. + +//!Обрабатывает все аварии и при их возникновении останавливает привод. +//! \memberof TSM_Protect +void SM_Protect_Fast_Calc(TSM_Protect *p) { + + //аппаратная авария от инвертора + if (pwm.PDP_Fault) { + if ((sm_ctrl.state != CTRL_STOP) && (sm_ctrl.state != CTRL_RUN)) + sm_prot.bit_fault1 |= F_PDPINT; + } + + if (!DRV_FAULT) { + //имеется какая-то аппаратная авария + sm_prot.bit_fault1 |= F_PDPINT; + } + + /*Защита по максимальному току*/ + if (adc.Imeas_a > sm_prot.Imax_protect) sm_prot.bit_fault2 |= F_CTRL_MAX_I_PH_A; + if (adc.Imeas_a < -sm_prot.Imax_protect) sm_prot.bit_fault2 |= F_CTRL_MAX_I_PH_A; + if (adc.Imeas_b > sm_prot.Imax_protect) sm_prot.bit_fault2 |= F_CTRL_MAX_I_PH_B; + if (adc.Imeas_b < -sm_prot.Imax_protect) sm_prot.bit_fault2 |= F_CTRL_MAX_I_PH_B; + if (adc.Imeas_c > sm_prot.Imax_protect) sm_prot.bit_fault2 |= F_CTRL_MAX_I_PH_C; + if (adc.Imeas_c < -sm_prot.Imax_protect) sm_prot.bit_fault2 |= F_CTRL_MAX_I_PH_C; + + //при превышении скорости выше аварийной нормы + if (labs(cur_par.speed) > sm_prot.speed_max) { + sm_prot.bit_fault2 |= F_CTRL_SPEED_MAX; // максиммальное Ud + } + + //при превышении напряжения выше аварийной нормы + if (adc.Udc_meas > sm_prot.Umax_protect) { + sm_prot.bit_fault1 |= F_CTRL_HI_UDC; // максиммальное Ud + } + + //снижение напряжения + if (adc.Udc_meas < sm_prot.Umin_protect) { //если привод работал то ловим аварию + if (sm_ctrl.state != CTRL_STOP) { + sm_prot.bit_fault1 |= F_CTRL_LOW_UDC; + } + } + + DINT; //Запрещение прерываний + //Аварии, требующие полного останова + p->masked_bit_fault1 = p->bit_fault1 & p->mask_fault1;//маскирование флагов аварий + p->masked_bit_fault2 = p->bit_fault2 & p->mask_fault2; + EINT; //Разрешение прерываний + + + //считаем дискретный автомат защит + if (p->state_prev != p->state) //смена состояния? + p->E = 1;//Возводим флаг первого вхождения "entry" + else + p->E = 0;//иначе сбрасываем + p->state_prev = p->state; + + switch (p->state) {//в зависимости от текущего состояния + case PROT_OFF: { //Защита выключена + if (p->E == 1) { //Первое вхождение + } + + //Обнуляем все аварии + p->bit_fault1 = 0; + p->bit_fault2 = 0; + + //Пропускаем некоторый таймаут после включения контроллера + //чтобы не ловить ложные срабатывания аварий АЦП + if (p->powered_okCounter++ > 5000) { + p->state = PROT_ON_OK; + } + break; + } + + case PROT_ON_OK: { //Норма + if (p->E == 1) { //Первое вхождение + drv_status.bit.fault = 0; + } + //есть аварии? + if ((p->masked_bit_fault1 | p->masked_bit_fault2) != 0) { + p->state = PROT_FAIL; //переходим в состояние аварии + } + break; + } + + case PROT_FAIL: { //состояние аварии (сработала защита) + if (p->E == 1) { + cmd.all = 0; + } + drv_status.bit.fault = 1; + //Выключение ШИМ. Пока там все остальные дискретные автоматы пробурлятся, чтобы их не ждать + pwm.Off(&pwm); + //логика сбороса аварии + if (cmd.bit.trip_reset == 1) {//команда на сброс аварии + p->state = PROT_ON_OK;//идем в "норма" + p->clearDrvFault = 1; //отправить драйверу ключей команду сброса + //обнуляем все флаги аварий + p->bit_fault1 = 0; + p->bit_fault2 = 0; + cmd.all = 0;//командное слово + //в самом низу!!! пытаемся сбросить флаг pdp аппаратный + //если авария все еще имеется, то сразу произойдет прерывание + //и возведется флаг аварии + if (PWM0->TZFLG_bit.OST == 1) { //имеется флаг аппаратной аварии + //флаг можно сбрасывать + PWM0->TZCLR = 0x7; + PWM1->TZCLR = 0x7; + PWM2->TZCLR = 0x7; + } + } + break; + } + } +} + +//! \memberof TSM_Protect +void SM_Protect_ms_Calc(TSM_Protect *p) { + if (WriteCounter <= 15) //если первое слово + { + if (((sm_prot.masked_bit_fault1 >> WriteCounter) & 0x1) != 0) //стоит ii-й флаг аварии + { + if (((sm_prot.bit_fault_written1 >> WriteCounter) & 0x1) == 0) //и она не записана + { + FaultLog.write(&FaultLog, WriteCounter + 1); + sm_prot.bit_fault_written1 |= (1 << WriteCounter); + } + } + else + sm_prot.bit_fault_written1 &= ~(1 << WriteCounter); + } + else if (WriteCounter <= 31) //второе слово + { + if (((sm_prot.masked_bit_fault2 >> (WriteCounter - 16)) & 0x1) != 0) //стоит ii-й флаг аварии + { + if (((sm_prot.bit_fault_written2 >> (WriteCounter - 16)) & 0x1) == 0) //и она только что поЯвилась + { + FaultLog.write(&FaultLog, WriteCounter + 1); + sm_prot.bit_fault_written2 |= (1 << (WriteCounter - 16)); + } + } + else + sm_prot.bit_fault_written2 &= ~(1 << (WriteCounter - 16)); + } + WriteCounter++; + if (WriteCounter >= (33 - 1)) + WriteCounter = 0; +} + +//! Медленный расчет. + +//! \memberof TSM_Protect +void SM_Protect_Slow_Calc(TSM_Protect *p) { + /* Проверка аппаратных защит драйвера. Он автоматически вырубает ключи при авариях, + * и опускает сигналы /FAULT и /OCTW, но чтобы понять, что именно случилось, надо по SPI прочитать статусы. + * Поэтому, видимо, можно в фоне. + */ + if (p->readDrvSts == 1) { + p->readDrvSts = 0; + } + + /* Чтобы сбросить аварию, надо прописать ему битик GATE_RESET */ + if (p->clearDrvFault == 1) { + p->clearDrvFault = 0; + } +} + +/*@}*/ diff --git a/Vsrc/SM_Sys.c b/Vsrc/SM_Sys.c new file mode 100644 index 0000000..3bfde86 --- /dev/null +++ b/Vsrc/SM_Sys.c @@ -0,0 +1,278 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file SMSys.c + \brief Модуль-обертка для расчета остальных модулей. (см. TSM_Sys) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + */ + +/** \addtogroup SMSys */ +/*@{*/ +#include "main.h" + +/* Объявление адреса размещения таблицы векторов прерываний */ +#if defined ( __CMCPPARM__ ) + extern const Uint32 __Vectors; +#elif defined (__GNUC__) + +#endif + +//! Инициализация системы управления после включения + +//!Инициализация некоторых модулей и настройка прерываний системы. +//!Здесь настраивается большинство прерываний +//! \memberof TSM_Sys +void SM_Sys_Init(TSM_Sys *p) { +#if defined (HW_VECTORCARD_DRV8301_EVM) + sw.HardwareType = 0; +#elif defined (HW_VECTORCARD_DRV8312_EVM) + sw.HardwareType = 1; +#elif defined (HW_VECTORCARD_SIMULATOR) + sw.HardwareType = 2; +#endif + cmd.all = 0; + drv_status.all = 0; + + sm_net.init(&sm_net); //Сетевая часть + adc.init(&adc); //Инициализация АЦП + sm_prot.init(&sm_prot); //Защиты + sm_cmd_logic.init(&sm_cmd_logic); //Логика включения/выключения + sm_ctrl.init(&sm_ctrl); //Структура системы управления + pwm.init(&pwm); //Модуль ШИМ + cur_par.init(&cur_par); //Расчет текущих показателей привода + leds.init(&leds);//светодиоды + + //глобальное времЯ (внешние или внутр. часы) + global_time.init(&global_time); + + if (drv_params.sens_type == POS_SENSOR_TYPE_HALL){ //В типе датчика выбран ДПР на элементах Холла +// DPReCAP.Init(&DPReCAP); //ДПР иниц. + } + if (drv_params.sens_type == POS_SENSOR_TYPE_ENCODER){ //В типе датчика выбран энкодер + //настроим квадратурный декодер + posspeedEqep.speed_nom = drv_params.speed_nom; //базовая скорость + posspeedEqep.pole_pairs = drv_params.p; //кол-во пар полюсов дригателя + posspeedEqep.Posspeed_CTL.bit.dir = 1; //направление движения + posspeedEqep.RevolutionCounter=0; + posspeedEqep.init(&posspeedEqep);//инициализация модуля энкодера + } + if (drv_params.sens_type == POS_SENSOR_TYPE_SSI){ //В типе датчика выбран датчик с SSI интерфейсом. Читайте заголовочник модуля перед использованием! + //настроим модуль датчика положения SSI + SSI_Encoder.speed_nom = drv_params.speed_nom; //базовая скорость + SSI_Encoder.pole_pairs = drv_params.p; //кол-во пар полюсов дригателя + SSI_Encoder.rotation_dir = 0; //направление движения + SSI_Encoder.RevolutionCounter=0; + SSI_Encoder.init(&SSI_Encoder);//Датчик положения SSI + } + if (drv_params.sens_type == POS_SENSOR_TYPE_ENC_HALL){ + //настроим квадратурный декодер +// DPReCAP.Init(&DPReCAP); //ДПР иниц. + posspeedEqep.speed_nom = drv_params.speed_nom; //базовая скорость + posspeedEqep.pole_pairs = drv_params.p; //кол-во пар полюсов дригателя + posspeedEqep.Posspeed_CTL.bit.dir = 1; //направление движения + posspeedEqep.RevolutionCounter=0; + posspeedEqep.init(&posspeedEqep);//инициализация модуля энкодера + } + + //листалка аварий для отображения на пульте управления (UniCON) + pult_faults_lister.num_of_words = 2; + pult_faults_lister.out_refresh_devisor = 1000; //при вызове в мс таймере период обновления будет равен 1сек + pult_faults_lister.w_ptrs[0] = (Uint16*) &sm_prot.masked_bit_fault1;//перебираются эти флаги аварий модуля защит + pult_faults_lister.w_ptrs[1] = (Uint16*) &sm_prot.masked_bit_fault2; + + AutoOffset.FilterK = _IQ(0.00001);//постоянная времени фильтра для автосмещения АЦП + AutoOffset.init(&AutoOffset); //авто смещение некоторых каналов АЦП (токи) + +#if defined(HW_VECTORCARD_SIMULATOR) || defined(HW_NIIET_BOARD_SIMULATOR) + //model.motorInternals.udc = 540; //задается через словарь объектов + model.tpr = _IQ10div(_IQ10(SystemCoreClock/1000.0), pwm.Frequency << 1) >> 10; //период частоты ШИМ + model.dt = _IQ4mpy(_IQ4(150 / 4), pwm.DeadBand >> 20) >> 4; //величина мертвого времени + model.Init(&model); //Модель двигателя +#endif + + // Настройка таймера 0 на 10 кГц + TMR0->INTSTATUS_bit.INT = 1; + TMR0->LOAD_bit.VAL = 10000 - 1; //9999 надо чтобы не плыло отностильно прерывания ШИМа, когда у того частота 10кГц + TMR0->CTRL = ((1 << 0) | (1 << 3)); // Запуск и разрешение прерываний + + // Настройка таймера 1 на 1 кГц + TMR1->INTSTATUS_bit.INT = 1; + TMR1->LOAD_bit.VAL = 100000 - 1; + TMR1->CTRL = ((1 << 0) | (1 << 3)); // Запуск и разрешение прерываний + + //Для подсчета тактов + TMR2->LOAD_bit.VAL = 0xFFFFFFFF; + TMR2->CTRL = (1 << 0); // Запуск + + extern int *g_pfnVectors; //там, где-то в стартап файле есть такой символ + //Надо показать в этом регистре, где лежит таблица прерываний. + //А лежит она там, куда записал её линкер, в зависимости от файла компоновки. + //Поэтому берем адрес от массива g_pfnVectors и кладем туда +#if defined (__CMCPPARM__) + SCB->VTOR = (uint32_t) (&__Vectors); +#elif defined (__GNUC__) + extern int *g_pfnVectors; + SCB->VTOR = (uint32_t) (&g_pfnVectors); +#endif + NVIC_SetPriorityGrouping(3); // 4 bit preemption, 0 bit of subprio + + NVIC_DisableIRQ(TMR0_IRQn); + NVIC_DisableIRQ(TMR1_IRQn); + NVIC_DisableIRQ(ECAP0_IRQn); + NVIC_DisableIRQ(ECAP1_IRQn); + NVIC_DisableIRQ(ECAP2_IRQn); + NVIC_DisableIRQ(PWM0_TZ_IRQn); + NVIC_DisableIRQ(QEP_IRQn); + + NVIC_ClearPendingIRQ(TMR0_IRQn); + NVIC_ClearPendingIRQ(TMR1_IRQn); + NVIC_ClearPendingIRQ(ECAP0_IRQn); + NVIC_ClearPendingIRQ(ECAP1_IRQn); + NVIC_ClearPendingIRQ(ECAP2_IRQn); + NVIC_ClearPendingIRQ(PWM0_TZ_IRQn); + NVIC_ClearPendingIRQ(QEP_IRQn); + + /* Прерывание 10 кГц */ + NVIC_EnableIRQ(TMR0_IRQn); + NVIC_SetPriority(TMR0_IRQn, IRQ_PRIORITY_10K); + + /* Прерывание 1 кГц */ + NVIC_EnableIRQ(TMR1_IRQn); + NVIC_SetPriority(TMR1_IRQn, IRQ_PRIORITY_1K); + + NVIC_EnableIRQ(ECAP0_IRQn); //CAP0 + NVIC_SetPriority(ECAP0_IRQn, IRQ_PRIORITY_CAP); + + NVIC_EnableIRQ(ECAP1_IRQn); //CAP1 + NVIC_SetPriority(ECAP1_IRQn, IRQ_PRIORITY_CAP); + + NVIC_EnableIRQ(ECAP2_IRQn); //CAP2 + NVIC_SetPriority(ECAP2_IRQn, IRQ_PRIORITY_CAP); + + NVIC_EnableIRQ(PWM0_TZ_IRQn); //PDP (в инверторе тексас нету такого пина) + NVIC_SetPriority(PWM0_TZ_IRQn, IRQ_PRIORITY_TZ); + + NVIC_EnableIRQ(QEP_IRQn); //QEP + NVIC_SetPriority(QEP_IRQn, IRQ_PRIORITY_EQEP); + + sm_sys.state = SYS_READY; + +#ifdef WATCHDOG_ON + Watchdog.enable(); //если сторожевой таймер используется, инициализируем +#endif //WATCHDOG_ON +} + + +//!Быстрый расчет (обычно 10кГц). + +//!Вызов быстрых расчетов модулей системы управления +//! \memberof TSM_Sys +void SM_Sys_Fast_Calc(TSM_Sys *p) { + sm_net.fast_calc(&sm_net);//расчет коммуникационных драйверов + if (drv_params.sens_type == POS_SENSOR_TYPE_ENCODER) //В типе датчика выбран энкодер + posspeedEqep.calc(&posspeedEqep); //ДПР энкодер + if (drv_params.sens_type == POS_SENSOR_TYPE_HALL){ //В типе датчика выбран ДПР Холла + DPReCAP.AngleCalc(&DPReCAP); //ДПР Холл, интерполяция угла положения (результат в DPReCAP.Angle) + DPReCAP.Angle6Calc(&DPReCAP); //ДПР Холл, получение угла с точнгстью 60 градусов (результат в DPReCAP.Angle6) + DPReCAP.SpeedCalc(&DPReCAP); //ДПР Холл, расчет скорости вращения (DPReCAP.speed) + DPReCAP.calc_10k(&DPReCAP); //ДПР Холл, служебные функции + } + if (drv_params.sens_type == POS_SENSOR_TYPE_SSI){ //Датчик с интерфейсом SSI. Перед употреблением читайте заголовочный файл! + SSI_Encoder.calc(&SSI_Encoder);//Датчик положения SSI + } + + + + sm_prot.fast_calc(&sm_prot); //Защиты + sm_ctrl.fast_calc(&sm_ctrl); //Главный дискретный автомат системы управления + + global_time.calc(&global_time); + + cur_par.calc(&cur_par); //Расчет текущих показателей привода + drv_params.sens_type = drv_params.sens_type & 3; //Отсекаем верхнюю часть переменной, там мусор + +#ifdef WATCHDOG_ON +// Watchdog.feed();//если сторожевой таймер используется, сбрасываем его здесь +#endif //WATCHDOG_ON +} + +//!Миллисекундный расчет 1кГц. + +//!Вызов расчетов модулей системы управления, требующих миллисекундной дискретизации +//! \memberof TSM_Sys +void SM_Sys_ms_Calc(TSM_Sys* p) { + sm_cmd_logic.ms_calc(&sm_cmd_logic); //Обработка команд управления + sm_net.ms_calc(&sm_net); //обертка для вызова коммуникационных драйверов + adc.ms_calc(&adc); //АЦП + sm_prot.ms_calc(&sm_prot); //Защиты + AutoOffset.ms_calc(&AutoOffset); //авто смещение некоторых каналов АЦП + //блочная передача драйвера CANopen. Через неё, в частности, грузятся осциллограммы dlog +// Can2BTInterface.ms_calc(&Can2BTInterface, TMR2->VALUE, &co2_vars); + leds.msCalc(&leds);//светодиоды + RTCclock.msCalc(&RTCclock);//часы + UserMem.ms_calc(&UserMem);//пользовательская память в МК + if ((drv_params.sens_type == 2) || (drv_params.sens_type == 3)){ //В типе датчика выбран ДПР Холла + DPReCAP.ms_calc(&DPReCAP); + } + global_time.ms_calc(&global_time); +} + +//!Медленный расчет (фоновый). + +//!Вызов медленных расчетов остальных модулей +//! \memberof TSM_Sys +void SM_Sys_Slow_Calc(TSM_Sys *p) { +// Can2BTInterface.slow_calc(&Can2BTInterface);//интерфейс блочной передачи CANopen, медленный расчет + UserMem.slow_calc(&UserMem);//пользовательская память в МК + RTCclock.slowCalc(&RTCclock);//часы реального времени + sm_prot.slow_calc(&sm_prot);//модуль защит + sm_net.slow_calc(&sm_net); //обертка для вызова коммуникационных драйверов + dlog.background_analizer(&dlog); //фоновый обработчик модуля осциллографирования + global_time.slow_calc(&global_time); + rmp.slow_calc(&rmp); //пересчет интенсивности разгона из пользовтельской во внутреннее представление + pwm.slow_calc(&pwm); //фоновый обработчик модуля ШИМ (пересчет пользовательских заданий) + adc.slow_calc(&adc); //Фоновый обработчик АЦП + cur_par.slow_calc(&cur_par); //Расчет текущих показателей привода + AutoOffset.slow_calc(&AutoOffset); + posspeedEqep.slow_calc(&posspeedEqep);//инициализация модуля энкодера + RotorObserver.slow_calc(&RotorObserver);//наблюдатель потока ротора АД + DPReCAP.slow_calc(&DPReCAP);//ДПР Холла + + //Пересчет коэффициентов для масштабирования токов и напряжений + drv_params._1_Udc_nom = _IQdiv(_IQ16(1), _IQ16(drv_params.Udc_nom)); + drv_params._1_I_nom = _IQdiv(_IQ16(1), _IQ16(drv_params.I_nom)); + drv_params._1_U_nom = _IQdiv(_IQ16(1), _IQ16(drv_params.U_nom)); + + if (sw.Reboot & 1) { //команда перезагрузки + sw.Reboot = 0; //сбрасываем её + if (sm_ctrl.state == CTRL_STOP) { //перезагружаемся только в останове + //выполняем сброс проца + //Перезагружает во флеш! + Watchdog.resetCPU(); + } + } + + //вызов расчета смещения АЦП для токов фаз + //Делаем расчет только в останове и отсутствии аварии + if ((sw.AutoOffset & 1) && (sm_ctrl.state == CTRL_STOP)) AutoOffset.Enabled=1; + else AutoOffset.Enabled=0; + + + +} +/*@}*/ + diff --git a/Vsrc/V_AutoOffset.c b/Vsrc/V_AutoOffset.c new file mode 100644 index 0000000..f8d67e8 --- /dev/null +++ b/Vsrc/V_AutoOffset.c @@ -0,0 +1,73 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_AutoOffset.c + \brief Автосмещение АЦП (см. TAutoOffset) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + @{ + */ + +/** \addtogroup TAutoOffset */ +/*@{*/ + +#include "DSP.h" +#include "v_IQmath.h" +#include "V_adc.h" +#include "V_AutoOffset.h" +#include "V_common.h" + +extern TAdcDrv adc; +extern TDrvParams drv_params; + +void AutoOffset_init(TAutoOffset *p) { + p->FilterK = _IQ(0.001); +} + +void AutoOffset_calc(TAutoOffset *p) { + //интеграторы для токов фаз. Когда модуль вызывается, токи должны быть нулевыми. + //если это не так, то интеграторы пойдут считать + p->IA_int = p->IA_int + _IQmpy(p->FilterK, adc.Imeas_a); + p->IB_int = p->IB_int + _IQmpy(p->FilterK, adc.Imeas_b); + p->IC_int = p->IC_int + _IQmpy(p->FilterK, adc.Imeas_c); +} + +void AutoOffset_slow_calc(TAutoOffset *p) { + + long IA_pu; + long IB_pu; + long IC_pu; + + if (p->Enabled){//если модуль авторасчета смещения токов включен + //пересчитываем из о.е. обратно в значения АЦП + IA_pu = -p->IA_int / (_IQ16mpy(adc.Imeas_a_gain, drv_params._1_I_nom)); + adc.Imeas_a_offset = IA_pu >> 1; + + IB_pu = -p->IB_int / (_IQ16mpy(adc.Imeas_b_gain, drv_params._1_I_nom)); + adc.Imeas_b_offset = IB_pu >> 1; + + IC_pu = -p->IC_int / (_IQ16mpy(adc.Imeas_c_gain, drv_params._1_I_nom)); + adc.Imeas_c_offset = IC_pu >> 1; + } else {//модуль выключен, инициализируем интеграторы текущими значенями смещений + p->IA_int=-(((long)adc.Imeas_a_offset)<<1)*_IQ16mpy(adc.Imeas_a_gain, drv_params._1_I_nom); + p->IB_int=-(((long)adc.Imeas_b_offset)<<1)*_IQ16mpy(adc.Imeas_b_gain, drv_params._1_I_nom); + p->IC_int=-(((long)adc.Imeas_c_offset)<<1)*_IQ16mpy(adc.Imeas_c_gain, drv_params._1_I_nom); + } + +} + +/*@}*/ + diff --git a/Vsrc/V_CANtoRS.c b/Vsrc/V_CANtoRS.c new file mode 100644 index 0000000..3a9395c --- /dev/null +++ b/Vsrc/V_CANtoRS.c @@ -0,0 +1,327 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file v_CANtoRS.c + \brief Преобразователь посылок CAN в RS и обратно. Работает +совместно с драйвером CANOpen + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup v_CANtoRS +@{ +*/ +#include "DSP.h" +#include "main.h" + + + +//! \memberof TCANtoRS +void CANtoRS_init(TCANtoRS *p) { + + GPIOB->ALTFUNCSET = (1 << 8) + (1 << 9); + GPIOB->DENSET = (1 << 8) + (1 << 9); + + p->UART=UART1;//Используемый в драйвере номер UART (0, 1) + + p->UART->CR_bit.UARTEN = 1; // Разрешить работу UART + + // Настройка частоты в двух регистрах: + // задание делителя частоты для получения BaudRate + // Т.к. блок UART тактируется с частотой 25 МГц (так настроено в ините микроконтроллера), + // то для получения частоты 57600 бит/с необходим + // делитель 25000000 / (16 * 57600) = 27,126736111111111111111111111111 + // Целая часть I = 27 + // Дробная часть F = (int)( 0.126736111*64 + 0.5 ) = 8 + // Формулы см. в документации + p->UART->IBRD_bit.DIVINT= 27; + p->UART->FBRD_bit.DIVFRAC = 8; + + + p->UART->LCRH_bit.SPS = 0; // Нет проверки четности + p->UART->LCRH_bit.WLEN = 3; // Длина посылки 8 бит + p->UART->LCRH_bit.FEN = 1; // Использовать FIFO + p->UART->CR_bit.TXE = 1; // Разрешить приём + p->UART->CR_bit.RXE = 1; // Разрешить передачу + p->UART->LCRH_bit.STP2 = 0; // 1 стоп-бит + + p->CounterWrongCRC=0; + p->CounterRes=0; + p->CounterSended=0; + p->PacketInWait=0; + +} + + + +//! Из заданного для передачи массива функция формирует +//!API пакет, а затем вызывает функцию +//!побайтовой отправки + + //! \memberof TCANtoRS +Uint16 CANtoRS_SendP(Uint16* Data, int16 len, TCANtoRS *p) { + volatile int16 i; + Uint16 MyCRC; + p->buf_out[0]=0x7E; + for (i=0;ibuf_out[i+1]=Data[i]; + MyCRC=CANtoRS_C_CRC(p,Data,len); + p->buf_out[len+1]=MyCRC & 0xFF;//первый байт + p->buf_out[len+2]=(MyCRC>>8) & 0xFF;//второй байт + p->all_len=1+len+2;//полная длина=сигнатура+данные + контрольная сумма + + i = 0; + // Если буфер TX не заполнен, то отправляем все байты из буфера + while ((p->UART->FR_bit.TXFF != 1) && (i < p->all_len)){ + p->UART->DR = p->buf_out[i]; + i++; + } + + return 1; +} + + + +#define CRC_MAGIC_NUMBER 0xA001 +//! Функция считает контрольную сумму пакета +//! и сравнивает с принятой. Если все верно, то возвращает 1 + //! \memberof TCANtoRS + +Uint16 CANtoRS_C_CRC(TCANtoRS *p,Uint16 *Data,Uint16 len) { //проверка контрольной суммы принятого API пакета + int16 i,j; + Uint16 MyCalcCRC=0xFFFF; + + for (j=0;j>1); + MyCalcCRC=MyCalcCRC^CRC_MAGIC_NUMBER; + } else + MyCalcCRC=(MyCalcCRC>>1); + } + + return MyCalcCRC; +} + + + +/*! Функция вызывается, когда пришли какие-то данные, +и обрабатывает их как переданный CAN пакет. Выделяет +идентификатор, длину и прочее. Рез-т помещает в структуру +p->MSG */ + //! \memberof TCANtoRS +void CANtoRS_Analysis(TCANtoRS *p) { + int16 i,j; + //посылка данных начинается с 12го байта, + //до этого служебная информация API пакета + p->MSG.id=0; + p->MSG.id=(p->ReadPackData[0] & 7)<<8; //нижние 3 бита сдвигаем наверх; + p->MSG.id|=p->ReadPackData[1]; + p->MSG.dlc=(p->ReadPackData[0]>>4) & 0xF; //верхние 4 бита сдвигаем вниз; длина посылки + for (i=2,j=0;iMSG.data[j]=p->ReadPackData[i]; + p->callback_go=1; +} + + + + + +/*! Побайтовый обработчик приходящих по SCI данных. +Работает по принципу дискретного автомата и пытается +найти в посылке API пакет. Сначала ждет заданную сигнатуру, +потом длину и т.п. В конце проверяет контрольную сумму и +вызывает дальнейшие обработчики */ + //! \memberof TCANtoRS + +void CANtoRS_Receive(TCANtoRS *p) { + Uint16 MyReadCRC_u16; + Uint16 MyCalcCRC; + Uint32 temp_byte; + Uint16 repeat; + for (repeat=0;repeat<7; repeat++) {//обработка не более n байт за один вход в функцию + + switch (p->APIpacketMode) { + + case 0: { //ожидание сигнатуры + + + if (p->UART->FR_bit.RXFE) + return; + temp_byte = p->UART->DR_bit.DATA; + if (temp_byte!=0x7e) { + p->MessDrop3++; + return; + } + p->ReadPackDataCounter=0;//счетчик данных + p->APIpacketMode=1; //сигрнатура найдена, режим приема данных + break; + }; + case 1: { //ожидание данных(полезная нагрузка) пакета + //все последующие байты складываем в API буфер + + if (p->UART->FR_bit.RXFE) + return; + temp_byte = p->UART->DR_bit.DATA; + p->ReadPackData[p->ReadPackDataCounter++]=temp_byte; + if (p->ReadPackDataCounter>=CANTORS_READ_DATA_MAX_LEN) { + p->ReadPackDataCounter=0;//счетчик данных + p->ReadCRCCounter=0;//счетчик контрольной суммы + p->APIpacketMode=2; //данные приняты, режим приема и проверси CRC + } + break; + }; + + case 2: { //ожидание CRC + //все последующие байты складываем в CRC буфер + + if (p->UART->FR_bit.RXFE) + return; + temp_byte = p->UART->DR_bit.DATA; + p->ReadCRC[p->ReadCRCCounter++]=temp_byte; + if (p->ReadCRCCounter>=2) { + p->ReadCRCCounter=0;//счетчик контрольной суммы + MyReadCRC_u16=(p->ReadCRC[0]&0xFF)+((p->ReadCRC[1]<<8)&0xFF00);//запаковываем двухбайтовую CRC в одну переменную + MyCalcCRC=CANtoRS_C_CRC(p,p->ReadPackData,CANTORS_READ_DATA_MAX_LEN); + if (MyCalcCRC!=MyReadCRC_u16) { + //ошибка! + p->CounterWrongCRC++; + p->APIpacketMode=0; + break; + }//контрольная сумма принята и верна + + CANtoRS_Analysis(p); + if (p->callback_go) { //если выставлен флаг, вызов callback + p->callback_go=0; + p->APIpacketMode=3; //обработка callback + } + else + p->APIpacketMode=0; + return; + } + break; + }; + case 3: { //обработка callback + p->CounterRes++; + p->callback(&co1_vars, &(p->MSG)); + p->APIpacketMode=0; + break; + }; + default: + return; + } + } + return; +} + + + +/*! Должна вызываться каждую секунду и отсылает +CAN пакеты HeartBeat. Если отослать не выходит (передача занята), +то сокращает последующий таймаут и, немного обождав, пытается +отправить заново */ + //! \memberof TCANtoRS +void CANtoRS_HeartBeat(TCANtoRS *p) { + TZCanMsg MSG; + int16 i; + MSG.id=0xE<<7;//heartbeat + MSG.id|=*p->nodeID;//номер узла + MSG.dlc=1;//длина + for (i=0;i<8;MSG.data[i++]=0);//очистка + MSG.data[0]=5;//данные heartbeat + if (!CANtoRS_Write(&MSG,p)) { //если не получилось отправить + p->HeartCounter=(CANTORS_HEART_COUNTER_MAX-3); //вскоре пробуем сделать это еще раз + p->HeartBeatGo=1;//и если будет событие на отправку SDO, но будет знать, что надо пропустить + } else { + p->HeartBeatGo=0; + } +} + + + //! \memberof TCANtoRS +Uint16 CANtoRS_WriteHelper(TZCanMsg* MSG,TCANtoRS *p) { + if (p->HeartBeatGo) { //хочет отправиться HeartBeat + CANtoRS_HeartBeat(p); + p->MessDrop1++; + return 0;//сообщение теряем... + } + if (CANtoRS_Write(MSG,p)) + p->CounterSended++; + else { + p->MessDrop2++; + + return 0; + } + return 1; +} + + +/*! Из структуры CAN пакета формирует массив-посылку, +где вначале 4 бита - длина, потом 1 бит пропуск и 11 идентификатор. +Далее непосредственно данные. После конструирования посылка отправляется*/ + //! \memberof TCANtoRS +Uint16 CANtoRS_Write(TZCanMsg* MSG,TCANtoRS *p) { + if (!p->PacketInWait) { //нет пакета в буфере + //копируем во временный буфер + p->bufMSG=*MSG; + p->PacketInWait=1;//флаг, что в буфере что-то есть + return 1; + //считается, что буфера на 1 позицию должно хватать + } else + return 0; +} + + //! \memberof TCANtoRS +Uint16 CANtoRS_Write_Real(TZCanMsg* MSG,TCANtoRS *p) { + int16 i; + + p->TempData[0]=(MSG->dlc & 0xF)<<4; + p->TempData[0]|=(MSG->id >> 8) & 7; + p->TempData[1]=MSG->id & 0xFF; + for (i=0;i<8;i++) p->TempData[i+2]=MSG->data[i]; + CANtoRS_SendP(p->TempData,10,p); + return 1; +} + +/*! Вызывается из миллисекундного таймера, отсчитывает 1 секунду +и вызывает функцию отправки HeartBeat. Заодно проверяет, +если в SCI возникла какая-то ошибка и он остановился, перезапускает. + */ + + //! \memberof TCANtoRS +void CANtoRS_calc(TCANtoRS *p) { + + //если в буфере есть пакет, ожидающий отправки и передатчик свободен и не ждет heartbeat + if (p->PacketInWait) { + if (!CANtoRS_Write_Real(&p->bufMSG,p))//отправить не удалось? + p->MessDrop2++; + p->PacketInWait=0;//очищаем буфер + } + else{//если пакета на отправк нет, обрабатывается всё остальное. Можно бы и обрабатывать сразу, но не хватает ресурсов + CANtoRS_Receive(p); + p->HeartCounter++; //счетчик для HeartBeat + + //не пора ли отправить HeartBeat? + if (p->HeartCounter>=(CANTORS_HEART_COUNTER_MAX-1)) { + p->HeartCounter=0; + CANtoRS_HeartBeat(p); + } + + } +} + + + +/*@}*/ diff --git a/Vsrc/V_CurPar.c b/Vsrc/V_CurPar.c new file mode 100644 index 0000000..c140b90 --- /dev/null +++ b/Vsrc/V_CurPar.c @@ -0,0 +1,89 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_CurPar.c + \brief Расчет наблюдаемых текущих параметров (см. TCurPar) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + */ + +/** \addtogroup V_CurPar */ +/*@{*/ + +#ifdef __cplusplus +extern "C" { +#endif +#include "DSP.h" // Device Headerfile and Examples Include File +#include "V_IQmath.h" // библиотека IQmath +#include "V_CurPar.h" // заголовочный файл +#include "main.h" +#ifdef __cplusplus +} +#endif + +//! Инициализация модуля + +//! Так, всяие обнуления... +//! \memberof TCurPar +void CurPar_init(TCurPar* p) { + //фильтры + p->fPower.T = _IQ(0.001); //фильтр мощности для вывода на экран + +} + +//!Расчет мощности из данных фаз + +//!Расчет происходит в двухфазной системе координат, привязанной к статору +//!Для расчета используются мгнованнеые напряжения фаз UalphaRef, UbetaRef, +//!мгнованные токи фаз Ialpha, Ibeta. Для каждой из осей напряжение умножается на ток, +//!полученная мгновенная мощность суммируется с аналогичной мощностью по другой оси, +//!а затем полученная суммартная мгновенная мощность фильтруется инерционным звеном первого порядка. +//! \memberof TCurPar +void CurPar_PowerCalcUf(TCurPar* p) { + p->Ualpha = pwm.UalphaRef; //Напряжение заданное оси альфа + p->Ubeta = pwm.UbetaRef; //Напряжение заданное оси бета + + //мгновенная мощность по осям альфа и бета подается на вход фильтра + p->fPower.input = _IQmpy(p->PowerK, + _IQmpy(p->Ualpha,p->Ialpha)+_IQmpy(p->Ubeta,p->Ibeta)); + + //расчет фильтра + p->fPower.calc(&p->fPower); + //результат работы фильтра - текущая активная мощность. + p->power = p->fPower.output; +} + +//!Расчет текущих параметров привода + +//! \memberof TCurPar +void CurPar_calc(TCurPar* p) { + + CurPar_PowerCalcUf(p); //Расчет мощности +} + +//! \memberof TCurPar +//Расчет внутреннего масштабирующего коэффицента мощности +//для приведения различных типов расчетов мощности к базовой мощности drv_params.power +void CurPar_slow_calc(TCurPar* p) { + float PowerMaxReal; + float PowerMaxScale; + PowerMaxReal = (float) drv_params.I_nom * drv_params.U_nom; + PowerMaxScale = _IQ6toF(drv_params.power); + p->PowerK = _IQmpy(_IQ(PowerMaxReal / PowerMaxScale), _IQ(3.0/2));//дробь 3/2 нужна для преобразования мощности от 2х фазного представления к 3х фазному +} + +/*@}*/ + diff --git a/Vsrc/V_DPR_eCAP.c b/Vsrc/V_DPR_eCAP.c new file mode 100644 index 0000000..5ff2393 --- /dev/null +++ b/Vsrc/V_DPR_eCAP.c @@ -0,0 +1,605 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_DPR_eCAP.c + \brief Модуль датчика абсолютного положения ротора с использованием модулей CAP TDPReCAP (см. TDPReCAP) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 1.1 03/01/2013 + + */ + +/** \addtogroup V_DPR_eCAP */ +/*@{*/ + +#include "DSP.h" // Device Headerfile and Examples Include File +#include "V_IQmath.h" // библиотека IQmath +#include "V_DPR_eCAP.h" // заголовочный файл модуля +#include "main.h" + +extern TDrvParams drv_params; +//! Инициализация + +//!Модули CAP_3, CAP_4, CAP_5 инициализируются +//!для захвата времени между событиями нарастающего и спадающего +//!фронтов, а также генерации прерываний по этим событиям. + +//! \memberof TDPReCAP +void DPReCAP_Init(TDPReCAP* p) { + + //Инициализация ECAP1 + ECAP0->ECEINT = 0x0000; // Disable all capture interrupts + ECAP0->ECCLR = 0xFFFF; // Clear all CAP interrupt flags + ECAP0->ECCTL0_bit.CAPLDEN = 0; // Disable CAP1-CAP4 register loads + ECAP0->ECCTL1_bit.TSCTRSTOP = 0; // Make sure the counter is stopped + ECAP0->ECCTL0_bit.PRESCALE = 0; // DIV1 + + // Configure peripheral registers + ECAP0->ECCTL1_bit.CONTOST = 0; // continuous mode + ECAP0->ECCTL0_bit.CAP0POL = 0; // rising edge + ECAP0->ECCTL0_bit.CAP1POL = 1; // falling edge + ECAP0->ECCTL0_bit.CTRRST0 = 0; // absolute time stamp + ECAP0->ECCTL0_bit.CTRRST1 = 0; // absolute time stamp + ECAP0->ECCTL1_bit.STOPWRAP = 1; // Wrap after Capture Event 2 +// ECAP0->ECCTL1_bit.SYNCI_EN = 1; // Enable sync in + ECAP0->ECCTL1_bit.SYNCOSEL = 0; // Pass through + ECAP0->ECCTL0_bit.CAPLDEN = 1; // Enable capture units + + + + ECAP0->ECCTL1_bit.TSCTRSTOP = 1; // Start Counter + ECAP0->ECCTL1_bit.REARM = 0; // Has no effect (Не очень понимаю этот регистр) + ECAP0->ECCTL0_bit.CAPLDEN = 1; // Enable CAP1-CAP4 register loads + ECAP0->ECEINT_bit.CEVT0 = 1; // 1 events = interrupt + ECAP0->ECEINT_bit.CEVT1 = 1; // 2 events = interrupt + + //Инициализация ECAP2 + ECAP1->ECEINT = 0x0000; // Disable all capture interrupts + ECAP1->ECCLR = 0xFFFF; // Clear all CAP interrupt flags + ECAP1->ECCTL0_bit.CAPLDEN = 0; // Disable CAP1-CAP4 register loads + ECAP1->ECCTL1_bit.TSCTRSTOP = 0; // Make sure the counter is stopped + ECAP1->ECCTL0_bit.PRESCALE = 0; // DIV1 + + // Configure peripheral registers + ECAP1->ECCTL1_bit.CONTOST = 0; // continuous mode + ECAP1->ECCTL0_bit.CAP0POL = 0; // rising edge + ECAP1->ECCTL0_bit.CAP1POL = 1; // falling edge + ECAP1->ECCTL0_bit.CTRRST0 = 0; // absolute time stamp + ECAP1->ECCTL0_bit.CTRRST1 = 0; // absolute time stamp + ECAP1->ECCTL1_bit.STOPWRAP = 1; // Wrap after Capture Event 2 +// ECAP1->ECCTL1_bit.SYNCI_EN = 1; // Enable sync in + ECAP1->ECCTL1_bit.SYNCOSEL = 0; // Pass through + ECAP1->ECCTL0_bit.CAPLDEN = 1; // Enable capture units + + ECAP1->ECCTL1_bit.TSCTRSTOP = 1; // Start Counter + ECAP1->ECCTL1_bit.REARM = 0; // Has no effect (Не очень понимаю этот регистр) + ECAP1->ECCTL0_bit.CAPLDEN = 1; // Enable CAP1-CAP4 register loads + ECAP1->ECEINT_bit.CEVT0 = 1; // 1 events = interrupt + ECAP1->ECEINT_bit.CEVT1 = 1; // 2 events = interrupt + + //Инициализация ECap3 + ECAP2->ECEINT = 0x0000; // Disable all capture interrupts + ECAP2->ECCLR = 0xFFFF; // Clear all CAP interrupt flags + ECAP2->ECCTL0_bit.CAPLDEN = 0; // Disable CAP1-CAP4 register loads + ECAP2->ECCTL1_bit.TSCTRSTOP = 0; // Make sure the counter is stopped + ECAP2->ECCTL0_bit.PRESCALE = 0; // DIV1 + + // Configure peripheral registers + ECAP2->ECCTL1_bit.CONTOST = 0; // continuous mode + ECAP2->ECCTL0_bit.CAP0POL = 0; // rising edge + ECAP2->ECCTL0_bit.CAP1POL = 1; // falling edge + ECAP2->ECCTL0_bit.CTRRST0 = 0; // absolute time stamp + ECAP2->ECCTL0_bit.CTRRST1 = 0; // absolute time stamp + ECAP2->ECCTL1_bit.STOPWRAP = 1; // Wrap after Capture Event 2 +// ECAP2->ECCTL1_bit.SYNCI_EN = 1; // Enable sync in + ECAP2->ECCTL1_bit.SYNCOSEL = 0; // Pass through + ECAP2->ECCTL0_bit.CAPLDEN = 1; // Enable capture units + + ECAP2->ECCTL1_bit.TSCTRSTOP = 1; // Start Counter + ECAP2->ECCTL1_bit.REARM = 0; // Has no effect (Не очень понимаю этот регистр) + ECAP2->ECCTL0_bit.CAPLDEN = 1; // Enable CAP1-CAP4 register loads + ECAP2->ECEINT_bit.CEVT0 = 1; // 1 events = interrupt + ECAP2->ECEINT_bit.CEVT1 = 1; // 2 events = interrupt + + p->TsNom = ((SystemCoreClock / (drv_params.speed_nom * drv_params.p)) * 15*2); + //коэффициент для пересчета времени между метками в мс в скорость в об/мин + //60 - об/мин, 1000 мс в секунде, 6 меток на эл. оборот + p->TsNomMilsec = (60.0*1000 / (6*drv_params.speed_nom * drv_params.p)); + + + DPReCAP_Angle6Calc(p); + p->CAP_WrongEdgeCnt = 0; + +} + + +//! Определение углового положения с дискретностью 60 градусов + +//!Определение углового положения происходит исходя из опроса трех каналов датчика +//!через GPIO. Результат попадает в переменную Angle6. + +//! \memberof TDPReCAP +void DPReCAP_Angle6Calc(TDPReCAP* p) { + // На момент расчёта, запрещаем прерывания по датчикам. + //Если этого не сделать, то эта функция может вызваться в 10к, + //на половне прерваться прерыванием CAP, в котором она вызовется второй раз, + //потом управление вернется к этой функции в 10к и в p->Angle6 попадет старый результат + ECAP0->ECEINT = 0x0000; + ECAP1->ECEINT = 0x0000; + ECAP2->ECEINT = 0x0000; + + // Формируем код по состоянию ножек. + p->HallCode = 0; + +#if defined(HW_VECTORCARD_SIMULATOR) || defined(HW_NIIET_BOARD_SIMULATOR) + p->HallCode = model.hallSensor; + +#else + if (p->UserDirection == 0) { + if (GPIOA->DATA & (1 << 4)) + p->HallCode = p->HallCode + 1; + if (GPIOA->DATA & (1 << 5)) + p->HallCode = p->HallCode + 2; + if (GPIOA->DATA & (1 << 6)) + p->HallCode = p->HallCode + 4; + } else { + if (GPIOA->DATA & (1 << 4)) + p->HallCode = p->HallCode + 4; + if (GPIOA->DATA & (1 << 5)) + p->HallCode = p->HallCode + 2; + if (GPIOA->DATA & (1 << 6)) + p->HallCode = p->HallCode + 1; + } +#endif + + + + + switch (p->HallCode) { + case 5: // 0 + p->Angle6 = 0; + break; + case 4: // 60 + p->Angle6 = _IQ(1.0 / 6.0); + break; + case 6: // 120 + p->Angle6 = _IQ(1.0 / 3.0); + break; + case 2: //180 + p->Angle6 = _IQ(1.0 / 2.0); + break; + case 3: // 240 + p->Angle6 = _IQ(2.0 / 3.0); + break; + case 1: // 300 + p->Angle6 = _IQ(5.0 / 6.0); + break; + } + + // Разрешаем прерывания назад. + ECAP0->ECEINT = 6; + ECAP1->ECEINT = 6; + ECAP2->ECEINT = 6; +} + +void DPReCAP_AngleErrorCalc(TDPReCAP* p) { + long AngleDiff = 0; + AngleDiff = (labs( + ((p->Angle6 - p->AnglePrev + _IQ(0.5)) & 0x00FFFFFF) - _IQ(0.5))) + & 0x00FFFFFF; + p->AnglePrev = p->Angle6; + + if (AngleDiff > _IQ(61.0 / 360)) { //если угол с прошлого раза изменился больше, чем на 60 градусов, то датчик косячит + p->WrongCodeCounter++; + p->WrongCodeCounterPerSec++; + + } +} + +//! Определение углового положения с учетом работы интерполятора углового положения + +//!Интерполятор углового положения (а вернее даже экстраполятор) +//!использует дискретное угловое положение Angle6, выдаваемое функцией DPReCAP_Angle6Calc. +//!Функция "сглаживает" угловое положение во времени, делая из степенчатой смены угла "лесенкой" +//!непрерывную "пилу" (переменная Angle). Для этого используется сохраненное время между двумя любыми +//!предыдущими фронтами с каналов датчика положения (PrevTs). Считая, что скорость вращения постоянна, +//!следующий фронт (а значит смену углового положения) можно прогнозировать через то же самое время. +//!Таким образом, у текущему дискретному угловому положению Angle6 прибавляется +//!добавка, рассчитываемая по формуле 60*(Текущее время/Период). +//!Так, в момент прихода фронта с датчика переменная Angle равна Angle6. Через некоторый момент времени +//! Angle станет равным Angle6+60*(delta/Ts), где delta - текущее время с момента события последнего фронта с датчика, +//! а Ts - период, время между предыдущими двумя событиями фронров датчика. +//! Функция также учитывает направление вращения, а также добавляет пользовательское смещение +//! AngleOffset к результирующему угловому положению. + +//! \memberof TDPReCAP +void DPReCAP_AngleCalc(TDPReCAP* p) { + Uint32 delta, Timer; + Uint32 PrevTs; + _iq Angle; + _iq Angle6; + + // Фиксируем значения переменных на момент начала расчёта + Angle6 = p->Angle6; + +#if (!defined(HW_VECTORCARD_SIMULATOR)) && (!defined(HW_NIIET_BOARD_SIMULATOR)) + + PrevTs = p->PrevTs; + // На момент расчёта, запрещаем прерывания по датчикам. + ECAP0->ECEINT = 0x0000; + ECAP1->ECEINT = 0x0000; + ECAP2->ECEINT = 0x0000; + + + + // Фиксируем значение одного из таймеров на момент начала выполнения модуля. + switch (p->DPReCAP_FLG1.bit.CAPnumber) { + case 1: + Timer = ECAP0->TSCTR; + break; + case 2: + Timer = ECAP1->TSCTR; + break; + case 3: + Timer = ECAP2->TSCTR; + break; + } + + // Если скорость равна нулю или выбран соответствующий режим, то угол не интеполируем. + if ((p->speed == 0) || (p->DPReCAP_FLG1.bit.AngleMode == 0) + || (p->Ts == 0)) { + Angle = _IQ(1.0 / 12); + } else { + delta = Timer - PrevTs; // Сколько натикал таймер с момента прошлого обновления периода. + Angle = _IQdiv(delta, p->Ts); // Интеполируем угол. Отношение прошлого перехода к текущим "тикам". + if (Angle >= _IQ(1.0 / 6.0)) // ограничиваем угол в приделах 1/6. + Angle = _IQ(1.0 / 6.0); + } +#else //симулятор + Angle=_IQ(model.hallSensorInterpAdd * (1/(2*MOTOR_MODEL_PI)));//приращение угла для интерполятора уже предпосчитано в модели двигателя с учетом дискретности +#endif + + if (p->DPReCAP_FLG1.bit.Dir == 1) + Angle = _IQ(1.0/6.0) - Angle; + + if (p->UserDirection) //пользовательская инверсия направления + Angle = -Angle + _IQ(1.0/6); + + p->Angle = Angle6 + Angle + p->AngleOffset; + + p->Angle &= 0x00FFFFFF; + + + // Разрешаем прерывания назад. + ECAP0->ECEINT = 6; + ECAP1->ECEINT = 6; + ECAP2->ECEINT = 6; +} + +//! Функция расчета скорости + +//!Для расчета скорости используется переменная Tspeed, +//!которая представляет собой время между событиями фронтов датчика положения +//!произошедших по одному и тому же каналу. Так, например, временем между нарастающим и спадающим фронтом +//!канала CAP3, затем между спадающим и нарастающим фронтом CAP4 и т.п. +//!На основе этого времени, направления вращения и предпосчитанной константой TsNom +//!рассчитывается скорость вращения. + +//! \memberof TDPReCAP +void DPReCAP_SpeedCalc(TDPReCAP* p) { +#if (!defined(HW_VECTORCARD_SIMULATOR)) && (!defined(HW_NIIET_BOARD_SIMULATOR)) + + _iq speed; + + // Считаем скорость в относительных единицах относительно номинальной. + if ((p->Tspeed != 0) && (p->DPReCAP_FLG1.bit.ZeroFLG == 0)) { + + // Знак скорости опрделяется в зависимости от направления. + if (p->DPReCAP_FLG1.bit.Dir == 0) + speed = _IQdiv(p->TsNom, p->Tspeed); + else + speed = -_IQdiv(p->TsNom, p->Tspeed); + if (p->UserDirection) { //задается пользователем + speed = -speed; + } + } else { + speed = 0; + } + + p->speed = speed; + + + DINT;//нужно для потокобезопасного обращения к переменной DPReCAP_FLG1 (чтобы не перетереть присваивание в прерывании захвата) + // Обнуление скорости, если привысили заданное время между двумя соседними событиями. + if (p->milsec > p->milsecFIX) { + p->speed = 0; + p->DPReCAP_FLG1.bit.ZeroFLG = 1; +// p->cnt1 = 0; // Надо обнулять при стопе и hold'е. Здесь не надо, только для теста. + } + EINT; + + DINT;//нужно для потокобезопасного обращения к переменной DPReCAP_FLG1 (чтобы не перетереть присваивание в прерывании захвата) + + // При скорости меньше заданной, отключаем интерполяцию угла. + if ((labs(p->speed)) <= (p->speedMIN)) + p->DPReCAP_FLG1.bit.SpeedMinFLG = 0; + else + p->DPReCAP_FLG1.bit.SpeedMinFLG = 1; + EINT; + +#else //симулятор + p->speed=p->SimulatorOmega2IQ_factor*model.hallSensorOmega;//Частота вращения уже предпосчитана в модели двигателя с учетом дискретности +#endif +} + +//! Функция, вызываемая в прерывании по нарастающему и спадающему фронту канала датчика 1 + +//! В функции запоминается время таймера модуля CAP в переменную Timer1. +//! Исходя из этого считаются две переменные - p->Ts, время между двумя ближайшими фронтами, +//!необходимое для интерполятора углового положения, и переменная p->Tspeed, +//!время между двумя фронтами одного и того же канала, неободимое для расчета скорости. +//! \memberof TDPReCAP +void DPReCAP_CAP1Calc(TDPReCAP* p) { + Uint32 Timer=0; + if (p->cnt >= 2) { + p->cnt=2; + p->HelpCalc(p); + + // В зависимости от номера предудыщего CAP определяем направление вращения. + if (p->DPReCAP_FLG1.bit.CAPnumber == 3) + p->DPReCAP_FLG1.bit.Dir = 0; + if (p->DPReCAP_FLG1.bit.CAPnumber == 2) + p->DPReCAP_FLG1.bit.Dir = 1; + if (p->DPReCAP_FLG1.bit.CAPnumber == 1) { + if (p->DPReCAP_FLG1.bit.PrevDir == 0) + p->DPReCAP_FLG1.bit.Dir = 1; + else + p->DPReCAP_FLG1.bit.Dir = 0; + } + if (p->DPReCAP_FLG1.bit.Dir != p->DPReCAP_FLG1.bit.PrevDir) { + p->DPReCAP_FLG1.bit.PrevDir = p->DPReCAP_FLG1.bit.Dir; + p->cnt2 = 1; + } + + if (ECAP0->ECFLG_bit.CEVT0==1)//Фронт вверх + { + Timer = ECAP0->CAP0; + } + if (ECAP0->ECFLG_bit.CEVT1==1)//Фронт вниз + { + Timer = ECAP0->CAP1; + } + + // считаем периоды для расчёта угла и скорости. + p->Ts = (Timer - p->PrevTs) * 6; + p->PrevTs = Timer; + + p->Tspeed = Timer - p->PrevTspeed1; + p->PrevTspeed1 = Timer; + + } else { + p->Ts = 0; + p->Tspeed = 0; + } + + + p->cnt++; + p->milsec = 0; + p->DPReCAP_FLG1.bit.CAPnumber = 1; + +} + +//! Функция, вызываемая в прерывании по нарастающему и спадающему фронту канала датчика 2 + +//! В функции запоминается время таймера модуля CAP в переменную Timer1. +//! Исходя из этого считаются две переменные - p->Ts, время между двумя ближайшими фронтами, +//!необходимое для интерполятора углового положения, и переменная p->Tspeed, +//!время между двумя фронтами одного и того же канала, неободимое для расчета скорости. +//! \memberof TDPReCAP +void DPReCAP_CAP2Calc(TDPReCAP* p) { + Uint32 Timer=0; + if (p->cnt >= 2) { + p->cnt=2; + p->HelpCalc(p); + + // В зависимости от номера предудыщего CAP определяем направление вращения. + if (p->DPReCAP_FLG1.bit.CAPnumber == 1) + p->DPReCAP_FLG1.bit.Dir = 0; + if (p->DPReCAP_FLG1.bit.CAPnumber == 3) + p->DPReCAP_FLG1.bit.Dir = 1; + if (p->DPReCAP_FLG1.bit.CAPnumber == 2) { + if (p->DPReCAP_FLG1.bit.PrevDir == 0) + p->DPReCAP_FLG1.bit.Dir = 1; + else + p->DPReCAP_FLG1.bit.Dir = 0; + } + + if (p->DPReCAP_FLG1.bit.Dir != p->DPReCAP_FLG1.bit.PrevDir) { + p->DPReCAP_FLG1.bit.PrevDir = p->DPReCAP_FLG1.bit.Dir; + p->cnt2 = 1; + } + + if (ECAP1->ECFLG_bit.CEVT0==1) + { + Timer = ECAP1->CAP0; + } + if (ECAP1->ECFLG_bit.CEVT1==1) + { + Timer = ECAP1->CAP1; + } + + // считаем периоды для расчёта угла и скорости. + p->Ts = (Timer - p->PrevTs) * 6; + p->PrevTs = Timer; + + p->Tspeed = Timer - p->PrevTspeed2; + p->PrevTspeed2 = Timer; + + } else { + p->Ts = 0; + p->Tspeed = 0; + } + + + p->cnt++; + p->milsec = 0; + p->DPReCAP_FLG1.bit.CAPnumber = 2; + +} + +//! Функция, вызываемая в прерывании по нарастающему и спадающему фронту канала датчика 3 + +//! В функции запоминается время таймера модуля CAP в переменную Timer1. +//! Исходя из этого считаются две переменные - p->Ts, время между двумя ближайшими фронтами, +//!необходимое для интерполятора углового положения, и переменная p->Tspeed, +//!время между двумя фронтами одного и того же канала, неободимое для расчета скорости. +//! \memberof TDPReCAP +void DPReCAP_CAP3Calc(TDPReCAP* p) { + Uint32 Timer; + if (p->cnt >= 2) { + p->cnt=2; + p->HelpCalc(p); + + // В зависимости от номера предудыщего CAP определяем направление вращения. + if (p->DPReCAP_FLG1.bit.CAPnumber == 2) + p->DPReCAP_FLG1.bit.Dir = 0; + if (p->DPReCAP_FLG1.bit.CAPnumber == 1) + p->DPReCAP_FLG1.bit.Dir = 1; + if (p->DPReCAP_FLG1.bit.CAPnumber == 3) { + if (p->DPReCAP_FLG1.bit.PrevDir == 0) + p->DPReCAP_FLG1.bit.Dir = 1; + else + p->DPReCAP_FLG1.bit.Dir = 0; + } + + if (p->DPReCAP_FLG1.bit.Dir != p->DPReCAP_FLG1.bit.PrevDir) { + p->DPReCAP_FLG1.bit.PrevDir = p->DPReCAP_FLG1.bit.Dir; + p->cnt2 = 1; + } + + if (ECAP2->ECFLG_bit.CEVT0==1) + { + Timer = ECAP2->CAP0; + } + if (ECAP2->ECFLG_bit.CEVT1==1) + { + Timer = ECAP2->CAP1; + } + + + // считаем периоды для расчёта угла и скорости. + p->Ts = (Timer - p->PrevTs) * 6; + p->PrevTs = Timer; + + p->Tspeed = Timer - p->PrevTspeed3; + p->PrevTspeed3 = Timer; + + } else { + p->Ts = 0; + p->Tspeed = 0; + } + + + p->cnt++; + p->milsec = 0; + p->DPReCAP_FLG1.bit.CAPnumber = 3; +} + +void DPReCAP_calc_10k(TDPReCAP* p) { + + DINT; + if (p->CAPCalcEna1==0){ + p->CAPCalcEna1=1; + ECAP0->ECCLR_bit.CEVT0 = 1; + ECAP0->ECCLR_bit.CEVT1 = 1; + ECAP0->ECCLR_bit.INT = 1; + } + if (p->CAPCalcEna2==0){ + p->CAPCalcEna2=1; + ECAP1->ECCLR_bit.CEVT0 = 1; + ECAP1->ECCLR_bit.CEVT1 = 1; + ECAP1->ECCLR_bit.INT = 1; + } + if (p->CAPCalcEna3==0){ + p->CAPCalcEna3=1; + ECAP2->ECCLR_bit.CEVT0 = 1; + ECAP2->ECCLR_bit.CEVT1 = 1; + ECAP2->ECCLR_bit.INT = 1; + } + EINT; + +} + + +void DPReCAP_HelpCalc(TDPReCAP* p) { + // Обнуляем скорость и выставляем флаг, + // если время между двумя событиями больше заданного. + if (p->milsec > p->milsecFIX) { + p->speed = 0; + p->DPReCAP_FLG1.bit.ZeroFLG = 1; + } else { + p->DPReCAP_FLG1.bit.ZeroFLG = 0; + } +} + +void DPReCAP_SlowCalc(TDPReCAP* p) { +//формула для расчета T=Ts/Tfiltra где - Tfiltra постоянная времени фильтра +// p->AngleFilter_1_T=_IQdiv(FAST_CALC_TS,AngleFilterT); + if (p->enabled) + if (p->initialized==0){ + p->Init(p); + GPIOA->ALTFUNCSET = (1 << 4) + (1 << 5) + (1 << 6); + GPIOA->DENSET = (1 << 4) + (1 << 5) + (1 << 6); + SIU->REMAPAF_bit.ECAP0EN = 1; + SIU->REMAPAF_bit.ECAP1EN = 1; + SIU->REMAPAF_bit.ECAP2EN = 1; + p->initialized=1; + } +} + + +void DPReCAP_msCalc(TDPReCAP* p) { + p->milsec++;//счетчик времени отсутствия меток + if (p->milsecREF != p->milsecPrevREF) { + p->milsecFIX=p->milsecREF; + p->speedMinREF = _IQdiv(p->TsNomMilsec, p->milsecFIX); + p->milsecPrevREF = p->milsecREF; + } + + p->ErrorLevelTimeCounterBig++; + if (p->ErrorLevelTimeCounterBig > 10000) { + p->ErrorLevel = p->ErrorLevelCounter; + p->ErrorLevelCounter = 0; + p->ErrorLevelTimeCounterBig = 0; + } + + p->ErrorLevelTimeCounter++; + if (p->ErrorLevelTimeCounter > 1000) { + if (p->WrongCodeCounterPerSec > p->WrongCodeCounterLimitPerSec){ + p->SensorFault = 1; + } else + p->SensorFault = 0; + p->WrongCodeCounterPerSec=0; + p->ErrorLevelTimeCounter = 0; + } + + + if (p->CAP_WrongEdgeCntPrev != p->CAP_WrongEdgeCnt) + p->ErrorLevelCounter++; + p->CAP_WrongEdgeCntPrev = p->CAP_WrongEdgeCnt; + +} + +/*@}*/ + diff --git a/Vsrc/V_Global_time.c b/Vsrc/V_Global_time.c new file mode 100644 index 0000000..afc42ba --- /dev/null +++ b/Vsrc/V_Global_time.c @@ -0,0 +1,217 @@ + +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file Global_time.c + \brief Модуль работы со временем + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 1.2 2013_10_16 + +*/ + +/** \addtogroup Global_time */ +/*@{*/ + +#ifdef __cplusplus +extern "C" { +#endif + + +#include + + +//!ИнициализациЯ модулЯ + +//!Если есть часы реального времени, считывает из них времЯ. +//!Восстанавливает времЯ работы и времени включенного состоЯниЯ из SPI. + +//! \memberof TGlobalTime +void GlobalTime_init(TGlobalTime *p) +{ + p->read_PowerOn_time(p); + p->read_oper_time(p); + + + #ifdef USE_ABSOLUTE_TIME_CLOCK + //инициализациЯ абсолютного времени + if (p->time_type == 1) + { + //инициализациЯ из часов реального времени + p->absolute_time.day=spiclock.day; + p->absolute_time.hour=spiclock.hour; + p->absolute_time.minute=spiclock.minute; + p->absolute_time.second=spiclock.second; + p->absolute_time.year=spiclock.year; + } + #endif + //инициализациЯ относительного времени + p->relative_time1.ON = 1;//т.к. 1-е времЯ ЯвлЯетсЯ обЯзательным + + p->relative_time1.relative_date.hour = (p->PowerOn_time >> 6); + p->relative_time1.relative_date.minute = (p->PowerOn_time & 0x3f); + + p->relative_time2.relative_date.hour = (p->operational_time >> 6); + p->relative_time2.relative_date.minute = (p->operational_time & 0x3f); +} + + + + +//!Расчет относительного времени. + +//!Вызывает функции расчета относительно времени и, если есть, считывает времЯ +//!с модулЯ часов реального вермени в абсолютное времЯ. + +//! \memberof TGlobalTime +void GlobalTime_calc(TGlobalTime *p) +{ + //счет относительных времен + GlobalTime_REL_TIME_calc(&p->relative_time1); + GlobalTime_REL_TIME_calc(&p->relative_time2); +} + + +//!Расчет относительного времени. + +//!Вызывает функции расчета относительно времени и, если есть, считывает времЯ +//!с модулЯ часов реального вермени в абсолютное времЯ. + +//! \memberof TGlobalTime +void GlobalTime_ms_calc(TGlobalTime *p) { + + //управление счетом operational_time + if (sm_ctrl.state != 0) //Если в каком-то режиме работы + global_time.relative_time2.ON = TRUE; + else + global_time.relative_time2.ON = FALSE; + + //ВремЯ запитанного состоЯниЯ в минутах + p->PowerOn_time = (global_time.relative_time1.relative_date.hour << 6) + (global_time.relative_time1.relative_date.minute & 0x3f); + //ВремЯ в работе, в минутах + p->operational_time = (global_time.relative_time2.relative_date.hour << 6) + (global_time.relative_time2.relative_date.minute & 0x3f); + + p->PowerOn_time_min = p->relative_time1.relative_date.hour*60 +p->relative_time1.relative_date.minute; + p->operational_time_min = p->relative_time2.relative_date.hour*60 + p->relative_time2.relative_date.minute; + + +#ifdef USE_ABSOLUTE_TIME_CLOCK + if (global_time.time_type == 1) { + //времЯ - из часов реального времени + global_time.absolute_time.day = spiclock.day; + global_time.absolute_time.hour = spiclock.hour; + global_time.absolute_time.minute = spiclock.minute; + global_time.absolute_time.second = spiclock.second; + global_time.absolute_time.year = spiclock.year; + } +#endif +} + +//!Расчет относительного времени + +//!УчитываЯ, что функциЯ вызываетсЯ с какой-то определенной дискретизацией, +//!инкрементирует относительное времЯ, переденное ей в структуре типа RELATIVE_TIME +//! \memberof TGlobalTime +void GlobalTime_REL_TIME_calc(RELATIVE_TIME *p) { + if (p->ON == 0) + return; + if (p->tic_isr != 0) + p->tic_isr--; + p->delta_millisecond = 0; + p->delta_second = 0; + if (p->tic_isr == 0) { + //миллисекунда + p->tic_isr = GLOBAL_TIME_CALC_FREQ; + p->millisecond_counter++; + p->delta_millisecond = 1; + if (p->relative_date.millisecond == 999) { + //секунда + p->relative_date.millisecond = 0; + p->second_counter++; + p->delta_second = 1; + if (p->relative_date.second == 59) { + //минута + p->relative_date.second = 0; + if (p->relative_date.minute == 59) { + //час + p->relative_date.minute = 0; + p->relative_date.hour++; + } else + p->relative_date.minute++; + } else + p->relative_date.second++; + } else + p->relative_date.millisecond++; + } +} + + +//!Читает времЯ наработки. + +//! \memberof TCurPar +void GlobalTime_read_PowerOn_time(TGlobalTime *p) { //чтение work_time + UserMem.MemStartAddr = GLOBAL_TIME_POWER_ON_TIME_ADDR; + UserMem.MCUStartAddr = (Uint16*) (&(p->PowerOn_time)); + UserMem.data_length = 4; + UserMem.read(&UserMem); +} + + +//!записывает времЯ наработки. + +//! \memberof TCurPar +void GlobalTime_write_PowerOn_time(TGlobalTime *p) { //запись work_time + UserMem.MemStartAddr = GLOBAL_TIME_POWER_ON_TIME_ADDR; + UserMem.MCUStartAddr = (Uint16*) (&(p->PowerOn_time)); + UserMem.data_length = 4; + UserMem.write(&UserMem); +} + +//!Читает времЯ включенного сосотЯниЯ. +//! \memberof TCurPar +void GlobalTime_read_oper_time(TGlobalTime *p) { //чтение operational_time + UserMem.MemStartAddr = GLOBAL_TIME_OPERATIONAL_TIME_ADDR; + UserMem.MCUStartAddr = (Uint16*) (&(p->operational_time)); + UserMem.data_length = 4; + UserMem.read(&UserMem); +} + +//!записывает времЯ включенного сосотЯниЯ. +//! \memberof TCurPar +void GlobalTime_write_oper_time(TGlobalTime *p) { //запись operational_time + UserMem.MemStartAddr = GLOBAL_TIME_OPERATIONAL_TIME_ADDR; + UserMem.MCUStartAddr = (Uint16*) (&(p->operational_time)); + UserMem.data_length = 4; + UserMem.write(&UserMem); +} + + +void GlobalTime_slow_calc(TGlobalTime*p) { + //если стоит флаг на сохранение времен в SPI или с момент прошлой записи прошел час + if ((p->WtiteSPI_flag) || (p->PrevWriteSPIHour != global_time.relative_time1.relative_date.hour)) { + + p->write_PowerOn_time(p); //запись времени вкл. состоЯниЯ + p->write_oper_time(p); //запись рабочего времени + p->PrevWriteSPIHour = global_time.relative_time1.relative_date.hour; + p->WtiteSPI_flag = 0; + } +} + + + +#ifdef __cplusplus +} // Extern "C" +#endif +/*@}*/ + diff --git a/Vsrc/V_IQmath.c b/Vsrc/V_IQmath.c new file mode 100644 index 0000000..aba631f --- /dev/null +++ b/Vsrc/V_IQmath.c @@ -0,0 +1,280 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_IQmath.c + \brief Библиотека функций целочисленной математики + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup V_IQmath + @{*/ + +#include "V_IQmath.h" +#include "stdlib.h" +#include "math.h" + +#if defined (__GNUC__) || defined (CMCPPARM) +#if defined (__GNUC__) +// Count leading zeros, using processor-specific instruction if available. +#define clz(x) __builtin_clzl(x) +#endif +#if defined (CMCPPARM) //CodeMaster +#define clz(x) __CLZ(x) +#endif +#else +static uint8_t clz(uint32_t x) { + uint8_t result = 0; + if (x == 0) return 32; + while (!(x & 0xF0000000)) { + result += 4; + x <<= 4; + } + while (!(x & 0x80000000)) { + result += 1; + x <<= 1; + } + return result; +} +#endif + +//! Деление двух чисел в формате 22.10 + +//! \memberof V_IQmath +int32 _IQ10div(int32 a, int32 b) { + if (b == 0) + return 0; + return _IQ10((float )(a) / b); //32 такта +} + +//! Деление двух чисел в формате 8.24 +//! \memberof V_IQmath +int32 _IQ24div(int32 a, int32 b) { + if (b == 0) + return 0; + return _IQ24((float )a / b); //32 такта +} + + +//! Квадратный корень в формате 8.24. Работает через аппаратный float, занимает 43 такта. +//! В CodeMaster нет функции sqrtf, поэтому для него вызывается sqrt. Для GCC вызывать +//! sqrt нельзя, т.к. тогда он попытается работать с double, а не float. +int32 _IQ24sqrt(int32 number) { + return _IQ(sqrtf((float)_IQtoF(number))); +} + + + +static const int16 sinTableQ15[259] = { + 0xfcdc, 0x0, 0x324, 0x648, 0x96b, 0xc8c, 0xfab, 0x12c8, + 0x15e2, 0x18f9, 0x1c0c, 0x1f1a, 0x2224, 0x2528, 0x2827, 0x2b1f, + 0x2e11, 0x30fc, 0x33df, 0x36ba, 0x398d, 0x3c57, 0x3f17, 0x41ce, + 0x447b, 0x471d, 0x49b4, 0x4c40, 0x4ec0, 0x5134, 0x539b, 0x55f6, + 0x5843, 0x5a82, 0x5cb4, 0x5ed7, 0x60ec, 0x62f2, 0x64e9, 0x66d0, + 0x68a7, 0x6a6e, 0x6c24, 0x6dca, 0x6f5f, 0x70e3, 0x7255, 0x73b6, + 0x7505, 0x7642, 0x776c, 0x7885, 0x798a, 0x7a7d, 0x7b5d, 0x7c2a, + 0x7ce4, 0x7d8a, 0x7e1e, 0x7e9d, 0x7f0a, 0x7f62, 0x7fa7, 0x7fd9, + 0x7ff6, 0x7fff, 0x7ff6, 0x7fd9, 0x7fa7, 0x7f62, 0x7f0a, 0x7e9d, + 0x7e1e, 0x7d8a, 0x7ce4, 0x7c2a, 0x7b5d, 0x7a7d, 0x798a, 0x7885, + 0x776c, 0x7642, 0x7505, 0x73b6, 0x7255, 0x70e3, 0x6f5f, 0x6dca, + 0x6c24, 0x6a6e, 0x68a7, 0x66d0, 0x64e9, 0x62f2, 0x60ec, 0x5ed7, + 0x5cb4, 0x5a82, 0x5843, 0x55f6, 0x539b, 0x5134, 0x4ec0, 0x4c40, + 0x49b4, 0x471d, 0x447b, 0x41ce, 0x3f17, 0x3c57, 0x398d, 0x36ba, + 0x33df, 0x30fc, 0x2e11, 0x2b1f, 0x2827, 0x2528, 0x2224, 0x1f1a, + 0x1c0c, 0x18f9, 0x15e2, 0x12c8, 0xfab, 0xc8c, 0x96b, 0x648, + 0x324, 0x0, 0xfcdc, 0xf9b8, 0xf695, 0xf374, 0xf055, 0xed38, + 0xea1e, 0xe707, 0xe3f4, 0xe0e6, 0xdddc, 0xdad8, 0xd7d9, 0xd4e1, + 0xd1ef, 0xcf04, 0xcc21, 0xc946, 0xc673, 0xc3a9, 0xc0e9, 0xbe32, + 0xbb85, 0xb8e3, 0xb64c, 0xb3c0, 0xb140, 0xaecc, 0xac65, 0xaa0a, + 0xa7bd, 0xa57e, 0xa34c, 0xa129, 0x9f14, 0x9d0e, 0x9b17, 0x9930, + 0x9759, 0x9592, 0x93dc, 0x9236, 0x90a1, 0x8f1d, 0x8dab, 0x8c4a, + 0x8afb, 0x89be, 0x8894, 0x877b, 0x8676, 0x8583, 0x84a3, 0x83d6, + 0x831c, 0x8276, 0x81e2, 0x8163, 0x80f6, 0x809e, 0x8059, 0x8027, + 0x800a, 0x8000, 0x800a, 0x8027, 0x8059, 0x809e, 0x80f6, 0x8163, + 0x81e2, 0x8276, 0x831c, 0x83d6, 0x84a3, 0x8583, 0x8676, 0x877b, + 0x8894, 0x89be, 0x8afb, 0x8c4a, 0x8dab, 0x8f1d, 0x90a1, 0x9236, + 0x93dc, 0x9592, 0x9759, 0x9930, 0x9b17, 0x9d0e, 0x9f14, 0xa129, + 0xa34c, 0xa57e, 0xa7bd, 0xaa0a, 0xac65, 0xaecc, 0xb140, 0xb3c0, + 0xb64c, 0xb8e3, 0xbb85, 0xbe32, 0xc0e9, 0xc3a9, 0xc673, 0xc946, + 0xcc21, 0xcf04, 0xd1ef, 0xd4e1, 0xd7d9, 0xdad8, 0xdddc, 0xe0e6, + 0xe3f4, 0xe707, 0xea1e, 0xed38, 0xf055, 0xf374, 0xf695, 0xf9b8, + 0xfcdc, 0x0, 0x324 +}; + + + +//! Функция синуса, табличная, точная, с кубической интерполяцией между точками. + +//! Внутри работает с тоностью 16.16, но конвертируется в 8.24 +//! 83 такта +//!Взято из библиотеки DSP ARM +//! \memberof V_IQmath +int32 _IQ24sinPU_accurate( + int32 x) { + int32 sinVal; /* Temporary variables output */ + int16 *tablePtr; /* Pointer to table */ + int16 fract, in, in2; /* Temporary variables for input, output */ + int32 wa, wb, wc, wd; /* Cubic interpolation coefficients */ + int16 a, b, c, d; /* Four nearest output values */ + int16 fractCube, fractSquare; /* Temporary values for fractional value */ + int16 oneBy6 = 0x1555; /* Fixed point16 value of 1/6 */ + int16 tableSpacing = 0x80; /* Table spacing */ + int32 index; /* Index variable */ + + in = (x>>9)&0x7FFF; + + + /* Calculate the nearest index */ + index = (int32_t) in / tableSpacing; + + /* Calculate the nearest value of input */ + in2 = (int16) ((index) * tableSpacing); + + /* Calculation of fractional value */ + fract = (in - in2) << 8; + + /* fractSquare = fract * fract */ + fractSquare = (int16) ((fract * fract) >> 15); + + /* fractCube = fract * fract * fract */ + fractCube = (int16) ((fractSquare * fract) >> 15); + + /* Checking min and max index of table */ + if (index < 0) { + index = 0; + } else if (index > 256) { + index = 256; + } + + /* Initialise table pointer */ + tablePtr = (int16 *) & sinTableQ15[index]; + + /* Cubic interpolation process */ + /* Calculation of wa */ + /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAA)*fract; */ + wa = (int32) oneBy6 *fractCube; + wa += (int32) 0x2AAA *fract; + wa = -(wa >> 15); + wa += ((int32) fractSquare >> 1u); + + /* Read first nearest value of output from the sin table */ + a = *tablePtr++; + + /* sinVal = a * wa */ + sinVal = a * wa; + + /* Calculation of wb */ + wb = (((int32) fractCube >> 1u) - (int32) fractSquare) - + (((int32) fract >> 1u) - 0x7FFF); + + /* Read second nearest value of output from the sin table */ + b = *tablePtr++; + + /* sinVal += b*wb */ + sinVal += b * wb; + + + /* Calculation of wc */ + wc = -(int32) fractCube + fractSquare; + wc = (wc >> 1u) + fract; + + /* Read third nearest value of output from the sin table */ + c = *tablePtr++; + + /* sinVal += c*wc */ + sinVal += c * wc; + + /* Calculation of wd */ + /* wd = (oneBy6)*fractCube - (oneBy6)*fract; */ + fractCube = fractCube - fract; + wd = ((int16) (((int32) oneBy6 * fractCube) >> 15)); + + /* Read fourth nearest value of output from the sin table */ + d = *tablePtr++; + + /* sinVal += d*wd; */ + sinVal += d * wd; + + + /* Return the output value */ + return sinVal>>6; +} + + + + + +//! Функция синуса, приближенная, быстрая. + +//!A sine approximation via a fourth-order cosine approx. +//! Внутри работает с точностью 16.16, но конвертируется в 8.24 +//! http://www.coranac.com/2009/07/sines/ +//! 30 тактов +//! \memberof V_IQmath + +int32 _IQ24sinPU(int32 x) { + int32 c, y; + static const int32 qN = 13, qA = 12, B = 19900, C = 3516; + x = x >> 9; //from 8.24 + c = x << (30 - qN); // Semi-circle info into carry. + x -= 1 << qN; // sine -> cosine calc + + x = x << (31 - qN); // Mask with PI + x = x >> (31 - qN); // Note: SIGNED shift! (to qN) + x = x * x >> (2 * qN - 14); // x=x^2 To Q14 + + y = B - (x * C >> 14); // B - x^2*C + y = (1 << qA) - (x * y >> 16); // A - x^2*(B-x^2*C) + y = y << 12; // to 8.24 + return c >= 0 ? y : -y; +} + +//! Функция atan2. + +//!http://www.dspguru.com/dsp/tricks/fixed-point-atan2-with-self-normalization +//!100 тактов + +//! \memberof V_IQmath +int32 _IQ24atan2PU(int32 inY , int32 inX) { + int32 abs_inY, angle, r, r_3; + + abs_inY = labs(inY)+1;// kludge to prevent 0/0 condition + + if (inX >= 0) { + r = _IQ24div( (inX - abs_inY), (inX + abs_inY)); + r_3=_IQmpy(_IQmpy(r,r),r); + angle = _IQ24mpy(_IQ(0.1963f/(2.0f*_PI)),r_3)-_IQ24mpy(_IQ(0.9817f/(2.0f*_PI)),r)+_IQ24(_PI/4.0f/(2.0f*_PI)); + } else { + r = _IQ24div( (inX + abs_inY), (abs_inY - inX)); + r_3=_IQmpy(_IQmpy(r,r),r); + angle = _IQ24mpy(_IQ(0.1963f/(2.0f*_PI)),r_3)-_IQ24mpy(_IQ(0.9817f/(2.0f*_PI)),r)+_IQ24(3.0f*_PI/4.0f/(2.0f*_PI)); + } + if (inY < 0) { + angle = -angle; + } + angle=angle&0xFFFFFF; + return angle; +} + + +//! Функция вычисления амплитуды вектора +//! 60 тактов + +//! \memberof V_IQmath +int32 _IQ24mag(int32 a, int32 b) { + return _IQ24sqrt(_IQ24mpy(a, a) + _IQ24mpy(b, b)); +} + +/*@}*/ + diff --git a/Vsrc/V_PWM_Module.c b/Vsrc/V_PWM_Module.c new file mode 100644 index 0000000..b269444 --- /dev/null +++ b/Vsrc/V_PWM_Module.c @@ -0,0 +1,652 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_PWM_Module.c + \brief Модуль реализации векторной ШИМ (см. TPWM_Module) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup V_PWM_Module + @{*/ + + +#include "V_IQmath.h" +#include "V_PWM_Module.h" +#include "main.h" + +//! Инициализация + +//! \memberof TPWM_Module +void PWM_Module_Init(TPWM_Module *p) { + SIU->PWMSYNC_bit.PRESCRST = 0; //синхронизация таймеров - сброс внутренних счетчиков + + +// ------------------------------------------------------------------------ + // Настраиваем модуль ePWM0 + // ------------------------------------------------------------------------ + if (p->Frequency < PWM_FREQ_MIN) + p->Frequency = PWM_FREQ_MIN; + if (p->Frequency > PWM_FREQ_MAX) + p->Frequency = PWM_FREQ_MAX; + PWM0->TBPRD = _IQ10div(_IQ10(SystemCoreClock/1000.0), p->Frequency << 1) >> 10; //период + + p->k_pwm = PWM0->TBPRD; + p->FreqPrev = p->Frequency; //предыдущая частота + PWM0->TBPHS_bit.TBPHS = 0x0000; // Phase is 0 + PWM0->TBCTR = 0x0000; // Clear counter + + // Setup counter mode + PWM0->TBCTL_bit.PRDLD = TB_SHADOW; // загрузка TBPRD при TBCTR = 0 + PWM0->TBCTL_bit.CTRMODE = TB_COUNT_UPDOWN; // Count up-down + PWM0->TBCTL_bit.PHSEN = TB_DISABLE; // Disable phase loading + PWM0->TBCTL_bit.PHSDIR = TB_UP; // Считать вверх после загрузки фазы + PWM0->TBCTL_bit.HSPCLKDIV = 0; // High Speed Time-base Clock Prescale + PWM0->TBCTL_bit.CLKDIV = 0; // Time-base Clock Prescale + PWM0->TBCTL_bit.SYNCOSEL = TB_CTR_ZERO; // выдаём синхро-сигнал при TBCTR = 0 + + // Setup shadowing + PWM0->CMPCTL_bit.SHDWAMODE = CC_SHADOW; //включить SHADOW для сравнения + PWM0->CMPCTL_bit.LOADAMODE = CC_CTR_ZERO; // Load on period and zero + + PWM0->CMPCTL_bit.SHDWBMODE = CC_SHADOW; //включить SHADOW для сравнения + PWM0->CMPCTL_bit.LOADBMODE = CC_CTR_ZERO; // Load on period and zero + + // Set Compare values + PWM0->CMPA_bit.CMPA = 0; // Set compare A value + + // Set actions + PWM0->AQCTLA = AQ_EPWM_DISABLE; // для начала события для PWM1A запрещены + PWM0->AQCTLA_bit.ZRO = 1; //обнуляем при нуле счетчика + PWM0->AQCTLA_bit.CAU = 2; //включаем при сравнении и инкрементиовании + PWM0->AQCTLA_bit.CAD = 1; //обнуляем при сравнении и декрементровании + + //Для PWMB тоже самое, что для PWMА. Без инверсии. Инверсия далее в модуле МВ + PWM0->AQCTLB = PWM0->AQCTLA; // для начала события для PWM1B запрещены + PWM0->AQCTLB_bit.ZRO = PWM0->AQCTLA_bit.ZRO; //обнуляем при нуле счетчика + PWM0->AQCTLB_bit.CAU = PWM0->AQCTLA_bit.CAU; //включаем при сравнении и инкрементиовании + PWM0->AQCTLB_bit.CAD = PWM0->AQCTLA_bit.CAD; //обнуляем при сравнении и декрементровании + + PWM0->AQSFRC_bit.RLDCSF = 0; //по ТО надо писать 0 + + // Setup Deadband + // DBRED = DBFED = 150 * Tм_мкс / 4 + PWM0->DBRED = _IQ4mpy(_IQ4(150 / 4), p->DeadBand >> 20) >> 4; + PWM0->DBFED = PWM0->DBRED; + + // Настройка модуля мёртвого времени: + // INMODE: S5=0 S4=0 - сигнал с задержанным передним фронтом и сигнал с задержанным задним фронтом + // формируются из сигнала PWMA + // POLSEL: S3 = 1 S2 = 1 - сигнал с задержанным передним фронтом идёт как есть, а сигнал + // с задержанным задним фронтом инвертируется + // OUTMODE:S0 = 1 S1 = 1 на канал PWMA выходит исходный сигнал PWMA, но с задержанным передним фронтом + // На канал PWMB выходит сигнал PWMA с задержанным задним фронтом да ещё и с инверсией + PWM0->DBCTL_bit.INMODE = DBA_ALL; + PWM0->DBCTL_bit.POLSEL = DB_ACTV_HIC; + PWM0->DBCTL_bit.OUTMODE = DB_FULL_ENABLE; + + PWM0->ETSEL_bit.INTSEL = ET_DISABLE; // Disable INT (шимовское) + PWM0->ETSEL_bit.INTEN = 0; // Disable INT + + + //разрешаем TZ быть источником аппаратной аварии (one-shot) + // PWM0->TZSEL_bit.OSHT1 = TZ_ENABLE; +// PWM0->TZSEL_bit.OSHT2 = TZ_ENABLE; +// PWM0->TZSEL_bit.OSHT3 = TZ_ENABLE; + + // Trip-Zone + PWM0->TZCTL_bit.TZA = TZ_STATE; // по событию "One-Shot Trip" переводим + PWM0->TZCTL_bit.TZB = TZ_STATE; // ШИМ выходы в нужное состояние + + //Для VectorCARD от ШИМа запускается ADC + //PWM0->ETSEL_bit.SOCAEN = 1; // Разрешить запуск ацп + //PWM0->ETSEL_bit.SOCASEL = 1; // Запускать при CTR == 0 (Underflow) + + // ------------------------------------------------------------------------ + // Настраиваем модуль ePWM1 + // ------------------------------------------------------------------------ + // Setup TBCLK + PWM1->TBPRD = PWM0->TBPRD; //период такой же + PWM1->TBPHS_bit.TBPHS = 0x0001; // Фаза равна 1 из-за задержки в один такт на синхронизацию + PWM1->TBCTR = 0x0000; // Clear counter + + // Setup counter mode + PWM1->TBCTL_bit.PRDLD = TB_SHADOW; // загрузка TBPRD при TBCTR = 0 + PWM1->TBCTL_bit.CTRMODE = TB_COUNT_UPDOWN; // Count up-down + PWM1->TBCTL_bit.PHSEN = TB_ENABLE; // Enable phase loading + PWM1->TBCTL_bit.PHSDIR = TB_UP; // Считать вверх после загрузки фазы + PWM1->TBCTL_bit.HSPCLKDIV = 0; // High Speed Time-base Clock Prescale + PWM1->TBCTL_bit.CLKDIV = 0; // Time-base Clock Prescale + PWM1->TBCTL_bit.SYNCOSEL = TB_SYNC_IN; // пропускаем синхро-сигнал "насквозь" + + // Setup shadowing + PWM1->CMPCTL_bit.SHDWAMODE = CC_SHADOW; //включить SHADOW для сравнения + PWM1->CMPCTL_bit.LOADAMODE = CC_CTR_ZERO; // Load on period and zero + + PWM1->CMPCTL_bit.SHDWBMODE = CC_SHADOW; //включить SHADOW для сравнения + PWM1->CMPCTL_bit.LOADBMODE = CC_CTR_ZERO; // Load on period and zero + + // Set Compare values + PWM1->CMPA_bit.CMPA = 0; // Set compare A value + + // Set actions + PWM1->AQCTLA = AQ_EPWM_DISABLE; // для начала события запрещены + PWM1->AQCTLA_bit.ZRO = 1; //обнуляем при нуле счетчика + PWM1->AQCTLA_bit.CAU = 2; //включаем при сравнении и инкрементиовании + PWM1->AQCTLA_bit.CAD = 1; //обнуляем при сравнении и декрементровании + + //Для PWMB тоже самое, что для PWMА. Без инверсии. Инверсия далее в модуле МВ + PWM1->AQCTLB = PWM0->AQCTLA; // для начала события для PWM1B запрещены + PWM1->AQCTLB_bit.ZRO = PWM0->AQCTLA_bit.ZRO; //обнуляем при нуле счетчика + PWM1->AQCTLB_bit.CAU = PWM0->AQCTLA_bit.CAU; //включаем при сравнении и инкрементиовании + PWM1->AQCTLB_bit.CAD = PWM0->AQCTLA_bit.CAD; //обнуляем при сравнении и декрементровании + + PWM1->AQSFRC_bit.RLDCSF = 0; //по ТО надо писать 0 + + // Active high complementary PWMs - Setup Deadband + PWM1->DBRED = PWM0->DBRED; + PWM1->DBFED = PWM1->DBRED; + PWM1->DBCTL_bit.INMODE = PWM0->DBCTL_bit.INMODE; + PWM1->DBCTL_bit.OUTMODE = PWM0->DBCTL_bit.OUTMODE; + PWM1->DBCTL_bit.POLSEL = PWM0->DBCTL_bit.POLSEL; + + // Interrupt where we will change the Compare Values + PWM1->ETSEL_bit.INTSEL = ET_DISABLE; // Disable INT + PWM1->ETSEL_bit.INTEN = 0; // Disable INT + + // Trip-Zone + PWM1->TZCTL_bit.TZA = TZ_STATE; // по событию "One-Shot Trip" переводим + PWM1->TZCTL_bit.TZB = TZ_STATE; // ШИМ выходы в нужное состояние + + // ------------------------------------------------------------------------ + // Настраиваем модуль ePWM2 + // ------------------------------------------------------------------------ + // Setup TBCLK + PWM2->TBPRD = PWM0->TBPRD; + PWM2->TBPHS_bit.TBPHS = 0x0001; // Фаза равна 1 из-за задержки в один такт на синхронизацию + PWM2->TBCTR = 0x0000; // Clear counter + + // Setup counter mode + PWM2->TBCTL_bit.PRDLD = TB_SHADOW; // загрузка TBPRD при TBCTR = 0 + PWM2->TBCTL_bit.CTRMODE = TB_COUNT_UPDOWN; // Count up-down + PWM2->TBCTL_bit.PHSEN = TB_ENABLE; // Enable phase loading + PWM2->TBCTL_bit.PHSDIR = TB_UP; // Считать вверх после загрузки фазы + PWM2->TBCTL_bit.HSPCLKDIV = 0; // High Speed Time-base Clock Prescale + PWM2->TBCTL_bit.CLKDIV = 0; // Time-base Clock Prescale + PWM2->TBCTL_bit.SYNCOSEL = TB_SYNC_IN; // разрешаем выдачу синхро-сигнала + + // Setup shadowing + PWM2->CMPCTL_bit.SHDWAMODE = CC_SHADOW; //включить SHADOW для сравнения + PWM2->CMPCTL_bit.LOADAMODE = CC_CTR_ZERO; // Load on period and zero + + PWM2->CMPCTL_bit.SHDWBMODE = CC_SHADOW; //включить SHADOW для сравнения + PWM2->CMPCTL_bit.LOADBMODE = CC_CTR_ZERO; // Load on period and zero + + // Set Compare values + PWM2->CMPA_bit.CMPA = 0; // Set compare A value + + // Set actions + PWM2->AQCTLA = AQ_EPWM_DISABLE; // для начала события запрещены + PWM2->AQCTLA_bit.ZRO = 1; //обнуляем при нуле счетчика + PWM2->AQCTLA_bit.CAU = 2; //включаем при сравнении и инкрементиовании + PWM2->AQCTLA_bit.CAD = 1; //обнуляем при сравнении и декрементровании + + //Для PWMB тоже самое, что для PWMА. Без инверсии. Инверсия далее в модуле МВ + PWM2->AQCTLB = PWM0->AQCTLA; // для начала события для PWM1B запрещены + PWM2->AQCTLB_bit.ZRO = PWM0->AQCTLA_bit.ZRO; //обнуляем при нуле счетчика + PWM2->AQCTLB_bit.CAU = PWM0->AQCTLA_bit.CAU; //включаем при сравнении и инкрементиовании + PWM2->AQCTLB_bit.CAD = PWM0->AQCTLA_bit.CAD; //обнуляем при сравнении и декрементровании + + PWM2->AQSFRC_bit.RLDCSF = 0; //по ТО надо писать 0 + + // Active high complementary PWMs - Setup Deadband + PWM2->DBRED = PWM0->DBRED; + PWM2->DBFED = PWM2->DBRED; + PWM2->DBCTL_bit.INMODE = PWM0->DBCTL_bit.INMODE; + PWM2->DBCTL_bit.OUTMODE = PWM0->DBCTL_bit.OUTMODE; + PWM2->DBCTL_bit.POLSEL = PWM0->DBCTL_bit.POLSEL; + + // Interrupt where we will change the Compare Values + PWM2->ETSEL_bit.INTSEL = ET_DISABLE; // Disable INT + PWM2->ETSEL_bit.INTEN = 0; // Disable INT + + // Trip-Zone + PWM2->TZCTL_bit.TZA = TZ_STATE; // по событию "One-Shot Trip" переводим + PWM2->TZCTL_bit.TZB = TZ_STATE; // ШИМ выходы в нужное состояние + + + // Отключаем ключи + PWM0->TZFRC_bit.OST = 1; + PWM1->TZFRC_bit.OST = 1; + PWM2->TZFRC_bit.OST = 1; + + + + //PWM0->TBCTL_bit.FREESOFT = 0; + //ШИМ 6 выводов + GPIOA->ALTFUNCSET = (1 << 8) + (1 << 9) + (1 << 10) + (1 << 11) + (1 << 12) + (1 << 13); + GPIOA->DENSET = (1 << 8) + (1 << 9) + (1 << 10) + (1 << 11) + (1 << 12) + (1 << 13); + + //Синхронный запуск ШИМ + SIU->PWMSYNC_bit.PRESCRST= 0b111; + +} + + + +//! Нормирование входных величин. + +//!Учитывает компенсацию напряжения при изменении Ud, +//!выполняет вписывание вектора в окружность, если требуется, и +//!выполняет смену базиса, относительно которого идет нормировка. +//! \memberof TPWM_Module +void PWM_Module_NormInput(TPWM_Module* p) { + _iq knorm; + + p->UalphaNorm=p->UalphaRef; + p->UbetaNorm=p->UbetaRef; + + //находим амплитуду (без учета ограничения) + p->U_mag=_IQmag(p->UalphaNorm,p->UbetaNorm); + + + p->UdCorTmp=_IQdiv(_IQ(1.0),(_IQ(1.0)+_IQmpy((adc.Udc_meas-_IQ(1.0)),p->UdCompK))); + //учет пульсаций напряжения на Ud + if (p->UdCompEnable&1) { //он включен? + p->UalphaNorm=_IQmpy(p->UalphaNorm, p->UdCorTmp);//изменим пропорционально коэфф-ту коррекции + p->UbetaNorm=_IQmpy(p->UbetaNorm, p->UdCorTmp);//и это тоже + } + + //вписывание заданной амплитуды напряжения в окружность, вписываемую в шестиугольник базывых векторов + //когда U_lim=1.0, это и есть такая окружность. Бывает, что мы хотим вписывать в шестиугольник. Тогда просто задираем вверх огрианичение U_lim + if (p->U_lim>_IQ(1.0/0.866)) //но нет смысла задирать выше максимально-реализ. напряжения (больше базового вектора) + p->U_lim=_IQ(1.0/0.866); + /* рассчитываем амплитуду вектора, который хотим отработать*/ + knorm=_IQmag(p->UalphaNorm,p->UbetaNorm);//плюс нормируем от 540 к 311 + if (knorm>=p->U_lim) { //он больше, чем наше ограничение? + knorm=_IQdiv(p->U_lim,knorm);//в эту же переменную, для экономии, рассчитываем нормировку + p->UalphaNorm=_IQmpy(knorm,p->UalphaNorm);//уменьшаем пропорционально нормировке + p->UbetaNorm=_IQmpy(knorm,p->UbetaNorm);//и это + p->ULimitation=1;//флаг о том, что идет ограничение напряжения + } else + p->ULimitation=0; + + /* рассчитываем приведенные вектора*/ + /* До этого момента напряжение нормировалось относительно + базиса фазного амплитудного значения, например, 220*sqrt(2) + Теперь производится переход, где за единицу принимается максимально + реализуемое напряжение (длина базового вектора) + */ + p->UalphaNorm=_IQmpy(p->UalphaNorm,_IQ(0.866)); + p->UbetaNorm=_IQmpy(p->UbetaNorm,_IQ(0.866)); +} + + + +//! Функция 6ти секторной векторной ШИМ + +//! \memberof TPWM_Module +void PWM_Module_No_SV_Update(TPWM_Module *p) { + _iq lambda1; + _iq lambda2; + _iq lambda3; + + int16 gamma; + int16 gamma1; + long tmp_pwm; + + //Присвоение трех уставок сравнения только если счетчик таймера далек от нуля, чтобы + //предотвратить частичное применение скважностей, что в векторной ШИМ может быть критично и испортить период ШИМ. + DINT; + if (PWM0->TBCTR>30) { + PWM0->CMPA_bit.CMPA=(Uint16)p->GammaA; + PWM1->CMPA_bit.CMPA=(Uint16)p->GammaB; + PWM2->CMPA_bit.CMPA=(Uint16)p->GammaC; + } + EINT; + + PWM_Module_NormInput(p); + + //Расчет скважностей по методу Изосимова. + //Подробнее см. диссертацию Чуева П.В. http://motorcontrol.ru/wp-content/uploads/2015/11/Chuev_vector_control.pdf + tmp_pwm = _IQmpy(_1_SQRT3,p->UbetaNorm); /*делим на корень из 3*/ + lambda1 = _IQmpy(p->k_pwm,(p->UalphaNorm - tmp_pwm)); + lambda2 = _IQmpy(p->k_pwm,2*tmp_pwm); + lambda3 = _IQmpy(p->k_pwm,p->UalphaNorm + tmp_pwm); + + + if (lambda1<=0) + if (lambda3>0) { + gamma=lambda3; + gamma1=-lambda1; + p->sector=1; /*110 начало */ + p->GammaA=p->k_pwm-gamma; + p->GammaB=p->k_pwm-(gamma+gamma1+1); + p->GammaC=p->k_pwm-0; + + } else if (lambda2>0) { + gamma=lambda2; + gamma1=-lambda3; + p->sector=2; /*011 начало */ + p->GammaA=p->k_pwm-0; + p->GammaB=p->k_pwm-(gamma+gamma1+1); + p->GammaC=p->k_pwm-gamma1; + /*011 начало */ + } else if (lambda1!=0) { + gamma=-lambda1; + gamma1=-lambda2; + p->sector=3; /*011 начало */ + p->GammaA=p->k_pwm-0; + p->GammaB=p->k_pwm-gamma; + p->GammaC=p->k_pwm-(gamma+gamma1+1); + /*011 начало */ + } else { + gamma=-lambda3; + gamma1 = lambda1; + p->sector= 4; /*101 начало */ + p->GammaA=p->k_pwm-gamma1; + p->GammaB=p->k_pwm-0; + p->GammaC=p->k_pwm-(gamma+gamma1+1); + /*101 начало */ + + } + else if (lambda2>0) { + gamma=lambda1; + gamma1=lambda2; + p->sector= 0; /*110 начало */ + p->GammaA=p->k_pwm-(gamma+gamma1+1); + p->GammaB=p->k_pwm-gamma1; + p->GammaC=p->k_pwm-0; + /*110 начало */ + } else if (lambda3<0) { + gamma=-lambda3; + gamma1 = lambda1; + p->sector= 4; /*101 начало */ + p->GammaA=p->k_pwm-gamma1; + p->GammaB=p->k_pwm-0; + p->GammaC=p->k_pwm-(gamma+gamma1+1); + /*101 начало */ + } else { + gamma=-lambda2; + gamma1=lambda3; + p->sector=5; /*101 начало */ + p->GammaA=p->k_pwm-(gamma+gamma1+1); + p->GammaB=p->k_pwm-0; + p->GammaC=p->k_pwm-gamma; + /*101 начало */ + } + + + /*насыщения */ + + if (p->GammaA<0) p->GammaA=0; + if (p->GammaB<0) p->GammaB=0; + if (p->GammaC<0) p->GammaC=0; + + if (p->GammaA>p->k_pwm) p->GammaA=p->k_pwm+1; + if (p->GammaB>p->k_pwm) p->GammaB=p->k_pwm+1; + if (p->GammaC>p->k_pwm) p->GammaC=p->k_pwm+1; + + //Присвоение трех уставок сравнения только если счетчик таймера далек от нуля, чтобы + //предотвратить частичное применение скважностей, что в векторной ШИМ может быть критично и испортить период ШИМ. + //Второй раз - чтобы предотвратить ситуацию с постоянной "незагрузкой" при равенстве частот расчета и ШИМ + DINT; + if (PWM0->TBCTR>30) { + PWM0->CMPA_bit.CMPA=(Uint16)p->GammaA; + PWM1->CMPA_bit.CMPA=(Uint16)p->GammaB; + PWM2->CMPA_bit.CMPA=(Uint16)p->GammaC; + } + EINT; +} + +//! Функция синусоидальной ШИМ + +//! \memberof TPWM_Module +void PWM_Module_Sin_Update(TPWM_Module *p) { + _iq PhasePtsA; + _iq PhasePtsB; + _iq PhasePtsC; + _iq knorm; + + + p->UalphaNorm = p->UalphaRef; + p->UbetaNorm = p->UbetaRef; + + //находим амплитуду (без учета ограничения) + p->U_mag = _IQmag(p->UalphaNorm, p->UbetaNorm); + + /* рассчитываем амплитуду вектора, который хотим отработать*/ + knorm = _IQmag(p->UalphaNorm, p->UbetaNorm); + if (knorm >= p->U_lim) { //он больше, чем наше ограничение? + knorm = _IQdiv(p->U_lim, knorm); //в эту же переменную, для экономии, рассчитываем нормировку + p->UalphaNorm = _IQmpy(knorm, p->UalphaNorm); //уменьшаем пропорционально нормировке + p->UbetaNorm = _IQmpy(knorm, p->UbetaNorm); //и это + p->ULimitation = 1; //флаг о том, что идет ограничение напряжения + } else + p->ULimitation = 0; + + //Нормирование входного напряжения. Так как синусоидальная ШИМ формирует на 0.866 меньшее напряжение, + //чем векторная ШИМ (270В амплитудного фазного напряжения вместо 311В), то для того, чтобы при том же задании в переменных + //p->UalphaNorm, p->UbetaNorm получилось то же самое напряжение на выходе, что и в векторной ШИМ, нужно задания увеличить в 1/0.866 раз. + //Деление на два нужно для последующих формул, чтобы переменые менялись в половинном от максимального диапазоне. + p->UalphaNorm = _IQmpy(p->UalphaNorm, _IQ(1/0.866/2)); + p->UbetaNorm = _IQmpy(p->UbetaNorm, _IQ(1/0.866/2)); + + /*фазное преобразование из системы альфа, бетта в a,b,c */ + + PhasePtsA = _IQ(0.5) - (p->UalphaNorm); + PhasePtsB = _IQ(0.5) - (_IQmpy(p->UbetaNorm,_IQ(0.8660254)) - (p->UalphaNorm >> 1)); + PhasePtsC = _IQ(0.5) - (-_IQmpy(p->UbetaNorm, _IQ(0.8660254)) - (p->UalphaNorm >> 1)); + + p->GammaA = _IQmpy(p->k_pwm, PhasePtsA); + p->GammaB = _IQmpy(p->k_pwm, PhasePtsB); + p->GammaC = _IQmpy(p->k_pwm, PhasePtsC); + + /*насыщения */ + + if (p->GammaA < 0) + p->GammaA = 0; + if (p->GammaB < 0) + p->GammaB = 0; + if (p->GammaC < 0) + p->GammaC = 0; + + if (p->GammaA > p->k_pwm) + p->GammaA = p->k_pwm + 1; + if (p->GammaB > p->k_pwm) + p->GammaB = p->k_pwm + 1; + if (p->GammaC > p->k_pwm) + p->GammaC = p->k_pwm + 1; + + + PWM0->CMPA_bit.CMPA = (Uint16) p->GammaA; + PWM1->CMPA_bit.CMPA = (Uint16) p->GammaB; + PWM2->CMPA_bit.CMPA = (Uint16) p->GammaC; + +} + +//! Функция ШИМ с раздельными фазами (для модели SRM) + +//! \memberof TPWM_Module +void PWM_Module_Separate_Update(TPWM_Module *p) { + _iq PhasePtsA; + _iq PhasePtsB; + _iq PhasePtsC; + _iq knorm; + + p->UPhARef = _IQmpy(p->UPhARef, _IQ(0.5)); + p->UPhBRef = _IQmpy(p->UPhBRef, _IQ(0.5)); + p->UPhCRef = _IQmpy(p->UPhCRef, _IQ(0.5)); + + PhasePtsA = _IQ(0.5) - p->UPhARef; + PhasePtsB = _IQ(0.5) - p->UPhBRef; + PhasePtsC = _IQ(0.5) - p->UPhCRef; + + p->GammaA = _IQmpy(p->k_pwm, PhasePtsA); + p->GammaB = _IQmpy(p->k_pwm, PhasePtsB); + p->GammaC = _IQmpy(p->k_pwm, PhasePtsC); + + /*насыщения */ + + if (p->GammaA < 0) + p->GammaA = 0; + if (p->GammaB < 0) + p->GammaB = 0; + if (p->GammaC < 0) + p->GammaC = 0; + + if (p->GammaA > p->k_pwm) + p->GammaA = p->k_pwm + 1; + if (p->GammaB > p->k_pwm) + p->GammaB = p->k_pwm + 1; + if (p->GammaC > p->k_pwm) + p->GammaC = p->k_pwm + 1; + + PWM0->CMPA_bit.CMPA = (Uint16) p->GammaA; + PWM1->CMPA_bit.CMPA = (Uint16) p->GammaB; + PWM2->CMPA_bit.CMPA = (Uint16) p->GammaC; + +} + +//! Функция ШИМ для начальной зарядки будстрепных конденсаторов инвертора + +//! \memberof TPWM_Module +void PWM_Module_ChargingMode(TPWM_Module *p) { + p->GammaA = p->k_pwm; + p->GammaB = p->k_pwm; + p->GammaC = p->k_pwm; + + DINT; + if (PWM0->TBCTR > 30) { + PWM0->CMPA_bit.CMPA = (Uint16) p->GammaA; + PWM1->CMPA_bit.CMPA = (Uint16) p->GammaB; + PWM2->CMPA_bit.CMPA = (Uint16) p->GammaC; + } + EINT; +} + +//! Общая функция-обертка для расчета ШИМ + +//Вызывающает ту версию ШИМ (ту функцию), что выбрана в настройках. + +//! \memberof TPWM_Module +void PWM_Module_Update(TPWM_Module *p) { + + if (p->ChargingMode) + PWM_Module_ChargingMode(p); + else { + switch (p->PWM_type) { + case PWM_TYPE_6SECT_NO_SV: { + PWM_Module_No_SV_Update(p); + break; + } + case PWM_TYPE_SIN_PWM: { + PWM_Module_Sin_Update(p); + break; + } + case PWM_TYPE_SRD: { + PWM_Module_Separate_Update(p); + break; + } + } + } + +} + +//! Медленный расчет + +//! Пересчитываются введенные пользователем величины +//! Величина мертвого времени, частота ШИМ и т.п. + +//! \memberof TPWM_Module +void PWM_Module_SlowCalc(TPWM_Module *p) { + Uint16 tmp; + //проверка ограничений величины мертвого времени + if (p->DeadBand < DEAD_BAND_MIN) + p->DeadBand = DEAD_BAND_MIN; + if (p->DeadBand > DEAD_BAND_MAX) + p->DeadBand = DEAD_BAND_MAX; + //пересчет МВ из формата IQ в мкс в такты таймера на 100мГц + PWM0->DBRED = _IQ4mpy(_IQ4(100), p->DeadBand >> 20) >> 4; + //во все ключи то же самое + PWM0->DBFED = PWM0->DBRED; + + PWM1->DBFED = PWM0->DBRED; + PWM1->DBRED = PWM0->DBRED; + PWM2->DBFED = PWM0->DBRED; + PWM2->DBRED = PWM0->DBRED; + + if (p->MinGammaLimit < DEAD_BAND_MIN) + p->MinGammaLimit = GAMMA_LIMIT_MIN; + if (p->MinGammaLimit > DEAD_BAND_MAX) + p->MinGammaLimit = GAMMA_LIMIT_MAX; + PWM0->FWDTH = _IQ4mpy(_IQ4(100), p->MinGammaLimit >> 20) >> 4; + PWM1->FWDTH = PWM0->FWDTH; + PWM2->FWDTH = PWM0->FWDTH; + //частота ШИМ. Смена "на лету". + if (p->FreqPrev != p->Frequency) { //сменили частоту + DINT; //запрещение прерываний + //проверка максимума/минимума + if (p->Frequency < PWM_FREQ_MIN) + p->Frequency = PWM_FREQ_MIN; + if (p->Frequency > PWM_FREQ_MAX) + p->Frequency = PWM_FREQ_MAX; + //изменяем период + p->k_pwm = _IQ10div(_IQ10(SystemCoreClock/1000.0), p->Frequency << 1) >> 10; //период + PWM0->TBPRD = p->k_pwm; + //для всех стоек то же самое + PWM1->TBPRD = p->k_pwm; + PWM2->TBPRD = p->k_pwm; + + + //посчитаем длину выборки для усреднения токов, исходя из частоты ШИМ + adc.IASampleLength = (p->Frequency >> 10) / 10; //Частота ШИМ в формате 22.10, приводим к инту и делим на 10 - частоту расчета системы управления + if (adc.IASampleLength > 4) //не более 4 точек + adc.IASampleLength = 4; + if (adc.IASampleLength < 1) //не менее 1 точки + adc.IASampleLength = 1; + adc.IBSampleLength = adc.IASampleLength; + adc.ICSampleLength = adc.IASampleLength; + adc.UdcSampleLength = adc.IASampleLength; + + p->FreqPrev = p->Frequency; //предыдущая частота + EINT; + } +} + +//! Функция включения ШИМ (включение инвертора) + +//! \memberof TPWM_Module +void PWM_Module_On(TPWM_Module *p) { + p->Enabled = 1; //флаг "включено" + + // Снимаем принудительную установку выходов + PWM0->TZCLR_bit.OST = 1; + PWM1->TZCLR_bit.OST = 1; + PWM2->TZCLR_bit.OST = 1; +} + +//! Функция выключения ШИМ (выключение инвертора) + +//! \memberof TPWM_Module +void PWM_Module_Off(TPWM_Module *p) { + + p->Enabled = 0; //флаг "выключено" + // Принудительно обнулим все ножки + PWM0->TZFRC_bit.OST = 1; + PWM1->TZFRC_bit.OST = 1; + PWM2->TZFRC_bit.OST = 1; +} + +/*@}*/ diff --git a/Vsrc/V_QEP.c b/Vsrc/V_QEP.c new file mode 100644 index 0000000..2a8e7d6 --- /dev/null +++ b/Vsrc/V_QEP.c @@ -0,0 +1,318 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_QEP.c + \brief Модуль оценки скорости и положения при помощи eQEP (см. TposspeedEqep) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup V_QEP + @{*/ + +#include "DSP.h" +#include "V_IQmath.h" +#include "V_QEP.h" +#include "math.h" +#include "stdlib.h" +#include "main.h" + +#define FIRST_LAUNCH_UP 1//!< первый пуск при переходе с низкой скорости на более высокую +#define NOT_FIRST_LAUNCH 0//!< не первый пуск +#define SCALE_IQ_K 10 +#define LOWEST_UPSS 0 + + +//Как рассчитывать скорость - +//Таймеров QEP между метками аппаратно +#define SPEED_CALC_TYPE_BY_QEP 0 +//Программно по производной угла +#define SPEED_CALC_TYPE_BY_SOFT 1 + + +//! Инициализация + +//! \memberof TposspeedEqep +void TposspeedEqep_init(TposspeedEqep *p) { + + QEP->QCAPCTL_bit.UPPS = LOWEST_UPSS; + QEP->QCAPCTL_bit.CCPS = 4; + QEP->QDECCTL_bit.QSRC = 0; //Вкл. режим квадратурного счёта + QEP->QEPCTL_bit.FREESOFT = 0; //Режим отладчика + QEP->QPOSINIT = 0; //Значение счётчика положения после инициализации или положительного переполнения + QEP->QEPCTL_bit.SWI = 1; //Сброс счётчика + QEP->QPOSMAX = (p->resol << 2) - 1; //Максимальное значение счётчика, после чего обнуление + if (p->Posspeed_CTL.bit.dir == 1) { //Проверка направления движения + QEP->QDECCTL_bit.QAP = 1; + } + + QEP->QEPCTL_bit.QPEN = 1; //Вкл. квадратурного счётчика + QEP->QCLR = 0xFFFF; //Отчистка всех флагов + QEP->QEPCTL_bit.QCLM = 0; //Режим захвата - по умолчанию, по событию отработки заданного числа импульсов + + if (p->Posspeed_CTL.bit.index_en == 1) { //если индексная метка есть + QEP->QEPCTL_bit.PCRM = 0; + QEP->QEINT_bit.IEL = 1; + } else { + QEP->QEPCTL_bit.PCRM = 1; //Режим обнуления счётчика - по максимальному значению + } + QEP->QWDPRD = 200000 / (1 << 2); //Ввод периода сторожевого таймера + QEP->QEPCTL_bit.WDE = 1; //Вкл. сторожевого таймера + + /*Расчёт вспомогательного коэффициента для расчёта скорости, + где 15=60/4, 60 - для перевода в об/мин; 4 - для получения интерполяции разрешения датчика (1 период дает 4 фронта); + SystemCoreClock - частота процессора*/ + p->k_low = SystemCoreClock / ((float) p->resol * p->speed_nom) * 15.0; + //В iq формате уменьшаем число в 1<<(24-SCALE_IQ_K), где 24 - дробная часть iq, а SCALE_IQ_K - то, насколько сдвигается величина + //с которой speedK дальше участвует в формуле + p->speedK = _IQ(p->k_low / (1 << (24 - 10))); + + p->resol_inv = 1.0 / ((float) p->resol); + + //Инициализация портов ввода вывода + GPIOB->ALTFUNCSET = (1 << 11) + (1 << 12) + (1 << 13); + SIU->REMAPAF_bit.QEPEN = 1; + GPIOB->DENSET = (1 << 11) + (1 << 12) + (1 << 13);//для приема ножки апп. аварии разрешаем работу ножки как цифры +} + +//! Функция расчёта скорости и положения, вызывается с необходимой дискретностью + +//! \memberof TposspeedEqep +void TposspeedEqep_Calc(TposspeedEqep *p) { + long temp; + //Текущее значение GPIO для отладки. Можно смотреть в осцах + p->GPIOsValue = (GPIOB->DATA >> 12) & 3; + + //если скорость высокая, а делитель UPEVNT не высокий + if ((labs(p->speed_elec) > _IQ(2)) && (QEP->QCAPCTL_bit.UPPS != 5)) { + QEP->QCAPCTL_bit.UPPS = 5; //делаем делитель UPEVNT высокий + p->skip_counter = 2; //два такта пропустим расчет скорости + } + + //если скорость низкая, а делитель не низкий + if ((labs(p->speed_elec) < _IQ(1.5)) && (QEP->QCAPCTL_bit.UPPS != LOWEST_UPSS)) { + QEP->QCAPCTL_bit.UPPS = LOWEST_UPSS; //делаем делитель UPEVNT низкий + p->skip_counter = 2; //два такта пропустим расчет скорости + } + + p->UPPS_forWatch = QEP->QCAPCTL_bit.UPPS; //для отображения UPPS наружу + + if (p->Posspeed_CTL.bit.CmdInit == 1) { //Команда переинициализации - все обнуляем + QEP->QEPCTL_bit.SWI = 1; + p->Posspeed_FLG1.bit.first_theta = 1; + p->Posspeed_FLG2.bit.pos_ident = 0; + p->Posspeed_CTL.bit.CmdInit = 0; + p->theta_elec = 0; + p->Poscnt_res = 0; + } + p->Poscnt_resPrev=p->Poscnt_res; + p->Poscnt_res = (unsigned long) QEP->QPOSCNT; //захват положения + + + p->Poscnt_res16=p->Poscnt_res;//Для наблюдения на осциллографе + p->Posspeed_FLG1.bit.PCO_tmp = QEP->QFLG_bit.PCO; //копия флага положительного переполнения счётчика + p->Posspeed_FLG1.bit.PCU_tmp = QEP->QFLG_bit.PCU; //копия флага отрицательного переполнения счётчика + QEP->QCLR_bit.PCO = 1; //отчистка флага положительного переполнения счётчика + QEP->QCLR_bit.PCU = 1; //отчистка флага отрицательного переполнения счётчика + + //перевод угла в метках на обороте в механический угол + //Здесь расчет во float - желательно переделать в IQ + p->theta_mech = _IQ((float )p->Poscnt_res * p->resol_inv * 0.25); //расчёт механического угла + p->theta_mech &= 0x00FFFFFF; + + + // Подсчёт количества полных оборотов. Через PCO и PCU получается как-то глючно + if (p->prevThetaMech - p->theta_mech > _IQ(0.5)) + p->RevolutionCounter++; + if (p->prevThetaMech - p->theta_mech < _IQ(-0.5)) + p->RevolutionCounter--; + p->prevThetaMech=p->theta_mech; + + //угол в метках без обнуления на обороте, абсолютный + p->Poscnt_resContinouosLong=p->Poscnt_res+((QEP->QPOSMAX+1)*p->RevolutionCounter); + p->Poscnt_resContinouosInt=p->Poscnt_resContinouosLong;//чтобы было уднобно смотреть в 16ти разрядном осциллографе + p->Poscnt_resContinouosInt8=p->Poscnt_resContinouosLong&0xF;//чтобы видеть метки в крупном масштабе + + + //перевод угла в метках абсолютных (не обнуляемых наобороте) в механический угол + //на 127 оборотах всё переполнится, но для демо сгодится + p->theta_mechContinouos = _IQ((float )p->Poscnt_resContinouosLong * p->resol_inv * 0.25); //расчёт механического угла + p->theta_elecContinouos = p->theta_mechContinouos*p->pole_pairs+ p->AngleOffset;//электрический угол абсолютный (не обнуляемый) + + //Расчёт электрического положения обнулемого по достижению 360 градусов + p->theta_el_tmp = p->theta_mech*p->pole_pairs + p->AngleOffset; + p->theta_elec = p->theta_el_tmp & 0x00FFFFFF; + + //рассчитывать скорость аппаратно, засекая время между метками средствами QEP + if (p->SpeedCalcType==SPEED_CALC_TYPE_BY_QEP){ + + /*Проверка на срабатывание сторожевого таймера - не пришло не единого импульса*/ + if (QEP->QFLG_bit.WTO == 1) { + p->Posspeed_FLG1.bit.first_launch = FIRST_LAUNCH_UP; //указатель первого запуска алгоритма после срабатывания таймера + p->speed_elec = 0; //обнуление скорости + QEP->QCLR_bit.WTO = 1; //отчистка флага + QEP->QWDTMR = 0; //обнуление таймера + } else { + /*переключение по первому запуску для инициализации*/ + if (p->Posspeed_FLG1.bit.first_launch == FIRST_LAUNCH_UP) { + //Откл. блока захвата + QEP->QCAPCTL_bit.CEN = 0; + QEP->QCAPCTL_bit.CEN = 1; + p->Posspeed_FLG1.bit.first_launch = NOT_FIRST_LAUNCH; + } + + p->QEPSTS=QEP->QEPSTS;//копия регистра статуса + + if (p->QEPSTS_bit.UPEVNT == 1) { //есть событие UPEVNT, значит в таймере захвачено время + p->Qcprdlat_tmp = QEP->QCPRD; //копия счетчика времени + p->speed_calc_skip = 0; //пропуск расчета скорости - не пропускать + + if (p->QEPSTS_bit.COEF == 1) { //проверка флага переполнения таймера + p->speed_elec = 0; + p->speed_calc_skip = 1; //пропустить расчет скорости + QEP->QEPSTS = 1 << 3; + } + + if (p->QEPSTS_bit.CDEF == 1) { //проверка на изменения направления движения во время захвата + p->speed_elec = 0; + p->speed_calc_skip = 1; //пропустить расчет скорости + QEP->QEPSTS = 1 << 2; + } + + if (p->Qcprdlat_tmp<7){//ложный фронт + p->speed_calc_skip = 1; //пропустить расчет скорости + } + + if (p->QEPSTS_bit.QDF!=p->DirPrev){//сменилось направление движения + p->speed_elec = 0; + p->speed_calc_skip = 1; //пропустить расчет скорости + } + p->DirPrev=p->QEPSTS_bit.QDF; + + if (p->skip_counter != 0) { //Сменился UPPS + p->skip_counter--; + p->speed_calc_skip = 1; //пропустить расчет скорости + } + + + if (p->Qcprdlat_tmp > ((1<<(32-SCALE_IQ_K-1)))) { //Счетчик 32 разряда, а драйвер предназначен для меньшего числа, определяемого SCALE_IQ_K + p->speed_elec = 0; + p->speed_calc_skip = 1; //пропустить расчет скорости + } + + if (!p->speed_calc_skip) { //если расчет скорости пропускать не надо + if (p->QEPSTS_bit.QDF == 1) //в зависимости от направления движения + p->speed_tmpIQ = _IQdiv(p->speedK, p->Qcprdlat_tmp << SCALE_IQ_K); //коэффициет скорости делется на 16ти разрядное время, подвинутое вверх на 15 + else + p->speed_tmpIQ = -_IQdiv(p->speedK, p->Qcprdlat_tmp << SCALE_IQ_K); + + //На сколько нужно подвинуть результат в зависимости от + //делителей на UPEVNT и тактировании счетчика времени + p->MoveK = QEP->QCAPCTL_bit.UPPS + - QEP->QCAPCTL_bit.CCPS; + + if (p->MoveK >= 0) //надо подвинуть вверх + p->speed_tmpIQ = p->speed_tmpIQ << p->MoveK; + else + //вниз + p->speed_tmpIQ = p->speed_tmpIQ >> -p->MoveK; + p->speed_elec = p->speed_tmpIQ; //готовая скорость в формате 8.24 + } + + QEP->QEPSTS = 1 << 7; + } + else if (QEP->QCTMR > QEP->QCPRD) + { //нет события UPEVNT, считаем по таймеру QCTMR, а не по периоду QCPRD + p->Qcprdlat_tmp = QEP->QCTMR; //копия счетчика + + if (p->QEPSTS_bit.COEF == 1) { //проверка флага переполнения таймера + p->speed_elec = 0; + p->speed_calc_skip = 1; //пропустить расчет скорости + } + + if (p->QEPSTS_bit.CDEF == 1) { //проверка на изменения направления движения во время захвата + p->speed_elec = 0; + p->speed_calc_skip = 1; //пропустить расчет скорости + } + if (p->Qcprdlat_tmp<7){//ложный фронт + p->speed_calc_skip = 1; //пропустить расчет скорости + } + + if (p->Qcprdlat_tmp > ((1<<(32-SCALE_IQ_K-1)))) { //Счетчик 32 разряда, а драйвер предназначен для меньшего числа, определяемого SCALE_IQ_K + p->speed_elec = 0; + p->speed_calc_skip = 1; //пропустить расчет скорости + } + + if (!p->speed_calc_skip) { //если расчет скорости пропускать не надо + if (p->QEPSTS_bit.QDF == 1) //в зависимости от направления движения + p->speed_tmpIQ = _IQdiv(p->speedK, p->Qcprdlat_tmp << SCALE_IQ_K); //коэффициет скорости делется на 16ти разрядное время, подвинутое вверх на 15 + else + p->speed_tmpIQ = -_IQdiv(p->speedK, p->Qcprdlat_tmp << SCALE_IQ_K); + + //На сколько нужно подвинуть результат в зависимости от + //делителей на UPEVNT и тактировании счетчика времени + p->MoveK = QEP->QCAPCTL_bit.UPPS + - QEP->QCAPCTL_bit.CCPS; + + if (p->MoveK >= 0) //надо подвинуть вверх + p->speed_tmpIQ = p->speed_tmpIQ << p->MoveK; + else + //вниз + p->speed_tmpIQ = p->speed_tmpIQ >> -p->MoveK; + p->speed_elec = p->speed_tmpIQ; //готовая скорость в формате 8.24 + } + } + } + + } + + //рассчитывать скорость программно через производную угла + if (p->SpeedCalcType==SPEED_CALC_TYPE_BY_SOFT){ + //Сначала легкий фильтр на сам угол + //0.5 и маски - это магия нечувствительности фильтра к разнице углов больше 360 + //Чтобы при обнулении угла при переходе через 360 градусов при + //вычитании из 5 градусов 355 получилось 10 (в IQ формате) + p->theta_finish=p->theta_finish+_IQmpy(_IQ(0.5),((p->theta_elec-p->theta_finish+_IQ(0.5))&0x00FFFFFF)-_IQ(0.5)); + p->theta_finish&=0x00FFFFFF; + //расчитываем приращение угла + temp = (p->theta_finish << 8) - (p->theta_start << 8); + p->d_fi = (temp >> 8); + p->theta_start = p->theta_finish; + + //скорость нефильтрованная, рассчитанная из производной угла за один период + p->speed_elec_temp=_IQmpy(p->d_fi,p->KThetaToSpeed)<<3; + + //инерционный фильтр для скорости + p->speed_filter.input = p->speed_elec_temp; + p->speed_filter.calc(&p->speed_filter); + p->speed_elec=p->speed_filter.output; + } +} + +//! Функция обработки репера (событие индекса) + +//! \memberof TposspeedEqep +void TposspeedEqep_IndexEvent(TposspeedEqep *p) { + p->Posspeed_FLG2.bit.pos_ident = 1; +} + +//! \memberof TposspeedEqep +void TposspeedEqep_SlowCalc(TposspeedEqep *p) { + //коэффициент перевода производной от угла (вычисляемую неизвестно в чем) в скорость + //сдвиг на 3 чтобы результат деления не переполнил 127, потом при использовании коэфа + //сдвинется назад на 3 + p->KThetaToSpeed=_IQdiv(_IQ(1.0),_IQmpyI32(drv_params.freq_nom,FAST_CALC_TS)<<3); +} +/*@}*/ + diff --git a/Vsrc/V_RTC_Clock.c b/Vsrc/V_RTC_Clock.c new file mode 100644 index 0000000..5189ce9 --- /dev/null +++ b/Vsrc/V_RTC_Clock.c @@ -0,0 +1,206 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_RTC_Clock.c + \brief Модуль для работы с часами реального времени + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + */ + +/* + + * + * Часы DS1340 работают в режиме слэйва и имеют 10 регимтров данных/контроля (0x0 ... 0x9). + * Время и дата лежат в регистрах 0x0 ... 0x6. + * Регистр контроля часов, регистр заряда акк., и регистр флагов лежат в 0x7 ... 0x9. + * Указатель на текущий регистр можно поменять, отправив в часы соответствующий номер . + * Чтобы прочитать что-то из часов, сначала нужно обратиться к часам в режиме записи и передать номер + * регистра, с которого нужно считать данные. После этого снова нужно обратиться к часам, но уже + * в режиме чтения. Тогда часы начнут слать содержимое всех регистров по очереди, начиная с того + * регистра, адрес которого был передан в предыдущем обращении. При такой "потоковой" передаче + * указатель на текущий регистр будет автоинкрементироваться, причем в такой последовательности + * (предположим, был установлен адрес 0x5) + * 0x5 -> 0x6 -> 0x7 -> 0x0 -> 0x1 -> ... -> 0x7 -> 0x0 + * Чтобы попасть в последние два регистра, нужно передать их адреса явно. + * + * Для того, чтобы записать в часики время, нужно проделать примерно то же самое. + * В режиме записи отправляется сначала номер регистра, в который нужно записать что-то, а затем + * данные, которые нужно туда положить. Указатель на регистры при потоковой передаче инкрементируется + * так же, как и при чтении. + * + * Данные хранятся в двоично-десятичном формате. + */ + +//Закомменченные функции вверху отличаются от нижних регистрами (NT_RTC и RTC_REG). Нужны ли закомменченные - не знаю. +#include +#include +// Включатель постоянного считывания времени с ЧРВ. Если дефайн закоменчен - считывание производится только при запуске, а потом +// время считается программно. Если раскомменчен - каждую секунду время считается с часов (секунда отсчитывается в мс) +//#define USE_RTC + +/* Инициализация RTC */ +void RTC_Clock_Init(TRTCClock *p) { + +} + +/* Функция считывания текущего времени */ +void RTC_Clock_Read_Time(TRTCClock *p) { +// Uint16 tempSec, tempMin, tempHour, tempDOW, tempDay, tempMonth, tempYear; +// +// /* Остановить обновление теневых регисторв */ +// NT_RTC->SHDW = 0x0; +// +// /* Прочитать время */ +// tempSec = NT_RTC->SECOND; +// tempMin = NT_RTC->MINUTE; +// tempHour = NT_RTC->HOUR; +// tempDOW = NT_RTC->WDAY; +// tempDay = NT_RTC->DAY; +// tempMonth = NT_RTC->MONTH; +// tempYear = NT_RTC->YEAR; +// +// /* Запустить обновление теневых регисторв */ +//// NT_RTC->SHDW = 0x80; +// +// // Затем нужно отформатировать пришедшие данные, т.к. они приходят в виде двоично-десятичных чисел (отстой) +// p->second = (tempSec & 0xF) + (((tempSec & 0x70) >> 4) * 10); +// p->minute = (tempMin & 0xF) + (((tempMin & 0x70) >> 4) * 10); +// p->hour = (tempHour & 0xF) + (((tempHour & 0x30) >> 4) * 10); +// p->DOW = (tempDOW & 0x7); +// p->day = (tempDay & 0xF) + (((tempDay & 0x30) >> 4) * 10); +// p->month = (tempMonth & 0xF) + (((tempMonth & 0x10) >> 4) * 10); +// p->year = (tempYear & 0xF) + (((tempYear & 0xF0) >> 4) * 10); +// +// // Наконец, упаковка основных показателей в структурку +// p->packed_time = ((Uint32) p->day << 27) + ((Uint32) p->month << 23) +// + ((Uint32) p->year << 17) + ((Uint32) p->hour << 12) +// + ((Uint32) p->minute << 6) + (Uint32) p->second; + +} + +/* Функция установки времени */ +void RTC_Clock_Set_Time(TRTCClock *p) { +// // Временные переменные (секунды, минуты, часы...) +// unsigned char tempSec, tempMin, tempHour, tempDOW, tempDay, tempMonth, +// tempYear; +// p->tryCounter = 0; +// +// // Сначала нужно распаковать дату +// p->second = p->timeToSet & 0x3F; +// p->minute = (p->timeToSet >> 6) & 0x3F; +// p->hour = (p->timeToSet >> 12) & 0x1F; +// p->year = (p->timeToSet >> 17) & 0x3F; +// p->month = (p->timeToSet >> 23) & 0xF; +// p->day = (p->timeToSet >> 27) & 0x1F; +// +// tempSec = ((p->second / 10) << 4) + ((p->second % 10) & 0xF); +// tempMin = ((p->minute / 10) << 4) + ((p->minute % 10) & 0xF); +// tempHour = ((p->hour / 10) << 4) + ((p->hour % 10) & 0xF); +// tempDOW = p->DOW & 0x3; +// tempDay = ((p->day / 10) << 4) + ((p->day % 10) & 0xF); +// tempMonth = ((p->month / 10) << 4) + ((p->month % 10) & 0xF); +// tempYear = ((p->year / 10) << 4) + ((p->year % 10) & 0xF); +// +// p->msInDay = (Uint32) p->hour * 3600000 + (Uint32) p->minute * 60000 +// + (Uint32) p->second * 1000; +// +// // Расчёт дня недели (пижонство) +// int16 a = (14 - p->month) / 12; +// int16 y = p->year - a; +// int16 m = p->month + 12 * a - 2; +// p->DOW = (7000 + (p->day + y + y / 4 - y / 100 + y / 400 + (31 * m) / 12)) +// % 7; +// +// NT_RTC->YEAR = tempYear; +// NT_RTC->MONTH = tempMonth; +// NT_RTC->DAY = tempDay; +// NT_RTC->WDAY = tempDOW; +// NT_RTC->HOUR = tempHour; +// NT_RTC->MINUTE = tempMin; +// NT_RTC->SECOND = tempSec; +} + +void RTC_Clock_Ms_Calc(TRTCClock *p) { + p->ms++; + p->msInDay++; +#ifdef USE_RTC + if (p->ms > 999) { + p->ms = 0; + p->readTimeFlag = 1; + } + + //проверка работы часов реального времени и установка, в зависимсоти от этого, указателя для банка аварий + if (p->secondPrev == p->second) //секунда не меняется + p->stoppedCounter++; //считаем, как долго + else //сменилась, значит часы работают + p->stoppedCounter = 0; + + if ((p->stoppedCounter < RTC_SECOND_WAITING_TIMEOUT) && (p->year<48)) //часы работают - тикают и год не 2048 (как когда нет батарейки) + p->ClockOk=1; + + else + { + p->ClockOk=0; + p->stoppedCounter = RTC_SECOND_WAITING_TIMEOUT; + } + p->secondPrev = p->second; + + + + + +#else + + if (p->ms == 1000) { + p->ms = 0; + p->second++; + + if (p->second == 60) { + p->second = 0; + p->minute++; + if (p->minute == 60) { + p->minute = 0; + p->hour++; + if (p->hour == 24) { + p->hour = 0; + p->msInDay = 0; + p->day++; + } + } + } + p->packed_time = ((Uint32)p->day << 27) + ((Uint32)p->month << 23) + ((Uint32)p->year << 17) + + ((Uint32)p->hour << 12) + ((Uint32)p->minute << 6) + (Uint32)p->second; + } + +#endif + +} + +void RTC_Clock_Slow_Calc(TRTCClock *p) { + if (p->setTimeFlag == 1) { + p->timeToSet = p->packed_time; + p->set(p); + p->read(p); + p->msInDay = (Uint32) p->hour * 3600000 + (Uint32) p->minute * 60000 + + (Uint32) p->second * 1000; + p->setTimeFlag = 0; + } else if (p->readTimeFlag == 1) { + p->read(p); + p->readTimeFlag = 0; + } +} + + diff --git a/Vsrc/V_SSI_Encoder.c b/Vsrc/V_SSI_Encoder.c new file mode 100644 index 0000000..e6f239c --- /dev/null +++ b/Vsrc/V_SSI_Encoder.c @@ -0,0 +1,164 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_SSI_Encoder.c + \brief Модуль оценки скорости и положения при помощи цифрового энкодера, работающего по интерфейсу SSI (см. TSSI_Encoder) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 1.0 25/04/2016 + + \addtogroup V_QEP + @{*/ + +#include "DSP.h" +#include "V_IQmath.h" +#include "V_SSI_Encoder.h" +#include "math.h" +#include "stdlib.h" +#include "main.h" + +//! Инициализация + +//! \memberof TSSI_Encoder +void SSI_Encoder_init(TSSI_Encoder *p) { +// volatile long delay; +// volatile Uint32 tempREG; +// +// //SPI-SOMI - на VectorCard нога 88, на проце B15, SPI_RXD2 +// //SPI-SIMO - на VectorCard нога 38, на проце C6, SPI_TXD2 +// //SPI-CLK - на VectorCard нога 39, на проце B14, SPI_CLK2 +// //SPI-STE - на VectorCard нога 89, на проце B13, SPI_FSS2 +// //Плата texas DRV8301-HC-EVM разведена так, что микроконтроллер - это ведомое устройство. +// //Нужно сделать его мастером. Подробнее читайте комментарий в заголовочном файле. +// +// // Настройка ног SPI +// GPIOB->ALTFUNCSET = (1 << 13);//чип-селект +// GPIOB->ALTFUNCSET = (1 << 14) | (1 << 15); +// NT_GPIOC->ALTFUNCSET = (1 << 6);//SIMO +// NT_COMMON_REG->GPIOPCTLB_bit.PIN13 = 2;//чип-селект +// NT_COMMON_REG->GPIOPCTLB_bit.PIN14 = 2; +// NT_COMMON_REG->GPIOPCTLB_bit.PIN15 = 2; +// NT_COMMON_REG->GPIOPCTLC_bit.PIN6 = 2;//SIMO +// +// +// // Настройка тактирования SSP модуля +// // Всего 4 модуля, на каждый модуль по 8 бит из регистра SSP_CLK_CTRL и по два бита из UART_SSP_CLK_SEL +// +// // UART_SSP_CLK_SEL +// // Во втором байте слова на каждый из 4-ёх модулей SSP отводится по два бита для выбора источника тактирования 0x0000XX00 +// // "00" - в качестве иточника тактирования модуля SSP выбирается системная частота 100 МГц, таким образом f_SSP_IN = SysClk = 100 MHz +// +// // SSP_CLK_CTRL +// // Младший бит разрешает тактирование (1 - разрешить) +// // Второй бит разрешает деление частоты f_SSP_IN источника тактового сигнала (0 - не делить, 1 - делить) +// // Старшие шесть выбирают делитель частоты этого исотчника: +// // X - деление по формуле SSPclk = f_SSP_IN /( 2 * (X +1) ) +// // Из документации на блок SSP - минимальная частота для работы модуля в режимах и мастер и слейв, +// // f_SSP_IN > 22.12 MHz, поэтому 25 МГц сделаем +// /* закомменчены, так как тоже самое делается в DRV8301_SPI +// tempREG = NT_COMMON_REG->UART_SPI_CLK_SEL;// Через tempREG, чтобы не задеть другие биты, отвечающие за тактирование UART'a +// tempREG &= 0xFFFF00FF; +// NT_COMMON_REG->UART_SPI_CLK_SEL = tempREG; +// NT_COMMON_REG->SPI_CLK = 0x07070707;// Разрешить тактирование, разрешить деление частоты, делить на 4 - 25 МГц +// */ +// +// +// // Настройка самого модуля SPI +// // Продолжение настройки тактирования. +// // Полученная ранее частота f_SSP_IN проходит ещё через два делителя. +// // SSPCPSR - первый делитель, в диапазоне 2 ... 254, может быть только чётным (младший бит всегда хардварно равен 0) +// // SSPCR0.bit.SCR - второй делитель от 0 до 255. +// // Битрейт в итоге BitRate = f_SSP_IN / ( SSPCPSR * (SCR + 1) ) +// +// SPI2->SPI_CR1 = 0;// Режим - мастер, LoopBack отключён, сам модуль SSP тоже отключён +// SPI2->SPI_IMSC = 0x0; // Запретить все прерывания +// SPI2->SPI_DMACR = 0; // Запретить DMA +// SPI2->SPI_ICR = 0x3; // Очистка прерываний ("переполнение FIFO приёма" и "необслуженное FIFO приёма") +// +// SPI2->SPI_CPSR = 4; // Деление входной частоты на 4 -> 6,25 MHz +// SPI2->SPI_CR0_bit.DSS = 12; // Размер данных - 12 бит +// SPI2->SPI_CR0_bit.SCR = 0x3F; // Второй делитель +// SPI2->SPI_CR0_bit.FRF = 0x0; // Какая-то "фаза" для протокола Motorola SPI +// SPI2->SPI_CR0_bit.SPH = 0x1; // Какая-то "полярность" для протокола Motorola SPI +// SPI2->SPI_CR0_bit.SPO = 0x0; // Выбор формата кадра Motorola/TI/Microwire. "0" - по протоколу Motorola SPI +// SPI2->SPI_CR1_bit.SSE = 1; // Разрешить работу +// +// p->resol_inv = 1.0 / ((float) p->resol); +// +// p->read(p); +} + + +//! Функция расчёта скорости и положения, вызывается с необходимой дискретностью + +//! \memberof TSSI_Encoder +void SSI_Encoder_Calc(TSSI_Encoder *p) { + p->read(p); +} + + + +void SSI_Encoder_Read(TSSI_Encoder*p) { +// _iq theta_elec_temp; +// Uint16 Data_read=0; +// _iq theta_mech_temp; +// +// if (SPI2->SPI_SR_bit.BSY == 0){//SPI свободен +// Data_read = SPI2->SPI_DR;//код с датчика (число от 0 до resol) +// SPI2->SPI_DR = 0xff;//отправляем что угодно, главное, чтобы тактирование шло +// +// +// if (p->rotation_dir)//обратное направление вращения +// Data_read=(p->resol-1)-Data_read;//период - текущее +// p->Poscnt_res=Data_read; +// } +// +// //перевод угла в метках на обороте в механический угол +// //Здесь расчет во float - желательно переделать в IQ +// p->theta_mech = _IQ((float )p->Poscnt_res * p->resol_inv); //расчёт механического угла +// p->theta_mech &= 0x00FFFFFF; +// //Фильтр угла +// if (p->theta_mech_filterK!=0){ +// p->theta_mech_filtered=p->theta_mech_filtered+_IQmpy(p->theta_mech_filterK,((p->theta_mech-p->theta_mech_filtered+_IQ(0.5))&0x00FFFFFF)-_IQ(0.5)); +// p->theta_mech_filtered&=0x00FFFFFF; +// }else +// p->theta_mech_filtered=p->theta_mech; +// +// // Подсчёт количества полных оборотов. +// if (p->prevThetaMech - p->theta_mech_filtered > _IQ(0.5)) +// p->RevolutionCounter++; +// if (p->prevThetaMech - p->theta_mech_filtered < _IQ(-0.5)) +// p->RevolutionCounter--; +// p->prevThetaMech=p->theta_mech_filtered; +// +// //угол в метках без обнуления на обороте, абсолютный +// p->Poscnt_resContinouosLong=p->Poscnt_res+(p->resol*p->RevolutionCounter); +// p->Poscnt_resContinouosInt=p->Poscnt_resContinouosLong;//чтобы было уднобно смотреть в 16ти разрядном осциллографе +// p->Poscnt_resContinouosInt8=p->Poscnt_resContinouosLong&0xF;//чтобы видеть метки в крупном масштабе +// +// //перевод угла в метках абсолютных (не обнуляемых наобороте) в механический угол +// //на 127 оборотах всё переполнится, но для демо сгодится +// p->theta_mechContinouos = p->theta_mech_filtered + _IQ(p->RevolutionCounter); //расчёт механического угла +// p->theta_elecContinouos = p->theta_mechContinouos*p->pole_pairs+ p->AngleOffset;//электрический угол абсолютный (не обнуляемый) +// +// //Расчёт электрического положения обнулемого по достижению 360 градусов +// p->theta_el_tmp = p->theta_mech_filtered*p->pole_pairs + p->AngleOffset; +// p->theta_elec = p->theta_el_tmp & 0x00FFFFFF; + +} + + + +/*@}*/ + diff --git a/Vsrc/V_UserMemory.c b/Vsrc/V_UserMemory.c new file mode 100644 index 0000000..9d0cbdc --- /dev/null +++ b/Vsrc/V_UserMemory.c @@ -0,0 +1,132 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_UserMemory.c + \brief Работа с пользовательской энергонезависимой памятью 1921BK01 (см. TUserMemory) + \author Лашкевич М.М., Шпак Д.М. + \version v 1.0 18/12/2014 +*/ + +/** \addtogroup TUserMemory */ +/*@{*/ + +#include +#include "DSP.h" + + + + +//!Инициализация + +//!Инициализация USERMEMORY +//! \memberof TUserMemory +void USERMEMORY_Init(TUserMemory *p) +{ + I2C->CTL1_bit.ENABLE = 1; + I2C->CTL1_bit.SCLFRQ = 63; // Divider: 100 000 000 / (63 * 4) ~ 400 кГц + I2C->CTL3_bit.SCLFRQ = 0; // Divider + +} + + +//! Проверка, не нужно ли сменить страницу + +//! Проверяет текущий адрес на флешке, с которым работает пользователь. Если адрес вышел из текущей страницы, страница записывается на флеш и читается в RAM новый +//! \memberof TUserMemory +void USERMEMORY_UpdateCurrentPage(TUserMemory *p, Uint16 spiaddr) +{ + +} + + +//! Запись в память + +//!Медленная функция, записывающая на flash заданные данные. +//!Работает с закешированными в оперативке данными, а физическ пишет на флеш только если адрес вылез за границы текущей страницы + +//! Адрес во флеше spiaddr, адрес 16ти разрядных данных пользователя startaddr, размер data_length. Все в байтах +//! При выполении операции startaddr инкрементируется, а spiaddr нет +//! \memberof TUserMemory +void USERMEMORY_Write(TUserMemory *p) +{ + +} + + +//! Чтение из памяти + +//!Медленная функция, считывающая из flash заданные данные. Подробности см. TUserMemory. + +//! Адрес во флеше spiaddr, адрес адрес 16ти разрядных данных пользователя startaddr, размер data_length. Все в байтах. +//! При выполении операции startaddr инкрементируется, а spiaddr нет +//! \memberof TUserMemory +void USERMEMORY_Read(TUserMemory *p) +{ + +} + + +//! Записывает страницу данные на флешку из кеша (из оперативки одну страницу) + +//! \memberof TUserMemory +void USERMEMORY_WriteFromCache(TUserMemory *p, int16 pageNum) +{ + +} + + + +//! Читает страницу данных из флеша в кеш (в оперативку) + +//! \memberof TUserMemory +void USERMEMORY_ReadToCache(TUserMemory *p, int16 pageNum) +{ + +} + + +//! Стереть всю флешку (будут FF) + +//! \memberof TUserMemory +void USERMEMORY_Full_Erase(TUserMemory *p){ + +} + + +//! Сбросить кеш из оперативки на флешку + +//! \memberof TUserMemory +void USERMEMORY_Flush(TUserMemory *p){ +} + +//! Медленный фоновый постоянный расчет - нужен пока для систематического сброса кеша на флешку по времени + +//! \memberof TUserMemory +void USERMEMORY_slow_calc(TUserMemory *p){ +// } +} + +//! Миллисекундный расчет - нужен пока для систематического сброса кеша на флешку по времени + +//! \memberof TUserMemory +void USERMEMORY_ms_calc(TUserMemory *p){ + + +} + + + +/*@}*/ + diff --git a/Vsrc/V_adc.c b/Vsrc/V_adc.c new file mode 100644 index 0000000..ec409f6 --- /dev/null +++ b/Vsrc/V_adc.c @@ -0,0 +1,185 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_adc.c + \brief Модуль обработки АЦП (см. TAdcDrv) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup V_adc + @{*/ + + +#include "main.h" + +//!Инициализация. + +//! Настраиваются секвенсоры и тип оцифровки данных. каналы для оцифровки, частота. +//! В данном случае оцифровка происходит по событию таймера,частота которого +//! равна частоте ШИМ, чтобы измерять ровно посередине периода ШИМ (требуется для шунтовых +//! датчиков тока) +//Запуск оцифровки производится по таймеру NT_PWM3, который синхронизирован с другими таймерами ШИМ. +//Оцифрованные измерения складываются в ФИФО. Каждый канал АЦП настроен на отдельный секвенсор с ФИФО длиной до 16 измерений. +//В прерывании с частотой 10 кГц данные забираются из ФИФО и складываются в кольцевые массивы (старые затираются новыми). +//В том же прерывании из кольцевого массива берется N последних точек и из них вычисляется среднее арифметическое. +//Число выборок для усреднения N зависит от частоты ШИМ и равна Fшим/10кГц. Если частоты ШИМ меньше 10 кГц, то берется одна выборка, если больше 40 кГц - 4 выборки. +//К вычисленному среднему значению добавляется калибровочный сдвиг, и оно умножается на коэффициент измерения, в результате получается окончательный результат измерения. + +//! \memberof TAdcDrv +void AdcDrv_init(TAdcDrv *p) { + PWM0->ETSEL_bit.SOCAEN = 1; + PWM0->ETSEL_bit.SOCASEL = ET_CTR_ZERO; + PWM0->ETPS_bit.SOCAPRD = 2; + + Uint32 AdcClock, AdcDiv, trash; + Uint32 pwmPrd = PWM0->TBPRD; // Предположим, частота 10 кГц + + if (pwmPrd < 1000) pwmPrd = 1000; + //Инициализация ADC + RCU->ADCCFG_bit.CLKSEL = RCU_ADCCFG_CLKSEL_PLLCLK; // Тактирование от PLL + RCU->ADCCFG_bit.DIVN = 0x1; // N = 2 * (DIVN + 1) = 4 -> ACLK = 25 MHz + RCU->ADCCFG_bit.DIVEN = 0x1; // Разрешить делитель + AdcDiv = 2 * (RCU->ADCCFG_bit.DIVN + 1); // Итого деление частоты + AdcClock = SystemCoreClock / AdcDiv; + RCU->ADCCFG_bit.CLKEN = 0x1; // Разрешить тактирование + RCU->ADCCFG_bit.RSTDIS = 0x1; // Снимаем сброс + ADC->ACTL_bit.ADCEN = 0x1; // Разрешаем работу АЦП + + //Настройка секвенсора 0 + // CH0, CH1, CH2, CH3. + ADC->EMUX_bit.EM0 = ADC_EMUX_EM0_PWM012A; // Запуск от таймера + ADC->SEQSYNC = ADC_SEQSYNC_SYNC0_Msk; // Разрешить секвенсор SEQ0 + ADC->SEQ[0].SRQCTL_bit.RQMAX = 0x3; // Опрашивать 4 канала за раз = RQMAX + 1 + ADC->SEQ[0].SRQSEL_bit.RQ0 = 0x0; // Какой вход АЦП когда опрашивается + ADC->SEQ[0].SRQSEL_bit.RQ1 = 0x1; // --//-- + ADC->SEQ[0].SRQSEL_bit.RQ2 = 0x2; // --//-- + ADC->SEQ[0].SRQSEL_bit.RQ3 = 0x3; // --//-- + ADC->SEQ[0].SCCTL_bit.RCNT = 3; // Делать ещё три перезапуска после первого запуска + ADC->SEQ[0].SRTMR_bit.VAL = (pwmPrd / AdcDiv) / (ADC->SEQ[0].SCCTL_bit.RCNT + 1); // Пауза между пусами АЦП на период ШИМ + ADC->SEQ[0].SCCTL_bit.ICNT = 3; // Вызов прерывания через каждые (ICNT + 1) оцифровки + ADC->SEQ[0].SCCTL_bit.RAVGEN = 1; // Разрешить усреднять по 4 точкам + ADC->SEQEN_bit.SEQEN0 = 1; // Разрешить секвенсор 0 + + + // Очистка FIFO + while (ADC->SEQ[0].SFLOAD) + trash = ADC->SEQ[0].SFIFO; + + // Разрешить EPWM0 запускать АЦП по нулю + + + // Ждём, пока АЦП выставит флаг "ГОТОВ" (можно вставить этот цикл после "ADCEN = 1") + while (!ADC->ACTL_bit.ADCRDY) {}; + + // Разрешить прерывание от первого секвенсера + ADC->IM_bit.SEQIM0 = 1; + NVIC_EnableIRQ(ADC_SEQ0_IRQn); + NVIC_SetPriority(ADC_SEQ0_IRQn, IRQ_PRIORITY_ADC); +} + + +//!Расчет АЦП с частотой основного расчета всей системы управления (обычно 10кГц). + +//! Занимается обработкой измеренных АЦП значений и преобразует в формат IQ24. +//! Токи фаз для повышения точности усредняются за несколько измерений + +//! \memberof TAdcDrv + +void AdcDrv_fast_calc(TAdcDrv *p) { + Uint32 trash; + // Если всё пошло хорошо, то в ФИФЕ будут уже усреднённые результаты - 4 штуки. + p->IA_temp = ADC->SEQ[0].SFIFO; + p->IB_temp = ADC->SEQ[0].SFIFO; + p->Udc_temp = ADC->SEQ[0].SFIFO; + p->T_temp = ADC->SEQ[0].SFIFO; + // Очистка FIFO на случай, если почему-то там оказалось больше чем надо значений (бывает после остановки житагом) + while (ADC->SEQ[0].SFLOAD) + trash = ADC->SEQ[0].SFIFO; + + p->Imeas_a = p->IaGainNom * (((p->IA_temp<< 4) + p->Imeas_a_offset)); + p->Imeas_b = p->IbGainNom * (((p->IB_temp<< 4) + p->Imeas_b_offset)); + p->Udc_meas = p->UdcGainNom * (p->Udc_temp + p->Udc_meas_offset); + p->Imeas_c = -p->Imeas_a - p->Imeas_b; + + //ADC->SEQ[0].SCCTL_bit.RAVGEN ^= 1; +} + +//!Медленный расчет. + +//!Занимается пересчетом коэффициентов, используемых в скоростной функции расчета, +//!чтобы не занимать процессорное время там. Находит коэффициенты, +//!на которые надо умножить полученное с АЦП значение, чтобы получить +//!относительные единицы с заданной базой. + +//! Пример p->PvalveGainNom=_IQ16mpy(p->Pvalve_gain,_IQ(1.0/100)); +//! Pvalve_gain - значение в формате int. задается пользователем в UniCON. +//!Определяет, скольким процентам соответствует полный диапазон АЦП. В простейшем случае +//!равен 100. Т.е. когда на АЦП максимальный сигнал, это соответствует 100%. + +//!_IQ(1.0/100) обратное значение для масштабирующего коэффициента. Так как величину процентов +//!естественнее всего перевести в относительные единицы так, что 100% соответствут 1.0, +//!то масштабирующий коэффициент (база) равен 100. Т.е. UniCON, прочитав из системы управления +//! число 1.0 в формате 8.24 должен умножить его на 100, чтобы отобразились проценты. +//! Здесь коэффициент задан явно как 1.0/100, но для ряда случаев базовое значение нужно менять. +//!Так, для токов фаз используется значение _1_I_nom, в формате 8.24, соответствующее единице деленной на +//базовое значение тока, например, 200 А. Так как в зависимости от мощности преобразователя базовый ток может меняться, +//то это значение, в отличие от процентов, сделано настраиваемым. Расчет _1_I_nom идет в другом месте, так как +//занимает много тактов расчета. + +//Для беззнакового значения АЦП измеряет число от 0 до 65535. (16 разрядов, где заполнены верхние). +//Для примера с процентами необходимо сделать так, чтобы получилось результирующее значение в формате 8.24, +//где 1.0 это 65535. Таким образом, нужно сдвинуть число 65535 на 24-16=8 разрядов. +//Сдвиг на 8 разрядов - это умножение на число 255. Число 255 - это 1.0 в формате 24.8. + +//Таким образом, PvalveGainNom - это коэффициент в формате 24.8. он получается в результате использования функции +//_IQ16mpy, аргумены которой Pvalve_gain (int) и 1.0/100 в формате 8.24. Функция IQ множения +//по сути представляет собой обычное оуможение в 64 разрядах со сдвигом результата вправо на Q разрядов. +//Т.е. _IQ16mpy умножает число в формате IQ24 9второй аргумент) на целочисленный коэффициент (первый аргумент), +//а потом сдвигате результат на 16 разрядов вправо. +//Так, в результате _IQ16mpy(p->Pvalve_gain,_IQ(1.0/100)); получается целочисленное число 255, являющейся +//1.0 в формате 24.8 из-за сдвига на 16 разрядов вправо. + +//Всё вышеприведенное мутево сделано с одной целью - увеличить производитлеьность обработки АЦП. + +//! \memberof TAdcDrv +void AdcDrv_slow_calc(TAdcDrv *p) { + // Пересчёт пауз между перезапусками + volatile Uint16 pwmPrd = PWM0->TBPRD; + + // Если считает вверх-вниз, то период на деле в два раза больше + if (PWM0->TBCTL_bit.CTRMODE == TB_COUNT_UPDOWN) + pwmPrd = pwmPrd << 1; + + // Делитель частоты АЦП + Uint16 AdcDiv = 2 * (RCU->ADCCFG_bit.DIVN + 1); + if (pwmPrd < 1000) pwmPrd = 1000; + + ADC->SEQ[0].SRTMR_bit.VAL = (pwmPrd / AdcDiv) / (ADC->SEQ[0].SCCTL_bit.RCNT + 1); + + p->IaGainNom = _IQ16mpy(p->Imeas_a_gain, drv_params._1_I_nom) << 1; + p->IbGainNom = _IQ16mpy(p->Imeas_b_gain, drv_params._1_I_nom) << 1; + p->IcGainNom = _IQ16mpy(p->Imeas_c_gain, drv_params._1_I_nom) << 1; + p->UdcGainNom = _IQ16mpy(p->Udc_meas_gain, drv_params._1_Udc_nom) << 4; +} + +//! Миллисекундный расчет + +//! \memberof TAdcDrv +void AdcDrv_ms_calc(TAdcDrv *p) { + +} + +/*@}*/ + diff --git a/Vsrc/V_bits_to_enum_numbers.c b/Vsrc/V_bits_to_enum_numbers.c new file mode 100644 index 0000000..b84efd3 --- /dev/null +++ b/Vsrc/V_bits_to_enum_numbers.c @@ -0,0 +1,72 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_bits_to_enum_numbers.c + \brief Модуль "листания" битовых переменных (см. TBitsToEnumNums) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + */ + +/** \addtogroup V_bits_to_enum_numbers */ +/*@{*/ + +#include "DSP.h" +#include "V_bits_to_enum_numbers.h" + +//! Преобразует битовые переменные в числа + +//!Требуется в основном для модуля защит или предупреждений, +//!для преобразования выставленных бит аварии в словах аварии в +//!порядковый номер этих бит и "листания" этих номеров с определенной +//!частотой, если выставлено несколько бит. Такое преобразование нужно для +//!удобства наблюдения аварий/предупреждений пользователем. +//!Вызывать необходимо с определенной дискретизацией (например, 10кГц). +//! \memberof TBitsToEnumNums +void BitsToEnumNums(TBitsToEnumNums* p) { + Uint16 i; + + p->counter++; + if (p->counter < p->out_refresh_devisor) + return; + p->counter = 0; + + //проверка правильности вызова + if ((p->num_of_words > NUM_OF_W_PTRS) || (p->num_of_words == 0)) + return; + + //перебираем биты в порядке возрастания + for (i = 0; i < (16 * p->num_of_words); i++) { + p->last_bit++; + if (p->last_bit > 15) { + p->last_bit = 0; + p->last_word++; + if (p->last_word > (p->num_of_words - 1)) + p->last_word = 0; + } + //делаем проверку бита + if ((*(p->w_ptrs[p->last_word])) & (0x1 << p->last_bit)) { + //битик имеется выводим результат + p->output = p->last_word * 16 + p->last_bit + 1; + return; + } + } + + //если дошли до сюда значит нет битиков, потому выдаем 0 + p->output = 0; +} + +/*@}*/ + diff --git a/Vsrc/V_data_log.c b/Vsrc/V_data_log.c new file mode 100644 index 0000000..909864f --- /dev/null +++ b/Vsrc/V_data_log.c @@ -0,0 +1,281 @@ +/*! + \file v_data_log.c + \brief 4-х канальный логгер длЯ осциллографированиЯ в реальном времени TDataLog (см. TDataLog) + + \author Коллектив ООО НПФ Вектор + \version v 2.01 18/09/2012 + */ + +/** \addtogroup v_data_log */ +/*@{*/ + +#include "DSP.h" +#include "co_ODvars.h" +#include "V_data_log.h" +#include "CANOpen_drv.h" + +//! Фоновый обработчик. + +/*! работает в фоне. Нужно длЯ установки адресов переменных через CAN. + если нет CAN, можно записать нужные адреса вручную в TDataLog.dlog_iptr */ +//! \memberof TDataLog +void dlog_background_analizer(TDataLog *p) { + //перевод длины предыстории из % в точки + p->trig_shift_int = (p->trig_shift&0xFFFFFF)>>16; //делаем количество точек + if (p->trig_shift_int > 255) //ограничим + p->trig_shift_int = 255; + + unsigned char mode; + + //если не стоит хоть один из первых шести бит control, + //то ничего анализировать и делать не надо + if (!(p->control & 0x3F)) + return; + //В любом случае перед всеми изменениЯми + //тормозим даталоггер. Иначе он может начать записывать данные по прерыванию, + //пока тут, в фоне, идет, скажем, запись адресов. + //И тогда в лучшем случае будет каша из данных, в худшем - останов контроллера + //при обращении по неправильному адресу. + p->mode_reset = 0; + p->valid_points_num = 0; //т.к. даталоггер останавливался (mode = 0), то предыстория неактуальна, т.к. + //1) за время стопа даталоггера между записанной предысторией и новыми данными будет разрыв по времени и + //2) выбранные записываемые переменные вообще могли смениться и предыстория останется от старых, а новые данные - от новых + //спрашиваем адреса у драйвера CANopen +#if DLOG_DATA_SIZE == 16 + if (p->control & 1) + if (!(p->dlog_iptr1 = (type_data*)co_getAddr(p->pco_vars, p->ind_subind1))) //если адрес=0 + p->dlog_iptr1 = (type_data*)&p->ind_subind1; //пусть указывает на ind_subind + if (p->control & 2) + if (!(p->dlog_iptr2 = (type_data*)co_getAddr(p->pco_vars, p->ind_subind2))) + p->dlog_iptr2 = (type_data*)&p->ind_subind2; + if (p->control & 4) + if (!(p->dlog_iptr3 = (type_data*)co_getAddr(p->pco_vars, p->ind_subind3))) + p->dlog_iptr3 = (type_data*)&p->ind_subind3; + if (p->control & 8) + if (!(p->dlog_iptr4 = (type_data*)co_getAddr(p->pco_vars, p->ind_subind4))) + p->dlog_iptr4 = (type_data*)&p->ind_subind4; +#endif +#if DLOG_DATA_SIZE == 32 + if (p->control & 1) + { + if (co_getObjectInfo(p->pco_vars, p->ind_subind1, (TObjectInfo*)&p->object1Info) == 0) + { + p->object1Info.varAddr = (void*)(&p->ind_subind1); + p->object1Info.varSize = 32; + } + } + if (p->control & 2) + { + if (co_getObjectInfo(p->pco_vars, p->ind_subind2, (TObjectInfo*)&p->object2Info) == 0) + { + p->object2Info.varAddr = (void*)(&p->ind_subind2); + p->object2Info.varSize = 32; + } + } + if (p->control & 4) + { + if (co_getObjectInfo(p->pco_vars, p->ind_subind3, (TObjectInfo*)&p->object3Info) == 0) + { + p->object3Info.varAddr = (void*)(&p->ind_subind3); + p->object3Info.varSize = 32; + } + } + if (p->control & 8) + { + if (co_getObjectInfo(p->pco_vars, p->ind_subind4, (TObjectInfo*)&p->object4Info) == 0) + { + p->object4Info.varAddr = (void*)(&p->ind_subind4); + p->object4Info.varSize = 32; + } + } + p->highPartOfValue = 0; +#endif + p->WriteDelimiter = (p->control >> 16) & 0xFF; //прореживание. ОграничиваетсЯ 8ю битами + mode = (p->control >> 4) & 3; //режим - 2 бита + p->control = 0; //все обработали, обнулЯем, чтобы при след. вызове не начать обрабатывать снова + dlog_set_mode(mode, p); //длЯ установки режима вызываетсЯ спец. функциЯ. НапрЯмую нельзЯ + +} + +//! функциЯ длЯ установки mode_reset. + +//! предполагаетсЯ длЯ управлениЯ логгером из других модулей +//! проверЯет mode_reset на валидность и обнулЯет счетчики +//! \memberof TDataLog + +void dlog_set_mode(Uint16 mode_reset, TDataLog *p) { + if (mode_reset > 3) + return; + //в 1 переводим только если текущий режим 2, чтоб синхронизироватьсЯ + //по первому событию (очень полезно когда событий много) + if (p->OneShotOperation == 1) { + if ((mode_reset == 1)) { + if (p->mode_reset == 2) + p->mode_reset = mode_reset; + else + return; + } + } else + p->mode_reset = mode_reset; + + if (mode_reset == 3) //Хотим перейти в режим однократной записи 1024 точек. + p->Wcounter = 0; //в этом режиме нужно писать с первой точки первого массива. Сбрасываем счетчик. + + + //при смене режима в любом случае сбрасываем флаг "данные готовы" + p->control &= ~(1 << 6); + p->WriteDelimiterCounter = 0; +#if DLOG_DATA_SIZE == 32 + p->highPartOfValue = 0; +#endif +} + +//! Записывает очередные точки в массивы осциллограммы. + +//!Должна вызыватьсЯ с заданной дискретизацией и занимаетсЯ записью массивов, +//! т.е. непосредственно осциллографированием. Умеет записывать данные +//! в массивы по-разному в зависимости от выбранного режима работы осциллографа +//! \memberof TDataLog + +void data_log_update(TDataLog *p) { +//везде испоьзуетсЯ p-> , а не p* - так быстрее + +//прореживание данных. Если не достигли уставки WriteDelimiter, выходим +//WriteDelimiter=1 - не делим +//WriteDelimiter=2 - берем каждую вторую + if ((p->WriteDelimiterCounter++ + 1) < p->WriteDelimiter) + return; + else + p->WriteDelimiterCounter = 0; + + if (p->mode_reset != p->mode_reset_prev) p->E=1; + else p->E=0; + p->mode_reset_prev = p->mode_reset; + + switch (p->mode_reset) { + case 0: { + p->Wcounter = 0; + return; + } + + case 1: //однократнаЯ запись - дошли до конца и стоп (режим 0) + { + //При входе в режим получаем точку срабатывания триггера (это текущий Wcounter, с которым мы сюда зашли) и рассчитываем первую точку, относящуюся к данной осце (исходя из текущей точки и заданной длины предыстории) + if (p->E==1) + { + p->prehistory_length = p->valid_points_num; //длина предыстории равна количеству валидных точек + if (p->prehistory_length > p->trig_shift_int) //если предыстория длиннее заданного, ограничим + p->prehistory_length = p->trig_shift_int; +#if DLOG_DATA_SIZE == 16 + p->Wcounter &= 0xFE; + p->prehistory_length &= 0xFE; + p->first_point_written = (p->Wcounter - p->prehistory_length) & 0xFE; +#endif +#if DLOG_DATA_SIZE == 32 + p->first_point_written = (p->Wcounter - p->prehistory_length) & 0xFF; + p->highPartOfValue = 0; +#endif + } + p->Wcounter &= 0xFF; //защита - если вдруг в counter не валидное значение +#if DLOG_DATA_SIZE == 16 + p->dl_buffer1_adr[p->Wcounter] = *p->dlog_iptr1; + p->dl_buffer2_adr[p->Wcounter] = *p->dlog_iptr2; + p->dl_buffer3_adr[p->Wcounter] = *p->dlog_iptr3; + p->dl_buffer4_adr[p->Wcounter] = *p->dlog_iptr4; +#endif +#if DLOG_DATA_SIZE == 32 + p->dl_buffer1_adr[p->Wcounter] = p->object1Info.varSize == 16 ? + *((int16*)p->object1Info.varAddr) : *((int32*)p->object1Info.varAddr); + p->dl_buffer2_adr[p->Wcounter] = p->object2Info.varSize == 16 ? + *((int16*)p->object2Info.varAddr) : *((int32*)p->object2Info.varAddr); + p->dl_buffer3_adr[p->Wcounter] = p->object3Info.varSize == 16 ? + *((int16*)p->object3Info.varAddr) : *((int32*)p->object3Info.varAddr); + p->dl_buffer4_adr[p->Wcounter] = p->object4Info.varSize == 16 ? + *((int16*)p->object4Info.varAddr) : *((int32*)p->object4Info.varAddr); +#endif + p->Wcounter++; + p->Wcounter &= 0xFF; //если прошли 256 точек, обнулитсЯ + if (p->Wcounter == p->first_point_written) //если дошли до последней записываемой точки + { + p->mode_reset = 0; //режим СТОП + + #if DLOG_DATA_SIZE == 16 + p->control |= 192; // "данные готовы" + "поддерживается блочная передача" + #else + p->control |= 192 | (1 << 8); // "данные готовы" + "поддерживается блочная передача" + "32-битные данные" + #endif + + } + return; + } + + case 2: //записываем лог по кругу + { + if (p->E == 1) + { +#if DLOG_DATA_SIZE == 32 + p->highPartOfValue = 0; +#endif + } + p->valid_points_num++; //считаем количество записанных валидных точек предыстории + if (p->valid_points_num > 256) //ограничиваем + p->valid_points_num = 256; + p->Wcounter &= 0xFF; //защита - если вдруг в counter не валидное значение +#if DLOG_DATA_SIZE == 16 + p->dl_buffer1_adr[p->Wcounter] = *p->dlog_iptr1; + p->dl_buffer2_adr[p->Wcounter] = *p->dlog_iptr2; + p->dl_buffer3_adr[p->Wcounter] = *p->dlog_iptr3; + p->dl_buffer4_adr[p->Wcounter] = *p->dlog_iptr4; +#endif +#if DLOG_DATA_SIZE == 32 + p->dl_buffer1_adr[p->Wcounter] = p->object1Info.varSize == 16 ? + *((int16*)p->object1Info.varAddr) : *((int32*)p->object1Info.varAddr); + p->dl_buffer2_adr[p->Wcounter] = p->object2Info.varSize == 16 ? + *((int16*)p->object2Info.varAddr) : *((int32*)p->object2Info.varAddr); + p->dl_buffer3_adr[p->Wcounter] = p->object3Info.varSize == 16 ? + *((int16*)p->object3Info.varAddr) : *((int32*)p->object3Info.varAddr); + p->dl_buffer4_adr[p->Wcounter] = p->object4Info.varSize == 16 ? + *((int16*)p->object4Info.varAddr) : *((int32*)p->object4Info.varAddr); +#endif + p->Wcounter++; + p->Wcounter &= 0xFF; //если прошли 256 точек, обнулитсЯ + return; + } + + case 3: //режим однократной записи 1024 точек + { + if (p->E==1) + { + p->first_point_written = 0; //пишем с первой точки, предыстория не нужна. +#if DLOG_DATA_SIZE == 32 + p->highPartOfValue = 0; +#endif + } + //с учетом того, что буферы в памЯти расположены последовательно, + //записываем в первый, "заезжаЯ" на остальные три +#if DLOG_DATA_SIZE == 16 + p->dl_buffer1_adr[p->Wcounter] = *p->dlog_iptr1; +#endif +#if DLOG_DATA_SIZE == 32 + p->dl_buffer1_adr[p->Wcounter] = p->object1Info.varSize == 16 ? + *((int16*)p->object1Info.varAddr) : *((int32*)p->object1Info.varAddr); +#endif + p->Wcounter++; + if (p->Wcounter >= 1024) //если дошли до конца + { + p->mode_reset = 0; //режим СТОП + + #if DLOG_DATA_SIZE == 16 + p->control |= 192; // "данные готовы" + "поддерживается блочная передача" + #else + p->control |= 192 | (1 << 8); // "данные готовы" + "поддерживается блочная передача" + "32-битные данные" + #endif + + } + return; + } + } +} + +/*@}*/ + diff --git a/Vsrc/V_event_log.c b/Vsrc/V_event_log.c new file mode 100644 index 0000000..c3e2f11 --- /dev/null +++ b/Vsrc/V_event_log.c @@ -0,0 +1,252 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_event_log.c + \brief Сохранение событий и времени возникновениЯ в ЭнОЗУ + ИспользуетсЯ драйвер работы с энергонезависимой памЯтью + Поэтому вызов init(); должен быть после инициализации ЭнОЗУ + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 1.0 2009_01_20 + +*/ + +/** \addtogroup W_event_log */ +/*@{*/ +#ifdef __cplusplus +extern "C" { +#endif + +#include + + + //!<Протоколирование аварий + +//Процедуры записи событий в энергонезависимую флешку очень долгие (связано с таймингами I2C-интерфейса +//и большим объемом данных, передаваемым по I2C в процессе записи). +//Поэтому алгоритм работы такой: +//Если нужно прочитать аварию [Logger_Event_Read] (срочно считывать аварию из банка не требуется) - +//она читается в фоновом цикле прямиком из ЭнОЗУ. +//Если нужно записать аварию в банк [Logger_Event_Write] - в прерывании (например, 1мс) данные аварии пишутся в FIFO; +//затем в фоновом цикле [Logger_Background_Calc] аварии читаются из FIFO [Event_FIFO_Read] +//(по одно за 1 фоновый цикл) и пишутся в ЭнОЗУ. + + +//прочитать событие из FIFO (для дальнейшей записи в ЭнОЗУ). +Uint16 Event_FIFO_Read(TEventFIFO* p,TEvent* ev) +{ + if (p->busy_flag > 0) return EVENT_FIFO_BUSY; + //выставлЯем флажок работы с FIFO + p->busy_flag = 1; + if (p->number_of_msgs == 0) + { + //освобождаем флаг работы с FIFO + p->busy_flag = 0; + return EVENT_FIFO_EMPTY; + } + //читаем данные из FIFO + ev->ev_code = p->msg_array[(p->read_ptr)].ev_code; + ev->ev_time = p->msg_array[(p->read_ptr)].ev_time; + ev->ev_num = p->msg_array[(p->read_ptr)].ev_num; + //подготовка FIFO к следующему вызову + p->read_ptr++; + if (p->read_ptr >= p->size) p->read_ptr = 0; + p->number_of_msgs--; + //освобождаем флаг работы с FIFO + p->busy_flag = 0; + return EVENT_FIFO_SUCCESSFUL; +} + + + +//Записать событие в FIFO (вызывается в Logger_Event_Write, в прерывании) +Uint16 Event_FIFO_Write(TEventFIFO* p,TEvent* ev) +{ + if (p->busy_flag > 0) return EVENT_FIFO_BUSY; + //выставлЯем флажок работы с FIFO + p->busy_flag = 1; + if (p->number_of_msgs == p->size) + { + //освобождаем флаг работы с FIFO + p->busy_flag = 0; + return EVENT_FIFO_FULL; + } + //записываем данные в FIFO + p->msg_array[(p->write_ptr)].ev_code = ev->ev_code; + p->msg_array[(p->write_ptr)].ev_time = ev->ev_time; + p->msg_array[(p->write_ptr)].ev_num = ev->ev_num; + //подготовка FIFO к следующему вызову + p->write_ptr++; + if (p->write_ptr >= p->size)p->write_ptr = 0; + p->number_of_msgs++; + //освобождаем флаг работы с FIFO + p->busy_flag = 0; + return EVENT_FIFO_SUCCESSFUL; +} + +//инициализация (если банк забит мусором - все данные FFFF, очищаем его) +void Logger_Init(TLogger* p,Uint16 BS,Uint16 SA,Uint32* tptr) +{ + TEvent tmp; + Uint16 i; + Uint16 last_log_num = 0; + Uint16 last_log_index = 0; + //инициализируем внутренние переменные + p->SPI_buf_size = BS; + p->SPI_start_addr = SA; + p->time_ptr = tptr; + + //далее нужно просканировать буфер в ЭнОЗУ - найти последнюю + UserMem.MemStartAddr = p->SPI_start_addr; + UserMem.data_length = 0; + for (i=0;iSPI_buf_size;i++) + { + //читаем номер + UserMem.MemStartAddr += UserMem.data_length; + UserMem.MCUStartAddr = (Uint16*)(&tmp.ev_num); + UserMem.data_length = LOG_NUM_LENGTH; + UserMem.read(&UserMem); + //читаем времЯ + UserMem.MemStartAddr += UserMem.data_length; + UserMem.MCUStartAddr = (Uint16*)(&tmp.ev_time); + UserMem.data_length = LOG_TIME_LENGTH; + UserMem.read(&UserMem); + //читаем код + UserMem.MemStartAddr += UserMem.data_length; + UserMem.MCUStartAddr = (Uint16*)(&tmp.ev_code); + UserMem.data_length = LOG_CODE_LENGTH; + UserMem.read(&UserMem); + + //делаем необходимые проверки + //если все полЯ 0xFFFF, то чистим всю памЯть + if ((tmp.ev_num == 0xFFFF) && (tmp.ev_time == 0xFFFFFFFF) && (tmp.ev_code == 0xFFFF)) + { + //чистим + p->clear(p); + //инициализируем переменные + p->INTERNAL_last_log_num = 0; + p->INTERNAL_last_log_index = 0; + return; + } + //ищем последнюю запись + if (last_log_num < tmp.ev_num) + { + last_log_num = tmp.ev_num; + last_log_index = i; + } + } + p->INTERNAL_last_log_num = last_log_num; + p->INTERNAL_last_log_index = last_log_index; +} + +//функциЯ очистки буфера в ЭнОЗУ +void Logger_Clear(TLogger* p) +{ + Uint16 zero = 0; + UserMem.MemStartAddr = p->SPI_start_addr; + UserMem.MCUStartAddr = (Uint16*)(&zero); + UserMem.data_length = 1; + for (int i=0;i<(p->SPI_buf_size * (LOG_LENGTH));i++) + { + UserMem.write(&UserMem); + UserMem.MemStartAddr++; + } + p->INTERNAL_last_log_index = 0; + p->INTERNAL_last_log_num = 0; +} + + +//быстраЯ функциЯ записи событиЯ в FIFO +Uint16 Logger_Event_Write(TLogger* p,Uint16 code) +{ + TEvent event; + //формируем данные + __disable_irq(); + event.ev_time = *(p->time_ptr); + event.ev_code = code; + event.ev_num = ++p->INTERNAL_last_log_num; + p->INTERNAL_last_log_code = code; + __enable_irq(); + //пишем в FIFO + return p->FIFO.write((struct SEventFIFO*)&(p->FIFO),(TEvent*)&event); +} + +//прочитать аварию из банка, сложить данные в TEvent* event +void Logger_Event_Read(TLogger* p,Uint16 shift_index,TEvent* event) +{ + Uint16 correction = 0; + //проверЯем правильность запроса + if (shift_index > (p->SPI_buf_size - 1)) return; + + //ввод коррекции длЯ организации кольца + if (((int16)p->INTERNAL_last_log_index - (int16)shift_index) < 0) correction = p->SPI_buf_size; + //чтение номера + UserMem.MemStartAddr = p->SPI_start_addr + ((p->INTERNAL_last_log_index - shift_index + correction)*(LOG_LENGTH)); + UserMem.MCUStartAddr = (Uint16*)(&(event->ev_num)); + UserMem.data_length = LOG_NUM_LENGTH; + UserMem.read(&UserMem); + //чтение времени + UserMem.MemStartAddr += UserMem.data_length; + UserMem.MCUStartAddr = (Uint16*)(&(event->ev_time)); + UserMem.data_length = LOG_TIME_LENGTH; + UserMem.read(&UserMem); + //чтение кода + UserMem.MemStartAddr += UserMem.data_length; + UserMem.MCUStartAddr = (Uint16*)(&(event->ev_code)); + UserMem.data_length = LOG_CODE_LENGTH; + UserMem.read(&UserMem); +} + +//функциЯ обработки FIFO и записи аварий в ЭнОЗУ. Если в FIFO что-то клали - запишем во флешку. +//Если FIFO занята или пустая - отдыхаем. +void Logger_Background_Calc(TLogger* p) +{ + Uint16 ret; + TEvent event; + //чтобы не сильно затормаживать фоновый цикл будем записывать по 1 записи за раз + ret = p->FIFO.read((struct SEventFIFO*)&(p->FIFO),(TEvent*)&event); + if (ret == EVENT_FIFO_SUCCESSFUL) + { + //пишем в ЭнОЗУ + if (p->INTERNAL_last_log_index >= (p->SPI_buf_size - 1)) p->INTERNAL_last_log_index = 0; + else p->INTERNAL_last_log_index++; + + //запись номера + UserMem.MemStartAddr = p->SPI_start_addr + (p->INTERNAL_last_log_index)*(LOG_LENGTH); + UserMem.MCUStartAddr = (Uint16*)(&(event.ev_num)); + UserMem.data_length = LOG_NUM_LENGTH; + UserMem.write(&UserMem); + //запись времени + UserMem.MemStartAddr += UserMem.data_length; + UserMem.MCUStartAddr = (Uint16*)(&(event.ev_time)); + UserMem.data_length = LOG_TIME_LENGTH; + UserMem.write(&UserMem); + //запись кода + UserMem.MemStartAddr += UserMem.data_length; + UserMem.MCUStartAddr = (Uint16*)(&(event.ev_code)); + UserMem.data_length = LOG_CODE_LENGTH; + UserMem.write(&UserMem); + } +} + +//функция проверки и записи висящих в данный момент флагов аварий +//Последовательно смотрится каждый бит слов аварий и, если он взведен, но еще не записан, производится запись. +void Logger_ms_Calc(TLogger* p){ + +} + +#ifdef __cplusplus +} // Extern "C" +#endif +/*@}*/ diff --git a/Vsrc/V_hzprof.c b/Vsrc/V_hzprof.c new file mode 100644 index 0000000..43fcf31 --- /dev/null +++ b/Vsrc/V_hzprof.c @@ -0,0 +1,53 @@ +/*! + Copyright 2017 Texas Instruments, АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_hzprof.c + \brief Кривая U(f) (см. TVhzProf) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup vhzprof + */ + +#include "V_IQmath.h" /* Include header for IQmath library */ +#include "V_hzprof.h" +#include + +//! Функция расчета кривой U(f) + +//!На вход принимает частоту freq, и исходя из настроенных значений +//!минимального напряжения на минимальной частоте и максимального +//!напряжения на максимальной частоте, выдает vout - напряжение +//!для частоты freq. Другими словами, модуль представляет собой +//!линейный интерполятор по двум реперным точкам с ограничением максимума и +//!минимума. + +//! \memberof TVhzProf +void vhz_prof_calc(TVhzProf *v) { + _iq vf_slope, freq_abs; + + freq_abs = labs(v->freq); + + if (freq_abs <= v->FL) + v->vout = v->Vmin; /* Profile #1 */ + else if ((freq_abs > v->FL) & (freq_abs <= v->FH)) { + vf_slope = _IQdiv((v->Vmax - v->Vmin), (v->FH - v->FL)); /* Computing v/f slope */ + v->vout = v->Vmin + _IQmpy(vf_slope, (freq_abs - v->FL)); /* Profile #2 */ + } else if ((freq_abs > v->FH) & (freq_abs < v->Fmax)) + v->vout = v->Vmax; /* Profile #3 */ +} + +/*@}*/ + diff --git a/Vsrc/V_led.c b/Vsrc/V_led.c new file mode 100644 index 0000000..eaf49b3 --- /dev/null +++ b/Vsrc/V_led.c @@ -0,0 +1,78 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file Vled.c + \brief Управление светодиодами + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup led + */ + +#include "DSP.h" +#include "main.h" + + +void LED_init(Tled *p) { + +} + +void LED_toggle(Tled *p, Uint16 led) { + +} + +void LED_on(Tled *p, Uint16 led) { + +} + +void LED_off(Tled *p, Uint16 led) { + +} + +void LED_clearAll(Tled *p) { + +} + +void LED_mode0(Tled *p) { + +} + +void LED_mode1(Tled *p) { + +} + +void LED_mode2(Tled *p) { + +} + +void LED_mode3(Tled *p) { + +} + +void LED_msCalc(Tled *p) { + +} + + + + + + + + + + + + diff --git a/Vsrc/V_pid_reg3.c b/Vsrc/V_pid_reg3.c new file mode 100644 index 0000000..1cd9d4f --- /dev/null +++ b/Vsrc/V_pid_reg3.c @@ -0,0 +1,111 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_pid_reg3.c + \brief ПИД-регулятор (см. TPidReg3) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup V_pid_reg3 + @{*/ + +#include "V_IQmath.h" // Include header for IQmath library +#include "V_pid_reg3.h" +#include "stdlib.h" +#include "main.h" +//! Функция расчета ПИД регулятора +//! Вообще это чуть доработанная версия тексасовского регулятора +//! Документацию этой магии лучше всего посмотреть, загуглив pid_reg3.pdf + +//! На входе pid_ref_reg3 - задание, pid_fdb_reg3 - обратная связь +//! На выходе pid_out_reg3. + +//! \memberof TPidReg3 +void pid_reg3_calc(TPidReg3 *v) { + v->e_reg3 = v->pid_ref_reg3 - v->pid_fdb_reg3;//ошибка - задание минус обратная связь + v->e_reg3Dz=v->e_reg3;//ошибка после коррекции блока мертвой зоны + + if (v->DeadZone!=0){//если есть уставка зоны нечувствительности + if (v->e_reg3Dz>0){//ошибка в плюс + v->e_reg3Dz=v->e_reg3Dz-v->DeadZone;//вычитаем мертвую зону + if (v->e_reg3Dz<0)//но так, чтобы ошибка не стала отрицательной + v->e_reg3Dz=0; + } + if (v->e_reg3Dz<0){ + v->e_reg3Dz=v->e_reg3Dz+v->DeadZone; + if (v->e_reg3Dz>0) + v->e_reg3Dz=0; + } + } + + v->up_reg3 = _IQmpy(v->Kp_reg3, v->e_reg3Dz); + + v->uprsat_reg3 = v->up_reg3 + v->ui_reg3 + v->ud_reg3; + + if (v->uprsat_reg3 > v->pid_out_max) + v->pid_out_reg3 = v->pid_out_max; + else if (v->uprsat_reg3 < v->pid_out_min) + v->pid_out_reg3 = v->pid_out_min; + else + v->pid_out_reg3 = v->uprsat_reg3; + + v->saterr_reg3 = v->pid_out_reg3 - v->uprsat_reg3 + v->saterr_reg3Add; + + //использовать ли фильтр для дифф. части. Если кфильтра ноль, то нет. + if (v->Kf_d == 0){ + v->e_reg3_filterOut = v->e_reg3;//выход фильтра + } + else{//иначе считаем фильтр + v->e_reg3_filterOut = v->e_reg3_filterOut + + _IQmpy(v->Kf_d, (v->e_reg3 - v->e_reg3_filterOut)); + } + + if ((v->DiffCounter++ + 1) >= v->DiffDelim) {//каждые сколько вызовов считать дифф. часть + if (v->KdFilterInitFlag==1){//это первый такт расчета регулятора + v->e_reg3_filterOut = v->e_reg3;//выход фильтра ошибки инициализируем ошибкой + v->up1_reg3 = v->e_reg3_filterOut;//производная ноль + v->KdFilterInitFlag=0;//инициализация завершена + } + v->ud_reg3 = _IQmpy(v->Kd_reg3, (v->e_reg3_filterOut - v->up1_reg3)<<6);//дифференциальная часть + v->up1_reg3 = v->e_reg3_filterOut; + v->DiffCounter = 0; + } + + if (v->Ki_reg3 != 0)//есть интегральная составляющая + v->ui_reg3 = v->ui_reg3 + + _IQmpy(v->Ki_reg3, + v->up_reg3) + _IQmpy(v->Kc_reg3,v->saterr_reg3); + else + v->ui_reg3 = 0; + + if (v->Kc_reg3 == 0) { + if (v->ui_reg3 > v->pid_out_max) + v->ui_reg3 = v->pid_out_max; + else if (v->ui_reg3 < v->pid_out_min) + v->ui_reg3 = v->pid_out_min; + } + +} + + +//! \memberof TPidReg3 +void pid_reg3_reset(TPidReg3 *v) { + v->pid_fdb_reg3=0; + v->pid_ref_reg3=0; + v->ui_reg3=0; + v->KdFilterInitFlag=1; +} + +/*@}*/ diff --git a/Vsrc/V_pid_reg3_pos.c b/Vsrc/V_pid_reg3_pos.c new file mode 100644 index 0000000..64060e0 --- /dev/null +++ b/Vsrc/V_pid_reg3_pos.c @@ -0,0 +1,109 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_pid_reg3.c + \brief ПИД-регулятор (см. TPidReg3) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup V_pid_reg3 + @{*/ + +#include "V_IQmath.h" // Include header for IQmath library +#include "V_pid_reg3_pos.h" +#include "stdlib.h" +#include "main.h" +//! Функция расчета ПИД регулятора +//! Вообще это чуть доработанная версия тексасовского регулятора +//! Документацию этой магии лучше всего посмотреть, загуглив pid_reg3.pdf + +//! На входе pid_ref_reg3 - задание, pid_fdb_reg3 - обратная связь +//! На выходе pid_out_reg3. + +//! \memberof TPidReg3 +void pid_reg3_calc_pos(TPidReg3_pos *v) { + v->e_reg3 = v->pid_ref_reg3 - v->pid_fdb_reg3;//ошибка - задание минус обратная связь + v->e_reg3Dz=v->e_reg3;//ошибка после коррекции блока мертвой зоны + + if (v->DeadZone!=0){//если есть уставка зоны нечувствительности + if (v->e_reg3Dz>0){//ошибка в плюс + v->e_reg3Dz=v->e_reg3Dz-v->DeadZone;//вычитаем мертвую зону + if (v->e_reg3Dz<0)//но так, чтобы ошибка не стала отрицательной + v->e_reg3Dz=0; + } + if (v->e_reg3Dz<0){ + v->e_reg3Dz=v->e_reg3Dz+v->DeadZone; + if (v->e_reg3Dz>0) + v->e_reg3Dz=0; + } + } + + v->up_reg3 = _IQmpy(v->Kp_reg3, v->e_reg3Dz); + + v->uprsat_reg3 = v->up_reg3 + v->ui_reg3 + v->ud_reg3; + + if (v->uprsat_reg3 > v->pid_out_max) + v->pid_out_reg3 = v->pid_out_max; + else if (v->uprsat_reg3 < v->pid_out_min) + v->pid_out_reg3 = v->pid_out_min; + else + v->pid_out_reg3 = v->uprsat_reg3; + + v->saterr_reg3 = v->pid_out_reg3 - v->uprsat_reg3 + v->saterr_reg3Add; + + //использовать ли фильтр для дифф. части. Если кфильтра ноль, то нет. + if (v->Kf_d == 0){ + v->e_reg3_filterOut = v->e_reg3;//выход фильтра + } + else{//иначе считаем фильтр + v->e_reg3_filterOut = posspeedEqep.speed_elec; + } + + if ((v->DiffCounter++ + 1) >= v->DiffDelim) {//каждые сколько вызовов считать дифф. часть + if (v->KdFilterInitFlag==1){//это первый такт расчета регулятора + v->e_reg3_filterOut = posspeedEqep.speed_elec;//выход фильтра ошибки инициализируем ошибкой + v->KdFilterInitFlag=0;//инициализация завершена + } + //v->ud_reg3 = _IQmpy(v->Kd_reg3, (v->e_reg3_filterOut - v->up1_reg3)<<6);//дифференциальная часть + v->ud_reg3 = _IQmpy(v->Kd_reg3,-posspeedEqep.speed_filter.output); + v->DiffCounter = 0; + } + + if (v->Ki_reg3 != 0)//есть интегральная составляющая + v->ui_reg3 = v->ui_reg3 + + _IQmpy(v->Ki_reg3, + v->up_reg3) + _IQmpy(v->Kc_reg3,v->saterr_reg3); + else + v->ui_reg3 = 0; + + if (v->Kc_reg3 == 0) { + if (v->ui_reg3 > v->pid_out_max) + v->ui_reg3 = v->pid_out_max; + else if (v->ui_reg3 < v->pid_out_min) + v->ui_reg3 = v->pid_out_min; + } + +} + + +//! \memberof TPidReg3 +void pid_reg3_reset_pos(TPidReg3_pos *v) { + v->pid_fdb_reg3=0; + v->pid_ref_reg3=0; + v->ui_reg3=0; + v->KdFilterInitFlag=1; +} + +/*@}*/ diff --git a/Vsrc/V_rmp_ctrl.c b/Vsrc/V_rmp_ctrl.c new file mode 100644 index 0000000..38de8dd --- /dev/null +++ b/Vsrc/V_rmp_ctrl.c @@ -0,0 +1,66 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file v_rmp_ctrl.c + \brief Задатчик интенсивности (см. TRMPCtrl) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + */ + +/** \addtogroup V_rmp_ctrl */ +/*@{*/ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "v_rmp_ctrl.h" +#include "V_IQmath.h" +#include "stdlib.h" +#ifdef __cplusplus +} +#endif + +//! Функция расчета задатчика интенсивности + +//!Изменяет output с заданным темпом T, +//!пока output не достигнет input. + +//! \memberof TRMPCtrl +void V_RMP_CTRL_calc(TRMPCtrl *p) { + //выход меньше входа? + if (p->output < p->input) + p->output += p->step;//увелчичиваем с заданным темпом выход + if (p->output > p->input) + p->output -= p->step; + + if ((labs(p->output - p->input) <= p->step) || (p->T==0)) {//вошли в задание с точность до шага или ЗИ вообще отключен + p->output = p->input;//выход равен входу + } +} + +//! Вспомогательная функция задатчика интенсивности + +//!Пересчитывает темп разгона T в шаг step c учетом частоты +//!вызова основной функции Ts (дискретизация, обычно 10кГц). + +//! \memberof TRMPCtrl +void V_RMP_CTRL_slow_calc(TRMPCtrl *p) { + p->step = _IQdiv(p->Ts, p->T);//шаг интегратора ЗИ +} + +/*@}*/ + diff --git a/Vsrc/V_rotor_observer.c b/Vsrc/V_rotor_observer.c new file mode 100644 index 0000000..d03affe --- /dev/null +++ b/Vsrc/V_rotor_observer.c @@ -0,0 +1,47 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file v_rotor_observer.c + \brief Наблюдатель ротора АД (см. TRotorObserver) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 1.0 28/06/2016 + + */ + +/** \addtogroup TRotorObserver */ +/*@{*/ + + +#include "main.h" + +#ifdef __cplusplus +#pragma CODE_SECTION("secureRamFuncs") +#else +#pragma CODE_SECTION(RotorObserver_calc,"secureRamFuncs"); +#endif + +void RotorObserver_calc(TRotorObserver *p) { + //инерционное звено с параметрами ротора + p->psi_d = p->psi_d + _IQmpy(p->Ks,p->id - p->psi_d); + p->psi_q = p->psi_q + _IQmpy(p->Ks,p->iq - p->psi_q); + p->theta_psi_elec = _IQatan2PU(p->psi_q ,p->psi_d); +} + +void RotorObserver_slow_calc(TRotorObserver *p) { + p->Ks=_IQdiv(FAST_CALC_TS,p->Tr); +} + +/*@}*/ + diff --git a/Vsrc/V_watchdog.c b/Vsrc/V_watchdog.c new file mode 100644 index 0000000..9d99138 --- /dev/null +++ b/Vsrc/V_watchdog.c @@ -0,0 +1,69 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file V_PWM_Module.c + \brief Модуль реализации векторной ШИМ (см. TPWM_Module) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup Twdog + @{*/ +#include "main.h" + +Twdog Watchdog = WDOG_DEFAULTS; +// Разрешение вочдога +void WDog_Enable (){ + RCU->WDTCFG_bit.CLKSEL = 2; // PLL + RCU->WDTCFG_bit.DIVN = 1; // PLL / 4 + RCU->WDTCFG_bit.DIVEN = 1; + RCU->WDTCFG_bit.RSTDIS = 1; + RCU->WDTCFG_bit.CLKEN = 1; + + WDT->LOCK = 0x1ACCE551; + WDT->LOAD_bit.VAL = 100000; + WDT->CTRL_bit.INTEN = 1; + WDT->CTRL_bit.RESEN = 1; + WDT->LOCK = 0x1ACCE551; + +} + +// Отключение вочдога +void WDog_Disable (){ + WDT->LOCK = 0x1ACCE551; + WDT->CTRL_bit.INTEN = 0; + WDT->CTRL_bit.RESEN = 0; + WDT->LOCK = 0x1ACCE551; +} + +// Сброс таймера вочдога +void WDog_Feed (){ + WDT->LOCK = 0x1ACCE551; + WDT->LOAD_bit.VAL = 2500 * 3; // 3 * 10 кГц прерывания + WDT->LOCK = 0x1ACCE551; +} + +// Перезагрузка проца вочдогом +void WDog_ResetSystem (){ + DINT; + WDog_Enable(); + WDT->LOCK = 0x1ACCE551; + WDT->LOAD_bit.VAL = 2; // 2 такта + WDT->LOCK = 0x1ACCE551; + + while(1); +} + + +/*@}*/ diff --git a/Vsrc/clarke.c b/Vsrc/clarke.c new file mode 100644 index 0000000..cd2acf0 --- /dev/null +++ b/Vsrc/clarke.c @@ -0,0 +1,35 @@ +/*! + Copyright 2017 Texas Instruments, АО "НИИЭТ" , ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file clarke.c + \brief Модуль фазных преобразований (см. TClarke) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + \addtogroup clarke + @{ + */ + +#include "V_IQmath.h" /* Include header for IQmath library */ +#include "clarke.h" + +//! Функция фазных преобразований +//! \memberof TClarke +void clarke_calc(TClarke *v) { + v->ds = v->as; + v->qs = _IQmpy((v->as + _IQmpy(_IQ(2),v->bs)), _IQ(0.57735026918963)); +} + +/*@}*/ + diff --git a/Vsrc/cood1.c b/Vsrc/cood1.c new file mode 100644 index 0000000..49fe413 --- /dev/null +++ b/Vsrc/cood1.c @@ -0,0 +1,3939 @@ +//Файл: cood.c +//Профиль: D:\Eclipse_GCC_ARM_wks\motorcontroldemo_035\cood.xml +//Дата созданиЯ: 18.07.2018 15:00:26 +//Пользователь: default +#include "DSP.h" +#include "main.h" +#include "cood1.h" +#include "co_ODvars.h" + +// всего 119 индексов в словаре +// всего 741 элементов в словаре +Uint16 const co1_numOfInd = 119; +//Номер перечеслениЯ длЯ групп +Uint16 const co1_groupEnum = 15; +//Хэш-сумма: +Uint32 const co1_odHash[4] = {0x9F1C7C00, 0x93ACC9A0, 0x52405691, 0x7C174CEB}; +//Таблица с адресами переменных + +long const CO1_OD_TBL3[] = { (long)(&co1_vars.co_deviceType), //[1000h.00h], Название=Тип устройства, ТекстПУ=Device Type, EngText=Device Type, группа=CAN +(long)(&co1_vars.co_errorRegister), //[1001h.00h], Название=Регистр ошибок, ТекстПУ=ErrReg, EngText=Error Register, группа=CAN +(long)(&co1_vars.co_deviceState), //[1002h.00h], Название=Manufacturer Status Register, ТекстПУ=DevSta, EngText=Manufacturer Status Register, группа=CAN +(long)(&co1_vars.co_emcyCOBID), //[1014h.00h], Название=COB-ID Emergency Object, ТекстПУ=eCOBID, EngText=COB-ID Emergency Object, группа=CAN +(long)(&co1_vars.co_CHBT), //[1016h.01h], Название=Время ожидания сообщения Heartbeat, ТекстПУ=CHBT, EngText=Consumer Heartbeat Time, группа=CAN +(long)(&co1_vars.co_PHBT), //[1017h.00h], Название=Период генерации сообщения Heartbeat, ТекстПУ=PHBT, EngText=Producer Heartbeat Time, группа=CAN +(long)(&co1_vars.co_vendorID), //[1018h.01h], Название=Код производителя, ТекстПУ=VendID, EngText=Vendor ID, группа=CAN +(long)(&co1_vars.co_productCode), //[1018h.02h], Название=Код продукта, ТекстПУ=PrCode, EngText=Product Code, группа=CAN +(long)(&co1_vars.co_revisionNumber), //[1018h.03h], Название=Номер ревизии, ТекстПУ=RevNum, EngText=Revision Number, группа=CAN +(long)(&co1_vars.co_serialNumber), //[1018h.04h], Название=Серийный номер, ТекстПУ=SerNum, EngText=Serial Number, группа=CAN +(long)(&co1_vars.co_csrxCOBID), //[1200h.01h], Название=COB-ID Client->Server(rx), ТекстПУ=CSRXID, EngText=COB-ID Client->Server(rx), группа=CAN +(long)(&co1_vars.co_sctxCOBID), //[1200h.02h], Название=COB-ID Server->Client(tx), ТекстПУ=SCTXID, EngText=COB-ID Server->Client(tx), группа=CAN +(long)(&co1_vars.co_cstxCOBID), //[1280h.01h], Название=COB-ID Client->Server(tx), ТекстПУ=CSTXID, EngText=COB-ID Client->Server(tx), группа=CAN +(long)(&co1_vars.co_scrxCOBID), //[1280h.02h], Название=COB-ID Server->Client(rx), ТекстПУ=SCRXID, EngText=COB-ID Server->Client(rx), группа=CAN +(long)(&co1_vars.co_ssNODEID), //[1280h.03h], Название=NODE-ID on SDO server, ТекстПУ=SDOSID, EngText=NODE-ID on SDO server, группа=CAN +(long)(&co1_vars.co_RPDO1COBID), //[1400h.01h], Название=COB-ID for RPDO1, ТекстПУ=IRPDO1, EngText=COB-ID for RPDO1, группа=CAN +(long)(&co1_vars.co_transType), //[1400h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_RPDO2COBID), //[1401h.01h], Название=COB-ID for RPDO2, ТекстПУ=IRPDO2, EngText=COB-ID for RPDO2, группа=CAN +(long)(&co1_vars.co_transType), //[1401h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_RPDO3COBID), //[1402h.01h], Название=COB-ID for RPDO3, ТекстПУ=IRPDO3, EngText=COB-ID for RPDO3, группа=CAN +(long)(&co1_vars.co_transType), //[1402h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_RPDO4COBID), //[1403h.01h], Название=COB-ID for RPDO4, ТекстПУ=IRPDO4, EngText=COB-ID for RPDO4, группа=CAN +(long)(&co1_vars.co_transType), //[1403h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_RPDO5COBID), //[1404h.01h], Название=COB-ID for RPDO5, ТекстПУ=IRPDO5, EngText=COB-ID for RPDO5, группа=CAN +(long)(&co1_vars.co_transType), //[1404h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_RPDO6COBID), //[1405h.01h], Название=COB-ID for RPDO6, ТекстПУ=IRPDO6, EngText=COB-ID for RPDO6, группа=CAN +(long)(&co1_vars.co_transType), //[1405h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_RPDO7COBID), //[1406h.01h], Название=COB-ID for RPDO7, ТекстПУ=IRPDO7, EngText=COB-ID for RPDO7, группа=CAN +(long)(&co1_vars.co_transType), //[1406h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_RPDO8COBID), //[1407h.01h], Название=COB-ID for RPDO8, ТекстПУ=IRPDO8, EngText=COB-ID for RPDO8, группа=CAN +(long)(&co1_vars.co_transType), //[1407h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_RPDO1_1Mapping), //[1600h.01h], Название=RPDO1-1 Mapping, ТекстПУ=RPM11, EngText=RPDO1-1 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO1_2Mapping), //[1600h.02h], Название=RPDO1-2 Mapping, ТекстПУ=RPM12, EngText=RPDO1-2 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO1_3Mapping), //[1600h.03h], Название=RPDO1-3 Mapping, ТекстПУ=RPM13, EngText=RPDO1-3 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO1_4Mapping), //[1600h.04h], Название=RPDO1-4 Mapping, ТекстПУ=RPM14, EngText=RPDO1-4 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO2_1Mapping), //[1601h.01h], Название=RPDO2-1 Mapping, ТекстПУ=RPM21, EngText=RPDO2-1 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO2_2Mapping), //[1601h.02h], Название=RPDO2-2 Mapping, ТекстПУ=RPM22, EngText=RPDO2-2 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO2_3Mapping), //[1601h.03h], Название=RPDO2-3 Mapping, ТекстПУ=RPM23, EngText=RPDO2-3 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO2_4Mapping), //[1601h.04h], Название=RPDO2-4 Mapping, ТекстПУ=RPM24, EngText=RPDO2-4 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO3_1Mapping), //[1602h.01h], Название=RPDO3-1 Mapping, ТекстПУ=RPM31, EngText=RPDO3-1 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO3_2Mapping), //[1602h.02h], Название=RPDO3-2 Mapping, ТекстПУ=RPM32, EngText=RPDO3-2 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO3_3Mapping), //[1602h.03h], Название=RPDO3-3 Mapping, ТекстПУ=RPM33, EngText=RPDO3-3 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO3_4Mapping), //[1602h.04h], Название=RPDO3-4 Mapping, ТекстПУ=RPM34, EngText=RPDO3-4 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO4_1Mapping), //[1603h.01h], Название=RPDO4-1 Mapping, ТекстПУ=RPM41, EngText=RPDO4-1 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO4_2Mapping), //[1603h.02h], Название=RPDO4-2 Mapping, ТекстПУ=RPM42, EngText=RPDO4-2 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO4_3Mapping), //[1603h.03h], Название=RPDO4-3 Mapping, ТекстПУ=RPM43, EngText=RPDO4-3 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO4_4Mapping), //[1603h.04h], Название=RPDO4-4 Mapping, ТекстПУ=RPM44, EngText=RPDO4-4 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO5_1Mapping), //[1604h.01h], Название=RPDO5-1 Mapping, ТекстПУ=RPM51, EngText=RPDO5-1 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO5_2Mapping), //[1604h.02h], Название=RPDO5-2 Mapping, ТекстПУ=RPM52, EngText=RPDO5-2 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO5_3Mapping), //[1604h.03h], Название=RPDO5-3 Mapping, ТекстПУ=RPM53, EngText=RPDO5-3 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO5_4Mapping), //[1604h.04h], Название=RPDO5-4 Mapping, ТекстПУ=RPM54, EngText=RPDO5-4 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO6_1Mapping), //[1605h.01h], Название=RPDO6-1 Mapping, ТекстПУ=RPM61, EngText=RPDO6-1 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO6_2Mapping), //[1605h.02h], Название=RPDO6-2 Mapping, ТекстПУ=RPM62, EngText=RPDO6-2 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO6_3Mapping), //[1605h.03h], Название=RPDO6-3 Mapping, ТекстПУ=RPM63, EngText=RPDO6-3 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO6_4Mapping), //[1605h.04h], Название=RPDO6-4 Mapping, ТекстПУ=RPM64, EngText=RPDO6-4 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO7_1Mapping), //[1606h.01h], Название=RPDO7-1 Mapping, ТекстПУ=RPM71, EngText=RPDO7-1 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO7_2Mapping), //[1606h.02h], Название=RPDO7-2 Mapping, ТекстПУ=RPM72, EngText=RPDO7-2 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO7_3Mapping), //[1606h.03h], Название=RPDO7-3 Mapping, ТекстПУ=RPM73, EngText=RPDO7-3 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO7_4Mapping), //[1606h.04h], Название=RPDO7-4 Mapping, ТекстПУ=RPM74, EngText=RPDO7-4 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO8_1Mapping), //[1607h.01h], Название=RPDO8-1 Mapping, ТекстПУ=RPM81, EngText=RPDO8-1 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO8_2Mapping), //[1607h.02h], Название=RPDO8-2 Mapping, ТекстПУ=RPM82, EngText=RPDO8-2 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO8_3Mapping), //[1607h.03h], Название=RPDO8-3 Mapping, ТекстПУ=RPM83, EngText=RPDO8-3 Mapping, группа=CAN +(long)(&co1_vars.co_RPDO8_4Mapping), //[1607h.04h], Название=RPDO8-4 Mapping, ТекстПУ=RPM84, EngText=RPDO8-4 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO1COBID), //[1800h.01h], Название=COB-ID for TPDO1, ТекстПУ=ITPDO1, EngText=COB-ID for TPDO1, группа=CAN +(long)(&co1_vars.co_transType), //[1800h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_TPDO1ITime), //[1800h.03h], Название=Inhibit Time 1, ТекстПУ=ITime1, EngText=Inhibit Time 1, группа=CAN +(long)(&co1_vars.co_compatEntry), //[1800h.04h], Название=Compatibility Entry, ТекстПУ=CompEn, EngText=Compatibility Entry, группа=CAN +(long)(&co1_vars.co_TPDO1EventTimer), //[1800h.05h], Название=Event Timer 1, ТекстПУ=EvTmr1, EngText=Event Timer 1, группа=CAN +(long)(&co1_vars.co_TPDO2COBID), //[1801h.01h], Название=COB-ID for TPDO2, ТекстПУ=ITPDO2, EngText=COB-ID for TPDO2, группа=CAN +(long)(&co1_vars.co_transType), //[1801h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_TPDO2ITime), //[1801h.03h], Название=Inhibit Time 2, ТекстПУ=ITime2, EngText=Inhibit Time 2, группа=CAN +(long)(&co1_vars.co_compatEntry), //[1801h.04h], Название=Compatibility Entry, ТекстПУ=CompEn, EngText=Compatibility Entry, группа=CAN +(long)(&co1_vars.co_TPDO2EventTimer), //[1801h.05h], Название=Event Timer 2, ТекстПУ=EvTmr2, EngText=Event Timer 2, группа=CAN +(long)(&co1_vars.co_TPDO3COBID), //[1802h.01h], Название=COB-ID for TPDO3, ТекстПУ=ITPDO3, EngText=COB-ID for TPDO3, группа=CAN +(long)(&co1_vars.co_transType), //[1802h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_TPDO3ITime), //[1802h.03h], Название=Inhibit Time 3, ТекстПУ=ITime3, EngText=Inhibit Time 3, группа=CAN +(long)(&co1_vars.co_compatEntry), //[1802h.04h], Название=Compatibility Entry, ТекстПУ=CompEn, EngText=Compatibility Entry, группа=CAN +(long)(&co1_vars.co_TPDO3EventTimer), //[1802h.05h], Название=Event Timer 3, ТекстПУ=EvTmr3, EngText=Event Timer 3, группа=CAN +(long)(&co1_vars.co_TPDO4COBID), //[1803h.01h], Название=COB-ID for TPDO4, ТекстПУ=ITPDO4, EngText=COB-ID for TPDO4, группа=CAN +(long)(&co1_vars.co_transType), //[1803h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_TPDO4ITime), //[1803h.03h], Название=Inhibit Time 4, ТекстПУ=ITime4, EngText=Inhibit Time 4, группа=CAN +(long)(&co1_vars.co_compatEntry), //[1803h.04h], Название=Compatibility Entry, ТекстПУ=CompEn, EngText=Compatibility Entry, группа=CAN +(long)(&co1_vars.co_TPDO4EventTimer), //[1803h.05h], Название=Event Timer 4, ТекстПУ=EvTmr4, EngText=Event Timer 4, группа=CAN +(long)(&co1_vars.co_TPDO5COBID), //[1804h.01h], Название=COB-ID for TPDO5, ТекстПУ=ITPDO5, EngText=COB-ID for TPDO5, группа=CAN +(long)(&co1_vars.co_transType), //[1804h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_TPDO5ITime), //[1804h.03h], Название=Inhibit Time 5, ТекстПУ=ITime5, EngText=Inhibit Time 5, группа=CAN +(long)(&co1_vars.co_compatEntry), //[1804h.04h], Название=Compatibility Entry, ТекстПУ=CompEn, EngText=Compatibility Entry, группа=CAN +(long)(&co1_vars.co_TPDO5EventTimer), //[1804h.05h], Название=Event Timer 5, ТекстПУ=EvTmr5, EngText=Event Timer 5, группа=CAN +(long)(&co1_vars.co_TPDO6COBID), //[1805h.01h], Название=COB-ID for TPDO6, ТекстПУ=ITPDO6, EngText=COB-ID for TPDO6, группа=CAN +(long)(&co1_vars.co_transType), //[1805h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_TPDO6ITime), //[1805h.03h], Название=Inhibit Time 6, ТекстПУ=ITime6, EngText=Inhibit Time 6, группа=CAN +(long)(&co1_vars.co_compatEntry), //[1805h.04h], Название=Compatibility Entry, ТекстПУ=CompEn, EngText=Compatibility Entry, группа=CAN +(long)(&co1_vars.co_TPDO6EventTimer), //[1805h.05h], Название=Event Timer 6, ТекстПУ=EvTmr6, EngText=Event Timer 6, группа=CAN +(long)(&co1_vars.co_TPDO7COBID), //[1806h.01h], Название=COB-ID for TPDO7, ТекстПУ=ITPDO7, EngText=COB-ID for TPDO7, группа=CAN +(long)(&co1_vars.co_transType), //[1806h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_TPDO7ITime), //[1806h.03h], Название=Inhibit Time 7, ТекстПУ=ITime7, EngText=Inhibit Time 7, группа=CAN +(long)(&co1_vars.co_compatEntry), //[1806h.04h], Название=Compatibility Entry, ТекстПУ=CompEn, EngText=Compatibility Entry, группа=CAN +(long)(&co1_vars.co_TPDO7EventTimer), //[1806h.05h], Название=Event Timer 7, ТекстПУ=EvTmr7, EngText=Event Timer 7, группа=CAN +(long)(&co1_vars.co_TPDO8COBID), //[1807h.01h], Название=COB-ID for TPDO8, ТекстПУ=ITPDO8, EngText=COB-ID for TPDO8, группа=CAN +(long)(&co1_vars.co_transType), //[1807h.02h], Название=Тип передачи, ТекстПУ=TransT, EngText=Transmission Type, группа=CAN +(long)(&co1_vars.co_TPDO8ITime), //[1807h.03h], Название=Inhibit Time 8, ТекстПУ=ITime8, EngText=Inhibit Time 8, группа=CAN +(long)(&co1_vars.co_compatEntry), //[1807h.04h], Название=Compatibility Entry, ТекстПУ=CompEn, EngText=Compatibility Entry, группа=CAN +(long)(&co1_vars.co_TPDO8EventTimer), //[1807h.05h], Название=Event Timer 8, ТекстПУ=EvTmr8, EngText=Event Timer 8, группа=CAN +(long)(&co1_vars.co_TPDO1_1Mapping), //[1A00h.01h], Название=TPDO1-1 Mapping, ТекстПУ=TPM11, EngText=TPDO1-1 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO1_2Mapping), //[1A00h.02h], Название=TPDO1-2 Mapping, ТекстПУ=TPM12, EngText=TPDO1-2 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO1_3Mapping), //[1A00h.03h], Название=TPDO1-3 Mapping, ТекстПУ=TPM13, EngText=TPDO1-3 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO1_4Mapping), //[1A00h.04h], Название=TPDO1-4 Mapping, ТекстПУ=TPM14, EngText=TPDO1-4 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO2_1Mapping), //[1A01h.01h], Название=TPDO2-1 Mapping, ТекстПУ=TPM21, EngText=TPDO2-1 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO2_2Mapping), //[1A01h.02h], Название=TPDO2-2 Mapping, ТекстПУ=TPM22, EngText=TPDO2-2 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO2_3Mapping), //[1A01h.03h], Название=TPDO2-3 Mapping, ТекстПУ=TPM23, EngText=TPDO2-3 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO2_4Mapping), //[1A01h.04h], Название=TPDO2-4 Mapping, ТекстПУ=TPM24, EngText=TPDO2-4 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO3_1Mapping), //[1A02h.01h], Название=TPDO3-1 Mapping, ТекстПУ=TPM31, EngText=TPDO3-1 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO3_2Mapping), //[1A02h.02h], Название=TPDO3-2 Mapping, ТекстПУ=TPM32, EngText=TPDO3-2 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO3_3Mapping), //[1A02h.03h], Название=TPDO3-3 Mapping, ТекстПУ=TPM33, EngText=TPDO3-3 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO3_4Mapping), //[1A02h.04h], Название=TPDO3-4 Mapping, ТекстПУ=TPM34, EngText=TPDO3-4 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO4_1Mapping), //[1A03h.01h], Название=TPDO4-1 Mapping, ТекстПУ=TPM41, EngText=TPDO4-1 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO4_2Mapping), //[1A03h.02h], Название=TPDO4-2 Mapping, ТекстПУ=TPM42, EngText=TPDO4-2 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO4_3Mapping), //[1A03h.03h], Название=TPDO4-3 Mapping, ТекстПУ=TPM43, EngText=TPDO4-3 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO4_4Mapping), //[1A03h.04h], Название=TPDO4-4 Mapping, ТекстПУ=TPM44, EngText=TPDO4-4 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO5_1Mapping), //[1A04h.01h], Название=TPDO5-1 Mapping, ТекстПУ=TPM51, EngText=TPDO5-1 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO5_2Mapping), //[1A04h.02h], Название=TPDO5-2 Mapping, ТекстПУ=TPM52, EngText=TPDO5-2 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO5_3Mapping), //[1A04h.03h], Название=TPDO5-3 Mapping, ТекстПУ=TPM53, EngText=TPDO5-3 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO5_4Mapping), //[1A04h.04h], Название=TPDO5-4 Mapping, ТекстПУ=TPM54, EngText=TPDO5-4 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO6_1Mapping), //[1A05h.01h], Название=TPDO6-1 Mapping, ТекстПУ=TPM61, EngText=TPDO6-1 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO6_2Mapping), //[1A05h.02h], Название=TPDO6-2 Mapping, ТекстПУ=TPM62, EngText=TPDO6-2 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO6_3Mapping), //[1A05h.03h], Название=TPDO6-3 Mapping, ТекстПУ=TPM63, EngText=TPDO6-3 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO6_4Mapping), //[1A05h.04h], Название=TPDO6-4 Mapping, ТекстПУ=TPM64, EngText=TPDO6-4 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO7_1Mapping), //[1A06h.01h], Название=TPDO7-1 Mapping, ТекстПУ=TPM71, EngText=TPDO7-1 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO7_2Mapping), //[1A06h.02h], Название=TPDO7-2 Mapping, ТекстПУ=TPM72, EngText=TPDO7-2 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO7_3Mapping), //[1A06h.03h], Название=TPDO7-3 Mapping, ТекстПУ=TPM73, EngText=TPDO7-3 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO7_4Mapping), //[1A06h.04h], Название=TPDO7-4 Mapping, ТекстПУ=TPM74, EngText=TPDO7-4 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO8_1Mapping), //[1A07h.01h], Название=TPDO8-1 Mapping, ТекстПУ=TPM81, EngText=TPDO8-1 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO8_2Mapping), //[1A07h.02h], Название=TPDO8-2 Mapping, ТекстПУ=TPM82, EngText=TPDO8-2 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO8_3Mapping), //[1A07h.03h], Название=TPDO8-3 Mapping, ТекстПУ=TPM83, EngText=TPDO8-3 Mapping, группа=CAN +(long)(&co1_vars.co_TPDO8_4Mapping), //[1A07h.04h], Название=TPDO8-4 Mapping, ТекстПУ=TPM84, EngText=TPDO8-4 Mapping, группа=CAN +(long)(&co1_vars.co_nodeID), //[2000h.00h], Название=CAN NODE-ID, ТекстПУ=NodeID, EngText=CAN NODE-ID, группа=CAN +(long)(&co1_vars.co_bitRate), //[2001h.00h], Название=CAN Bit Rate, ТекстПУ=CANBR, EngText=CAN Bit Rate, группа=CAN +(long)(&co1_vars.co_vendorID), //[2002h.01h], Название=Код производителя, ТекстПУ=VendID, EngText=Vendor ID, группа=CAN +(long)(&co1_vars.co_productCode), //[2002h.02h], Название=Код продукта, ТекстПУ=PrCode, EngText=Product Code, группа=CAN +(long)(&co1_vars.co_revisionNumber), //[2002h.03h], Название=Номер ревизии, ТекстПУ=RevNum, EngText=Revision Number, группа=CAN +(long)(&co1_vars.co_serialNumber), //[2002h.04h], Название=Серийный номер, ТекстПУ=SerNum, EngText=Serial Number, группа=CAN +(long)(&co1_vars.co_specialData1), //[2003h.01h], Название=Special Data 1, ТекстПУ=SpDat1, EngText=Special Data 1, группа=CAN +(long)(&co1_vars.co_specialData2), //[2003h.02h], Название=Special Data 2, ТекстПУ=SpDat2, EngText=Special Data 2, группа=CAN +(long)(&co1_vars.co_specialData3), //[2003h.03h], Название=Special Data 3, ТекстПУ=SpDat3, EngText=Special Data 3, группа=CAN +(long)(&co1_vars.co_specialData4), //[2003h.04h], Название=Special Data 4, ТекстПУ=SpDat4, EngText=Special Data 4, группа=CAN +(long)(&co1_vars.co_secretCode), //[2004h.00h], Название=Secret Code, ТекстПУ=Secret, EngText=Secret Code, группа=CAN +(long)(&co1_vars.co_protectBit), //[2005h.00h], Название=Protect Bit, ТекстПУ=ProtBt, EngText=Protect Bit, группа=CAN +(long)(&co1_odHash[0]), //[2007h.01h], Название=md5_hash_0, ТекстПУ=md5_hash_0, EngText=md5_hash_0, группа=CAN +(long)(&co1_odHash[1]), //[2007h.02h], Название=md5_hash_1, ТекстПУ=md5_hash_1, EngText=md5_hash_1, группа=CAN +(long)(&co1_odHash[2]), //[2007h.03h], Название=md5_hash_2, ТекстПУ=md5_hash_2, EngText=md5_hash_2, группа=CAN +(long)(&co1_odHash[3]), //[2007h.04h], Название=md5_hash_3, ТекстПУ=md5_hash_3, EngText=md5_hash_3, группа=CAN +(long)(&co1_vars.co_heartbeatFlag0), //[2010h.01h], Название=Heartbeat Flag 0-31, ТекстПУ=HFlag0, EngText=Heartbeat Flag 0-31, группа=CAN +(long)(&co1_vars.co_heartbeatFlag1), //[2010h.02h], Название=Heartbeat Flag 32-63, ТекстПУ=HFlag1, EngText=Heartbeat Flag 32-63, группа=CAN +(long)(&co1_vars.co_heartbeatFlag2), //[2010h.03h], Название=Heartbeat Flag 64-95, ТекстПУ=HFlag2, EngText=Heartbeat Flag 64-95, группа=CAN +(long)(&co1_vars.co_heartbeatFlag3), //[2010h.04h], Название=Heartbeat Flag 96-127, ТекстПУ=HFlag3, EngText=Heartbeat Flag 96-127, группа=CAN +(long)(&co1_vars.co_heartbeatMask0), //[2011h.01h], Название=Heartbeat Mask 0-31, ТекстПУ=HMask0, EngText=Heartbeat Mask 0-31, группа=CAN +(long)(&co1_vars.co_heartbeatMask1), //[2011h.02h], Название=Heartbeat Mask 32-63, ТекстПУ=HMask1, EngText=Heartbeat Mask 32-63, группа=CAN +(long)(&co1_vars.co_heartbeatMask2), //[2011h.03h], Название=Heartbeat Mask 64-95, ТекстПУ=HMask2, EngText=Heartbeat Mask 64-95, группа=CAN +(long)(&co1_vars.co_heartbeatMask3), //[2011h.04h], Название=Heartbeat Mask 96-127, ТекстПУ=HMask3, EngText=Heartbeat Mask 96-127, группа=CAN +(long)(&co1_vars.co_heartbeatAutoStart), //[2012h.00h], Название=Heartbeat Autostart, ТекстПУ=HBASta, EngText=Heartbeat Autostart, группа=CAN +(long)(&co1_vars.co_heartbeatAutoRecovery), //[2014h.00h], Название=Heartbeat Autorecovery, ТекстПУ=HBARec, EngText=Heartbeat Autorecovery, группа=CAN +(long)(&co1_vars.co_nodeState), //[2015h.00h], Название=Состояние драйвера CAN-Open, ТекстПУ=State, EngText=Состояние драйвера CAN-Open, группа=CAN +(long)(&co1_vars.co_emergencyErrorCode), //[2016h.00h], Название=Emergency Error Code, ТекстПУ=EmErCo, EngText=Emergency Error Code, группа=CAN +(long)(&co1_vars.co_deviceErrorState), //[2017h.00h], Название=Device Error State, ТекстПУ=DeErSt, EngText=Device Error State, группа=CAN +(long)(&co1_vars.co_ODCommand), //[2080h.01h], Название=Object Dictionary Command, ТекстПУ=ODComm, EngText=Object Dictionary Command, группа=CAN +(long)(&co1_vars.co_currentODIndex), //[2080h.02h], Название=Current OD Index, ТекстПУ=ODCInd, EngText=Current OD Index, группа=CAN +(long)(&co1_vars.co_currentODSubIndex), //[2080h.03h], Название=Current OD Sub-Index, ТекстПУ=ODCSub, EngText=Current OD Sub-Index, группа=CAN +(long)(&co1_vars.co_currentODEText), //[2080h.04h], Название=Current OD Element Text, ТекстПУ=ODCTxt, EngText=Current OD Element Text, группа=CAN +(long)(&co1_vars.co_currentODEFormat), //[2080h.05h], Название=Current OD Element Format, ТекстПУ=ODCFrm, EngText=Current OD Element Format, группа=CAN +(long)(&co1_vars.co_currentODEMin), //[2080h.06h], Название=Current OD Element Min, ТекстПУ=ODCMin, EngText=Current OD Element Min, группа=CAN +(long)(&co1_vars.co_currentODEMax), //[2080h.07h], Название=Current OD Element Max, ТекстПУ=ODCMax, EngText=Current OD Element Max, группа=CAN +(long)(&co1_vars.co_currentODEDefault), //[2080h.08h], Название=Current OD Element Default, ТекстПУ=ODCDef, EngText=Current OD Element Default, группа=CAN +(long)(&co1_vars.co_currentODEMinLow), //[2080h.09h], Название=Current OD Element MinLow, ТекстПУ=ODCMiL, EngText=Current OD Element MinLow, группа=CAN +(long)(&co1_vars.co_currentODEMaxLow), //[2080h.0Ah], Название=Current OD Element MaxLow, ТекстПУ=ODCMaL, EngText=Current OD Element MaxLow, группа=CAN +(long)(&co1_vars.co_currentODEDefaultLow), //[2080h.0Bh], Название=Current OD Element Default Low, ТекстПУ=ODCDeL, EngText=Current OD Element Default Low, группа=CAN +(long)(&co1_vars.co_currentODEAddrLow), //[2080h.0Ch], Название=Current OD Element Address, ТекстПУ=ODCAdr, EngText=Current OD Element Address, группа=CAN +(long)(&co1_vars.co_currentODEAddrLow), //[2080h.0Dh], Название=Current OD Element Address, ТекстПУ=ODCAdr, EngText=Current OD Element Address, группа=CAN +(long)(&co1_vars.co_currentODEType), //[2080h.0Eh], Название=Группа параметров, ТекстПУ=Группа, EngText=Parameter Group, группа=CAN +(long)(&co1_vars.co_odIndexSize), //[2081h.00h], Название=Количество индексов, ТекстПУ=КолИнд, EngText=Number of Indexes, группа=CAN +(long)(&co1_vars.co_defaultIndex1), //[2082h.01h], Название=Default Index 1, ТекстПУ=DfInd1, EngText=Default Index 1, группа=CAN +(long)(&co1_vars.co_defaultIndex2), //[2082h.02h], Название=Default Index 2, ТекстПУ=DfInd2, EngText=Default Index 2, группа=CAN +(long)(&co1_vars.co_maskElement01), //[2083h.01h], Название=Mask Element, ТекстПУ=MskEl0, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElement01), //[2083h.02h], Название=Mask Element, ТекстПУ=MskEl1, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElement23), //[2083h.03h], Название=Mask Element, ТекстПУ=MskEl2, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElement23), //[2083h.04h], Название=Mask Element, ТекстПУ=MskEl3, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElement45), //[2083h.05h], Название=Mask Element, ТекстПУ=MskEl4, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElement45), //[2083h.06h], Название=Mask Element, ТекстПУ=MskEl5, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElement67), //[2083h.07h], Название=Mask Element, ТекстПУ=MskEl6, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElement67), //[2083h.08h], Название=Mask Element, ТекстПУ=MskEl7, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElement89), //[2083h.09h], Название=Mask Element, ТекстПУ=MskEl8, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElement89), //[2083h.0Ah], Название=Mask Element, ТекстПУ=MskEl9, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElementAB), //[2083h.0Bh], Название=Mask Element, ТекстПУ=MskElA, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElementAB), //[2083h.0Ch], Название=Mask Element, ТекстПУ=MskElB, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElementCD), //[2083h.0Dh], Название=Mask Element, ТекстПУ=MskElC, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElementCD), //[2083h.0Eh], Название=Mask Element, ТекстПУ=MskElD, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElementEF), //[2083h.0Fh], Название=Mask Element, ТекстПУ=MskElE, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_maskElementEF), //[2083h.10h], Название=Mask Element, ТекстПУ=MskElF, EngText=Mask Element, группа=CAN +(long)(&co1_vars.co_scaleNum0), //[2100h.01h], Название=Scale Number 0, ТекстПУ=SN0, EngText=Scale Number 0, группа=CAN +(long)(&co1_vars.co_scaleNum0Format), //[2100h.02h], Название=Scale Number 0 Format, ТекстПУ=S0Fmt, EngText=Scale Number 0 Format, группа=CAN +(long)(&co1_vars.co_scaleNum0Format), //[2100h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum0Format), //[2100h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum0Format), //[2100h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum0Format), //[2100h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum1), //[2101h.01h], Название=Scale Number 1, ТекстПУ=SN1, EngText=Scale Number 1, группа=CAN +(long)(&co1_vars.co_scaleNum1Format), //[2101h.02h], Название=Scale Number 1 Format, ТекстПУ=S1Fmt, EngText=Scale Number 1 Format, группа=CAN +(long)(&co1_vars.co_scaleNum1Format), //[2101h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum1Format), //[2101h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum1Format), //[2101h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum1Format), //[2101h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum2), //[2102h.01h], Название=Scale Number 2, ТекстПУ=SN2, EngText=Scale Number 2, группа=CAN +(long)(&co1_vars.co_scaleNum2Format), //[2102h.02h], Название=Scale Number 2 Format, ТекстПУ=S2Fmt, EngText=Scale Number 2 Format, группа=CAN +(long)(&co1_vars.co_scaleNum2Format), //[2102h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum2Format), //[2102h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum2Format), //[2102h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum2Format), //[2102h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum3), //[2103h.01h], Название=Scale Number 3, ТекстПУ=SN3, EngText=Scale Number 3, группа=CAN +(long)(&co1_vars.co_scaleNum3Format), //[2103h.02h], Название=Scale Number 3 Format, ТекстПУ=S3Fmt, EngText=Scale Number 3 Format, группа=CAN +(long)(&co1_vars.co_scaleNum3Format), //[2103h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum3Format), //[2103h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum3Format), //[2103h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum3Format), //[2103h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum4), //[2104h.01h], Название=Scale Number 4, ТекстПУ=SN4, EngText=Scale Number 4, группа=CAN +(long)(&co1_vars.co_scaleNum4Format), //[2104h.02h], Название=Scale Number 4 Format, ТекстПУ=S4Fmt, EngText=Scale Number 4 Format, группа=CAN +(long)(&co1_vars.co_scaleNum4Format), //[2104h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum4Format), //[2104h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum4Format), //[2104h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum4Format), //[2104h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum5), //[2105h.01h], Название=Scale Number 5, ТекстПУ=SN5, EngText=Scale Number 5, группа=CAN +(long)(&co1_vars.co_scaleNum5Format), //[2105h.02h], Название=Scale Number 5 Format, ТекстПУ=S5Fmt, EngText=Scale Number 5 Format, группа=CAN +(long)(&co1_vars.co_scaleNum5Format), //[2105h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum5Format), //[2105h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum5Format), //[2105h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum5Format), //[2105h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum6), //[2106h.01h], Название=Scale Number 6, ТекстПУ=SN6, EngText=Scale Number 6, группа=CAN +(long)(&co1_vars.co_scaleNum6Format), //[2106h.02h], Название=Scale Number 6 Format, ТекстПУ=S6Fmt, EngText=Scale Number 6 Format, группа=CAN +(long)(&co1_vars.co_scaleNum6Format), //[2106h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum6Format), //[2106h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum6Format), //[2106h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum6Format), //[2106h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum7), //[2107h.01h], Название=Scale Number 7, ТекстПУ=SN7, EngText=Scale Number 7, группа=CAN +(long)(&co1_vars.co_scaleNum7Format), //[2107h.02h], Название=Scale Number 7 Format, ТекстПУ=S7Fmt, EngText=Scale Number 7 Format, группа=CAN +(long)(&co1_vars.co_scaleNum7Format), //[2107h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum7Format), //[2107h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum7Format), //[2107h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum7Format), //[2107h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum8), //[2108h.01h], Название=Scale Number 8, ТекстПУ=SN8, EngText=Scale Number 8, группа=CAN +(long)(&co1_vars.co_scaleNum8Format), //[2108h.02h], Название=Scale Number 8 Format, ТекстПУ=S8Fmt, EngText=Scale Number 8 Format, группа=CAN +(long)(&co1_vars.co_scaleNum8Format), //[2108h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum8Format), //[2108h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum8Format), //[2108h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum8Format), //[2108h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum9), //[2109h.01h], Название=Scale Number 9, ТекстПУ=SN9, EngText=Scale Number 9, группа=CAN +(long)(&co1_vars.co_scaleNum9Format), //[2109h.02h], Название=Scale Number 9 Format, ТекстПУ=S9Fmt, EngText=Scale Number 9 Format, группа=CAN +(long)(&co1_vars.co_scaleNum9Format), //[2109h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum9Format), //[2109h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum9Format), //[2109h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum9Format), //[2109h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNumA), //[210Ah.01h], Название=Scale Number A, ТекстПУ=SNA, EngText=Scale Number A, группа=CAN +(long)(&co1_vars.co_scaleNumAFormat), //[210Ah.02h], Название=Scale Number A Format, ТекстПУ=SAFmt, EngText=Scale Number A Format, группа=CAN +(long)(&co1_vars.co_scaleNumAFormat), //[210Ah.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNumAFormat), //[210Ah.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNumAFormat), //[210Ah.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNumAFormat), //[210Ah.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNumB), //[210Bh.01h], Название=Scale Number B, ТекстПУ=SNB, EngText=Scale Number B, группа=CAN +(long)(&co1_vars.co_scaleNumBFormat), //[210Bh.02h], Название=Scale Number B Format, ТекстПУ=SBFmt, EngText=Scale Number B Format, группа=CAN +(long)(&co1_vars.co_scaleNumBFormat), //[210Bh.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNumBFormat), //[210Bh.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNumBFormat), //[210Bh.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNumBFormat), //[210Bh.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNumC), //[210Ch.01h], Название=Scale Number C, ТекстПУ=SNC, EngText=Scale Number C, группа=CAN +(long)(&co1_vars.co_scaleNumCFormat), //[210Ch.02h], Название=Scale Number C Format, ТекстПУ=SCFmt, EngText=Scale Number C Format, группа=CAN +(long)(&co1_vars.co_scaleNumCFormat), //[210Ch.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNumCFormat), //[210Ch.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNumCFormat), //[210Ch.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNumCFormat), //[210Ch.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNumD), //[210Dh.01h], Название=Scale Number D, ТекстПУ=SND, EngText=Scale Number D, группа=CAN +(long)(&co1_vars.co_scaleNumDFormat), //[210Dh.02h], Название=Scale Number D Format, ТекстПУ=SDFmt, EngText=Scale Number D Format, группа=CAN +(long)(&co1_vars.co_scaleNumDFormat), //[210Dh.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNumDFormat), //[210Dh.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNumDFormat), //[210Dh.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNumDFormat), //[210Dh.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNumE), //[210Eh.01h], Название=Scale Number E, ТекстПУ=SNE, EngText=Scale Number E, группа=CAN +(long)(&co1_vars.co_scaleNumEFormat), //[210Eh.02h], Название=Scale Number E Format, ТекстПУ=SEFmt, EngText=Scale Number E Format, группа=CAN +(long)(&co1_vars.co_scaleNumEFormat), //[210Eh.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNumEFormat), //[210Eh.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNumEFormat), //[210Eh.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNumEFormat), //[210Eh.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNumF), //[210Fh.01h], Название=Scale Number F, ТекстПУ=SNF, EngText=Scale Number F, группа=CAN +(long)(&co1_vars.co_scaleNumFFormat), //[210Fh.02h], Название=Scale Number F Format, ТекстПУ=SFFmt, EngText=Scale Number F Format, группа=CAN +(long)(&co1_vars.co_scaleNumFFormat), //[210Fh.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNumFFormat), //[210Fh.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNumFFormat), //[210Fh.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNumFFormat), //[210Fh.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum10), //[2110h.01h], Название=Scale Number 10, ТекстПУ=SN10, EngText=Scale Number 10, группа=CAN +(long)(&co1_vars.co_scaleNum10Format), //[2110h.02h], Название=Scale Number 10 Format, ТекстПУ=S10Fmt, EngText=Scale Number 10 Format, группа=CAN +(long)(&co1_vars.co_scaleNum10Format), //[2110h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum10Format), //[2110h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum10Format), //[2110h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum10Format), //[2110h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum11), //[2111h.01h], Название=Scale Number 11, ТекстПУ=SN11, EngText=Scale Number 11, группа=CAN +(long)(&co1_vars.co_scaleNum11Format), //[2111h.02h], Название=Scale Number 11 Format, ТекстПУ=S11Fmt, EngText=Scale Number 11 Format, группа=CAN +(long)(&co1_vars.co_scaleNum11Format), //[2111h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum11Format), //[2111h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum11Format), //[2111h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum11Format), //[2111h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum12), //[2112h.01h], Название=Scale Number 12, ТекстПУ=SN12, EngText=Scale Number 12, группа=CAN +(long)(&co1_vars.co_scaleNum12Format), //[2112h.02h], Название=Scale Number 12 Format, ТекстПУ=S12Fmt, EngText=Scale Number 12 Format, группа=CAN +(long)(&co1_vars.co_scaleNum12Format), //[2112h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum12Format), //[2112h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum12Format), //[2112h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum12Format), //[2112h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum13), //[2113h.01h], Название=Scale Number 13, ТекстПУ=SN13, EngText=Scale Number 13, группа=CAN +(long)(&co1_vars.co_scaleNum13Format), //[2113h.02h], Название=Scale Number 13 Format, ТекстПУ=S13Fmt, EngText=Scale Number 13 Format, группа=CAN +(long)(&co1_vars.co_scaleNum13Format), //[2113h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum13Format), //[2113h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum13Format), //[2113h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum13Format), //[2113h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum14), //[2114h.01h], Название=Scale Number 14, ТекстПУ=SN14, EngText=Scale Number 14, группа=CAN +(long)(&co1_vars.co_scaleNum14Format), //[2114h.02h], Название=Scale Number 14 Format, ТекстПУ=S14Fmt, EngText=Scale Number 14 Format, группа=CAN +(long)(&co1_vars.co_scaleNum14Format), //[2114h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum14Format), //[2114h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum14Format), //[2114h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum14Format), //[2114h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum15), //[2115h.01h], Название=Scale Number 15, ТекстПУ=SN15, EngText=Scale Number 15, группа=CAN +(long)(&co1_vars.co_scaleNum15Format), //[2115h.02h], Название=Scale Number 15Format, ТекстПУ=S15Fmt, EngText=Scale Number 15Format, группа=CAN +(long)(&co1_vars.co_scaleNum15Format), //[2115h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum15Format), //[2115h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum15Format), //[2115h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum15Format), //[2115h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum16), //[2116h.01h], Название=Scale Number 16, ТекстПУ=SN16, EngText=Scale Number 16, группа=CAN +(long)(&co1_vars.co_scaleNum16Format), //[2116h.02h], Название=Scale Number 16Format, ТекстПУ=S16Fmt, EngText=Scale Number 16Format, группа=CAN +(long)(&co1_vars.co_scaleNum16Format), //[2116h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum16Format), //[2116h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum16Format), //[2116h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum16Format), //[2116h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum17), //[2117h.01h], Название=Scale Number 17, ТекстПУ=SN17, EngText=Scale Number 17, группа=CAN +(long)(&co1_vars.co_scaleNum17Format), //[2117h.02h], Название=Scale Number 17Format, ТекстПУ=S17Fmt, EngText=Scale Number 17Format, группа=CAN +(long)(&co1_vars.co_scaleNum17Format), //[2117h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum17Format), //[2117h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum17Format), //[2117h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum17Format), //[2117h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum18), //[2118h.01h], Название=Scale Number 18, ТекстПУ=SN18, EngText=Scale Number 18, группа=CAN +(long)(&co1_vars.co_scaleNum18Format), //[2118h.02h], Название=Scale Number 18Format, ТекстПУ=S18Fmt, EngText=Scale Number 18Format, группа=CAN +(long)(&co1_vars.co_scaleNum18Format), //[2118h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum18Format), //[2118h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum18Format), //[2118h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum18Format), //[2118h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum19), //[2119h.01h], Название=Scale Number 19, ТекстПУ=SN19, EngText=Scale Number 19, группа=CAN +(long)(&co1_vars.co_scaleNum19Format), //[2119h.02h], Название=Scale Number 19Format, ТекстПУ=S19Fmt, EngText=Scale Number 19Format, группа=CAN +(long)(&co1_vars.co_scaleNum19Format), //[2119h.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum19Format), //[2119h.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum19Format), //[2119h.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum19Format), //[2119h.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum1A), //[211Ah.01h], Название=Scale Number 1A, ТекстПУ=SN1A, EngText=Scale Number 1A, группа=CAN +(long)(&co1_vars.co_scaleNum1AFormat), //[211Ah.02h], Название=Scale Number 1AFormat, ТекстПУ=S1AFmt, EngText=Scale Number 1AFormat, группа=CAN +(long)(&co1_vars.co_scaleNum1AFormat), //[211Ah.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum1AFormat), //[211Ah.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum1AFormat), //[211Ah.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum1AFormat), //[211Ah.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum1B), //[211Bh.01h], Название=Scale Number 1B, ТекстПУ=SN1B, EngText=Scale Number 1B, группа=CAN +(long)(&co1_vars.co_scaleNum1BFormat), //[211Bh.02h], Название=Scale Number 1BFormat, ТекстПУ=S1BFmt, EngText=Scale Number 1BFormat, группа=CAN +(long)(&co1_vars.co_scaleNum1BFormat), //[211Bh.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum1BFormat), //[211Bh.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum1BFormat), //[211Bh.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum1BFormat), //[211Bh.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum1C), //[211Ch.01h], Название=Scale Number 1C, ТекстПУ=SN1C, EngText=Scale Number 1C, группа=CAN +(long)(&co1_vars.co_scaleNum1CFormat), //[211Ch.02h], Название=Scale Number 1C Format, ТекстПУ=S1CFmt, EngText=Scale Number 1C Format, группа=CAN +(long)(&co1_vars.co_scaleNum1CFormat), //[211Ch.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum1CFormat), //[211Ch.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum1CFormat), //[211Ch.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum1CFormat), //[211Ch.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&co1_vars.co_scaleNum1D), //[211Dh.01h], Название=Scale Number 1D, ТекстПУ=SN1D, EngText=Scale Number 1D, группа=CAN +(long)(&co1_vars.co_scaleNum1DFormat), //[211Dh.02h], Название=Scale Number 1D Format, ТекстПУ=S1DFmt, EngText=Scale Number 1D Format, группа=CAN +(long)(&co1_vars.co_scaleNum1DFormat), //[211Dh.03h], Название=Scale Number Format Q, ТекстПУ=Q-type, EngText=Scale Number Format Q, группа=CAN +(long)(&co1_vars.co_scaleNum1DFormat), //[211Dh.04h], Название=Scale Number Format NumOfFloat, ТекстПУ=NFloat, EngText=Scale Number Format NumOfFloat, группа=CAN +(long)(&co1_vars.co_scaleNum1DFormat), //[211Dh.05h], Название=Scale Number Format Prefix, ТекстПУ=Prefix, EngText=Scale Number Format Prefix, группа=CAN +(long)(&co1_vars.co_scaleNum1DFormat), //[211Dh.06h], Название=Scale Number Format Units, ТекстПУ=Units, EngText=Scale Number Format Units, группа=CAN +(long)(&cmd.all), //[2502h.01h], Название=Пуск, ТекстПУ=Пуск, EngText=Command: Start, группа=Слово управления +(long)(&cmd.all), //[2502h.02h], Название=Стоп, ТекстПУ=Стоп, EngText=Command: Stop, группа=Слово управления +(long)(&cmd.all), //[2502h.03h], Название=Сбросить состояние Аварии, ТекстПУ=СбрАвр, EngText=Command: Reset fault, группа=Слово управления +(long)(&cmd.all), //[2502h.04h], Название=Слово управления CAN, ТекстПУ=КмдCAN, EngText=CAN command register, группа=Слово управления +(long)(&drv_interface.req_data), //[2506h.01h], Название=Таймаут потери связи, ТекстПУ=OfflineCounterMax, EngText=OfflineCounterMax, группа=ВНЕ ГРУПП +(long)(&drv_interface.ans_data), //[2506h.02h], Название=Счетчик потери связи, ТекстПУ=OfflineCounter, EngText=OfflineCounter, группа=ВНЕ ГРУПП +(long)(&drv_interface.data_Low), //[2506h.03h], Название=data_Low, ТекстПУ=data_L, EngText=, группа=ВНЕ ГРУПП +(long)(&drv_interface.data_High), //[2506h.04h], Название=data_High, ТекстПУ=data_H, EngText=, группа=ВНЕ ГРУПП +(long)(&RTCclock.packed_time), //[250Fh.00h], Название=Часы реального времени, ТекстПУ=RTC, EngText=Real time clock, группа=Наблюдаемые +(long)(&sm_prot.Main_ErrorCode), //[2532h.01h], Название=Код аварии ARM, ТекстПУ=Код аварии ARM, EngText=, группа=Рег. тока якоря +(long)(&sm_prot.Main_ErrorCode), //[2532h.02h], Название=Расширение кода аварии, ТекстПУ=Авр+, EngText=Extension of fault ID, группа=Рег. тока якоря +(long)(&sm_prot.Main_Flags), //[2532h.03h], Название=Системный объект, ТекстПУ=System, EngText=System object, группа=Рег. тока якоря +(long)(&disp_group_number), //[2534h.01h], Название=Номер груп для пульта управления, ТекстПУ=№ гр ПУ, EngText=, группа=CAN +(long)(&VendorToken), //[2600h.01h], Название=VendorToken, ТекстПУ=VendorToken, EngText=VendorToken, группа=ВНЕ ГРУПП +(long)(&drv_status.all), //[3000h.00h], Название=Статус преобразователя, ТекстПУ=Статус, EngText=Статус преобразователя, группа=ВНЕ ГРУПП +(long)(&msCounter), //[3100h.01h], Название=Счётчик прерываний 1 кГц, ТекстПУ=Сч.прерыв.1 кГц, EngText=, группа=Счетчики +(long)(&FastCounter), //[3100h.02h], Название=Счётчик прерываний 10 кГц, ТекстПУ=Сч.прерыв.10 кГц, EngText=, группа=Счетчики +(long)(&LoopCounter), //[3100h.03h], Название=BackgroundCounter, ТекстПУ=BackgroundCounter, EngText=, группа=Счетчики +(long)(&TIsr10), //[3100h.04h], Название=T_10кГц, ТекстПУ=T_10кГц, EngText=T_10кГц, группа=Счетчики +(long)(&TIsr1), //[3100h.05h], Название=T_1кГц, ТекстПУ=T_1кГц, EngText=T_1кГц, группа=Счетчики +(long)(&rmp.T), //[5000h.01h], Название=T разгона до номинала, ТекстПУ=rmpT, EngText=T разгона до номинала, группа=ЗИ +(long)(&rmp.input), //[5000h.02h], Название=Вход ЗИ, ТекстПУ=ВходЗИ, EngText=Ramp input, группа=ЗИ +(long)(&rmp.output), //[5000h.03h], Название=Выход ЗИ, ТекстПУ=ВыходЗИ, EngText=Ramp output, группа=ЗИ +(long)(&pid_id.pid_ref_reg3), //[5100h.01h], Название=Задание, ТекстПУ=Зад-е, EngText=Reference, группа=Рег. тока Id +(long)(&pid_id.pid_fdb_reg3), //[5100h.02h], Название=Обратная связь, ТекстПУ=Обр.Св, EngText=Feedback, группа=Рег. тока Id +(long)(&pid_id.Kp_reg3), //[5100h.03h], Название=Пропорц. коэфф. Kp, ТекстПУ=Kp, EngText=Kp, группа=Рег. тока Id +(long)(&pid_id.pid_out_max), //[5100h.04h], Название=Максимум выхода, ТекстПУ=Max, EngText=Maximum Output Limits, группа=Рег. тока Id +(long)(&pid_id.pid_out_min), //[5100h.05h], Название=Минимум выхода, ТекстПУ=Min, EngText=Minimum Output Limits, группа=Рег. тока Id +(long)(&pid_id.Ki_reg3), //[5100h.06h], Название=Интегральный коэфф. Ki, ТекстПУ=Ki, EngText=Ki, группа=Рег. тока Id +(long)(&pid_id.Kd_reg3), //[5100h.07h], Название=Дифф. коэфф. Kd, ТекстПУ=Kd, EngText=Kd, группа=Рег. тока Id +(long)(&pid_id.Kc_reg3), //[5100h.08h], Название=Интегр.корректир.коэффициент, ТекстПУ=Kc, EngText=Integral correction gain, группа=Рег. тока Id +(long)(&pid_id.e_reg3), //[5100h.09h], Название=Ошибка рассогласования сигналов, ТекстПУ=Ошибка, EngText=, группа=Рег. тока Id +(long)(&pid_id.pid_out_reg3), //[5100h.0Ah], Название=Выход регулятора, ТекстПУ=Выход, EngText=Controller output, группа=Рег. тока Id +(long)(&pid_id.up_reg3), //[5100h.0Bh], Название=Вых.Пропорц., ТекстПУ=Вых.Пропорц., EngText=Ud, группа=Рег. тока Id +(long)(&pid_id.ui_reg3), //[5100h.0Ch], Название=Вых.Интегр., ТекстПУ=Вых.Интегр., EngText=Integral Output, группа=Рег. тока Id +(long)(&pid_id.ud_reg3), //[5100h.0Dh], Название=Вых.Диффер., ТекстПУ=Вых.Диффер., EngText=Ud, группа=Рег. тока Id +(long)(&pid_spd.pid_ref_reg3), //[5101h.01h], Название=Задание, ТекстПУ=pisref, EngText=Задание, группа=Рег. скорости +(long)(&pid_spd.pid_fdb_reg3), //[5101h.02h], Название=Обратная связь, ТекстПУ=pisfbd, EngText=Обратная связь, группа=Рег. скорости +(long)(&pid_spd.Kp_reg3), //[5101h.03h], Название=Пропорц. коэфф. Kp, ТекстПУ=Kp, EngText=Kp, группа=Рег. скорости +(long)(&pid_spd.pid_out_max), //[5101h.04h], Название=Максимум выхода, ТекстПУ=Max, EngText=Maximum Output Limits, группа=Рег. скорости +(long)(&pid_spd.pid_out_min), //[5101h.05h], Название=Минимум выхода, ТекстПУ=Min, EngText=Minimum Output Limits, группа=Рег. скорости +(long)(&pid_spd.Ki_reg3), //[5101h.06h], Название=Интегральный коэфф. Ki, ТекстПУ=Ki, EngText=Ki, группа=Рег. скорости +(long)(&pid_spd.Kd_reg3), //[5101h.07h], Название=Дифф. коэфф. Kd, ТекстПУ=pisKd, EngText=Дифференциальный коэффициент, группа=Рег. скорости +(long)(&pid_spd.Kc_reg3), //[5101h.08h], Название=Интегр.корректир.коэффициент, ТекстПУ=Kc, EngText=Integral correction gain, группа=Рег. скорости +(long)(&pid_spd.e_reg3), //[5101h.09h], Название=Ошибка рассогласования сигналов, ТекстПУ=Ошибка, EngText=, группа=Рег. скорости +(long)(&pid_spd.pid_out_reg3), //[5101h.0Ah], Название=Выход регулятора, ТекстПУ=pisout, EngText=Выход регулятора, группа=Рег. скорости +(long)(&pid_spd.up_reg3), //[5101h.0Bh], Название=Вых.Пропорц., ТекстПУ=Вых.Пропорц., EngText=Ud, группа=Рег. скорости +(long)(&pid_spd.ui_reg3), //[5101h.0Ch], Название=Вых.Интегр., ТекстПУ=Вых.Интегр., EngText=Integral Output, группа=Рег. скорости +(long)(&pid_spd.ud_reg3), //[5101h.0Dh], Название=Вых.Диффер., ТекстПУ=Вых.Диффер., EngText=Ud, группа=Рег. скорости +(long)(&pid_spd.saterr_reg3), //[5101h.0Eh], Название=Превышение насыщения, ТекстПУ=Прев. насыщ, EngText=saterr_reg3, группа=Рег. скорости +(long)(&pid_iq.pid_ref_reg3), //[5102h.01h], Название=Задание, ТекстПУ=Зад-ие, EngText=Задание, группа=Рег. тока Iq +(long)(&pid_iq.pid_fdb_reg3), //[5102h.02h], Название=Обратная связь, ТекстПУ=Обр.Св, EngText=Обратная связь, группа=Рег. тока Iq +(long)(&pid_iq.Kp_reg3), //[5102h.03h], Название=Пропорц. коэфф. Kp, ТекстПУ=Kp, EngText=Пропорциональный коэффициент Kp, группа=Рег. тока Iq +(long)(&pid_iq.pid_out_max), //[5102h.04h], Название=Максимум выхода, ТекстПУ=Max, EngText=Максимум выхода, группа=Рег. тока Iq +(long)(&pid_iq.pid_out_min), //[5102h.05h], Название=Минимум выхода, ТекстПУ=Min, EngText=Минимум выхода, группа=Рег. тока Iq +(long)(&pid_iq.Ki_reg3), //[5102h.06h], Название=Интегральный коэфф. Ki, ТекстПУ=Ki, EngText=Интегральный коэффициент Ki, группа=Рег. тока Iq +(long)(&pid_iq.Kd_reg3), //[5102h.07h], Название=Дифф. коэфф. Kd, ТекстПУ=Kd, EngText=Дифференциальный коэффициент Kd, группа=Рег. тока Iq +(long)(&pid_iq.Kc_reg3), //[5102h.08h], Название=Интегр.корректир.коэффициент, ТекстПУ=Kc, EngText=Integral correction gain, группа=Рег. тока Iq +(long)(&pid_iq.e_reg3), //[5102h.09h], Название=Ошибка рассогласования сигналов, ТекстПУ=Ошибка, EngText=, группа=Рег. тока Iq +(long)(&pid_iq.pid_out_reg3), //[5102h.0Ah], Название=Выход регулятора, ТекстПУ=Выход, EngText=Controller Output, группа=Рег. тока Iq +(long)(&pid_iq.up_reg3), //[5102h.0Bh], Название=Вых.Пропорц., ТекстПУ=Вых.Пропорц., EngText=Ud, группа=Рег. тока Iq +(long)(&pid_iq.ui_reg3), //[5102h.0Ch], Название=Вых.Интегр., ТекстПУ=Вых.Интегр., EngText=Integral Output, группа=Рег. тока Iq +(long)(&pid_iq.ud_reg3), //[5102h.0Dh], Название=Вых.Диффер., ТекстПУ=Вых.Диффер., EngText=Ud, группа=Рег. тока Iq +(long)(&pid_pos.pid_ref_reg3), //[5103h.01h], Название=Задание, ТекстПУ=pisref, EngText=Задание, группа=Рег. положения +(long)(&pid_pos.pid_ref_reg3), //[5103h.02h], Название=Задание, ТекстПУ=pisref, EngText=Задание, группа=Рег. положения +(long)(&pid_pos.pid_fdb_reg3), //[5103h.03h], Название=Обратная связь, ТекстПУ=pisfbd, EngText=Обратная связь, группа=Рег. положения +(long)(&pid_pos.pid_fdb_reg3), //[5103h.04h], Название=Обратная связь, ТекстПУ=pisfbd, EngText=Обратная связь, группа=Рег. положения +(long)(&pid_pos.Kp_reg3), //[5103h.05h], Название=Пропорц. коэфф. Kp, ТекстПУ=Kp, EngText=Kp, группа=Рег. положения +(long)(&pid_pos.pid_out_max), //[5103h.06h], Название=Максимум выхода, ТекстПУ=Max, EngText=Maximum Output Limits, группа=Рег. положения +(long)(&pid_pos.pid_out_min), //[5103h.07h], Название=Минимум выхода, ТекстПУ=Min, EngText=Minimum Output Limits, группа=Рег. положения +(long)(&pid_pos.Ki_reg3), //[5103h.08h], Название=Интегральный коэфф. Ki, ТекстПУ=Ki, EngText=Ki, группа=Рег. положения +(long)(&pid_pos.Kd_reg3), //[5103h.09h], Название=Дифф. коэфф. Kd, ТекстПУ=pisKd, EngText=Дифференциальный коэффициент, группа=Рег. положения +(long)(&pid_pos.DiffDelim), //[5103h.0Ah], Название=Делит. дифф. части, ТекстПУ=Делит. дифф. части, EngText=DiffDelim, группа=Рег. положения +(long)(&pid_pos.Kf_d), //[5103h.0Bh], Название=Коэф. фильтра, ТекстПУ=Коэф. фильтра, EngText=Kf_d, группа=Рег. положения +(long)(&pid_pos.Kc_reg3), //[5103h.0Ch], Название=Интегр.корректир.коэффициент, ТекстПУ=Kc, EngText=Integral correction gain, группа=Рег. положения +(long)(&pid_pos.DeadZone), //[5103h.0Dh], Название=Мертвая зона, ТекстПУ=Мертвая зона, EngText=DeadZone, группа=Рег. положения +(long)(&pid_pos.e_reg3), //[5103h.0Eh], Название=Ошибка рассогласования сигналов, ТекстПУ=Ошибка, EngText=, группа=Рег. положения +(long)(&pid_spd.saterr_reg3), //[5103h.0Fh], Название=Превышение насыщения, ТекстПУ=Прев. насыщ, EngText=saterr_reg3, группа=Рег. положения +(long)(&pid_pos.pid_out_reg3), //[5103h.10h], Название=Выход регулятора, ТекстПУ=pisout, EngText=Выход регулятора, группа=Рег. положения +(long)(&pid_pos.up_reg3), //[5103h.11h], Название=Вых.Пропорц., ТекстПУ=Вых.Пропорц., EngText=Ud, группа=Рег. положения +(long)(&pid_pos.ui_reg3), //[5103h.12h], Название=Вых.Интегр., ТекстПУ=Вых.Интегр., EngText=Integral Output, группа=Рег. положения +(long)(&pid_pos.ud_reg3), //[5103h.13h], Название=Вых.Диффер., ТекстПУ=Вых.Диффер., EngText=Ud, группа=Рег. положения +(long)(&pid_pos.e_reg3_filterOut), //[5103h.14h], Название=Фильтр ошибки, ТекстПУ=Фильтр ошибки, EngText=filterOut, группа=Рег. положения +(long)(&pwm.UalphaRef), //[5105h.01h], Название=UaЗад, ТекстПУ=UaЗад, EngText=UaЗад, группа=ШИМ +(long)(&pwm.UbetaRef), //[5105h.02h], Название=UbЗад, ТекстПУ=UbЗад, EngText=UbЗад, группа=ШИМ +(long)(&pwm.U_lim), //[5105h.03h], Название=U_огр, ТекстПУ=U_огр, EngText=U_огр, группа=ШИМ +(long)(&pwm.GammaA), //[5105h.04h], Название=GammaA, ТекстПУ=GmA, EngText=GammaA, группа=ШИМ +(long)(&pwm.GammaB), //[5105h.05h], Название=GammaB, ТекстПУ=GmB, EngText=GammaB, группа=ШИМ +(long)(&pwm.GammaC), //[5105h.06h], Название=GammaC, ТекстПУ=GmC, EngText=GammaC, группа=ШИМ +(long)(&pwm.k_pwm), //[5105h.07h], Название=TPWM, ТекстПУ=TPWM, EngText=TPWM, группа=ШИМ +(long)(&pwm.DeadBand), //[5105h.08h], Название=Мертвое время (мкс), ТекстПУ=Мерт. время, EngText=DeadBand, группа=ШИМ +(long)(&pwm.MinGammaLimit), //[5105h.09h], Название=Ограничение мин. скважн., ТекстПУ=GamLim, EngText=GamLim, группа=ШИМ +(long)(&pwm.UdCompK), //[5105h.0Ah], Название=Коэф. компенсации Ud, ТекстПУ=UdКомпK, EngText=UdCompK, группа=ШИМ +(long)(&pwm.UdCompEnable), //[5105h.0Bh], Название=Компенсация Ud, ТекстПУ=UdКомп, EngText=UdCompEnable, группа=ШИМ +(long)(&pwm.PWM_type), //[5105h.0Ch], Название=Тип ШИМ, ТекстПУ=ТипШИМ, EngText=PWMType, группа=ШИМ +(long)(&pwm.ULimitation), //[5105h.0Dh], Название=ULimitation, ТекстПУ=ULimitation, EngText=ULimitation, группа=ШИМ +(long)(&pwm.Frequency), //[5105h.0Eh], Название=Частота ШИМ, ТекстПУ=Fшим, EngText=PWM frequency, группа=ШИМ +(long)(&pwm.sector), //[5105h.0Fh], Название=Сектор, ТекстПУ=Сектор, EngText=Sector, группа=ШИМ +(long)(&pwm.U_mag), //[5105h.10h], Название=U_ампл, ТекстПУ=U_ампл, EngText=U_ампл, группа=ШИМ +(long)(&pwm.PDP_Fault), //[5105h.11h], Название=Флаги аварий, ТекстПУ=F_bits, EngText=F_bits, группа=ШИМ +(long)(&sm_ctrl.state), //[510Bh.01h], Название=sm_state, ТекстПУ=smstat, EngText=sm_state, группа=ДА sm_ctrl +(long)(&drv_status_code), //[510Bh.02h], Название=drv_status_code, ТекстПУ=stcode, EngText=drv_status_code, группа=ДА sm_ctrl +(long)(&sm_prot.bit_fault1), //[510Eh.01h], Название=Флаги аварий 1, ТекстПУ=bitF_1, EngText=Флаги аварий 1, группа=Защиты +(long)(&sm_prot.bit_fault2), //[510Eh.02h], Название=Флаги аварий 2, ТекстПУ=bitF_2, EngText=Флаги аварий 2, группа=Защиты +(long)(&sm_prot.mask_fault1), //[510Eh.03h], Название=Маска аварий 1L, ТекстПУ=mask1L, EngText=Маска аварий 1L, группа=Защиты +(long)(&sm_prot.mask_fault1), //[510Eh.04h], Название=Маска аварий 1H, ТекстПУ=mask1H, EngText=Маска аварий 1H, группа=Защиты +(long)(&sm_prot.mask_fault2), //[510Eh.05h], Название=Маска аварий 2L, ТекстПУ=mask2L, EngText=Маска аварий 2L, группа=Защиты +(long)(&sm_prot.mask_fault2), //[510Eh.06h], Название=Маска аварий 2H, ТекстПУ=mask2H, EngText=Маска аварий 2H, группа=Защиты +(long)(&sm_prot.Imax_protect), //[510Eh.07h], Название=Максимальный ток, ТекстПУ=Макс.Ток, EngText=Максимальный ток, группа=Защиты +(long)(&sm_prot.Umax_protect), //[510Eh.08h], Название=Максимальное напряжение, ТекстПУ=Ud_max, EngText=Максимальное напряжение, группа=Защиты +(long)(&sm_prot.Umin_protect), //[510Eh.09h], Название=Минимальное напряжение, ТекстПУ=Ud_min, EngText=Минимальное напряжение, группа=Защиты +(long)(&sm_prot.speed_max), //[510Eh.0Ah], Название=Максимальная скорость, ТекстПУ=speed_max, EngText=Maximum speed, группа=Защиты +(long)(&sm_prot.T_max), //[510Eh.0Bh], Название=Максимальная температура, ТекстПУ=t_max, EngText=t_max, группа=Защиты +(long)(&refs.speed_ref), //[5112h.01h], Название=Скорость, ТекстПУ=Скор_з, EngText=Скорость, группа=Задания +(long)(&refs.Iq_ref), //[5112h.02h], Название=Макс. ток ВУ, ТекстПУ=ТокСТз, EngText=ТокСТз, группа=Задания +(long)(&refs.i_flux_ref), //[5112h.03h], Название=Ток удержания, ТекстПУ=ТокУПз, EngText=Ток удержания, группа=Задания +(long)(&refs.theta_elec), //[5112h.04h], Название=theta_elec, ТекстПУ=элекУг, EngText=theta_elec, группа=Задания +(long)(&refs.uf_ref), //[5112h.05h], Название=Заданное напряжение ОВ, ТекстПУ=Uf_ref, EngText=Uf_ref, группа=Задания +(long)(&drv_params.p), //[5113h.01h], Название=Число пар полюсов, ТекстПУ=ПарПол, EngText=Число пар полюсов, группа=Базов. парам +(long)(&drv_params.I_nom), //[5113h.02h], Название=Номинальный ток, ТекстПУ=IпчНом, EngText=Номинальный ток, группа=Базов. парам +(long)(&drv_params.U_nom), //[5113h.03h], Название=Номинальное напряжение фазн., ТекстПУ=Uф_ном, EngText=Номинальное напряжение фазн., группа=Базов. парам +(long)(&drv_params.speed_nom), //[5113h.04h], Название=Номинальная скорость, ТекстПУ=СкоростьНом, EngText=Номинальная скорость, группа=Базов. парам +(long)(&drv_params.Udc_nom), //[5113h.05h], Название=Номинальное напряжение ЗПТ, ТекстПУ=UdcНом, EngText=Номинальное напряжение ЗПТ, группа=Базов. парам +(long)(&drv_params.Rs), //[5113h.06h], Название=Rs, ТекстПУ=Rs, EngText=Rs, группа=Базов. парам +(long)(&drv_params.Ls), //[5113h.07h], Название=Ls, ТекстПУ=Ls, EngText=Ls, группа=Базов. парам +(long)(&drv_params.freq_nom), //[5113h.08h], Название=Номинальная частота, ТекстПУ=Ном.част., EngText=Rated frequency, группа=Базов. парам +(long)(&drv_params.sens_type), //[5113h.09h], Название=Тип датчика положения, ТекстПУ=Sens_type, EngText=Sensor type, группа=Базов. парам +(long)(&sw.HardwareType), //[5114h.01h], Название=Тип аппаратной части, ТекстПУ=HardwareType, EngText=HardwareType, группа=Настройки СУ +(long)(&sm_ctrl.run_mode), //[5114h.02h], Название=Режим работы, ТекстПУ=РежРаб, EngText=Mode of operation, группа=Настройки СУ +(long)(&sw.recuperation_ena), //[5114h.03h], Название=Рекуперация, ТекстПУ=Рекупр, EngText=Рекуперация, группа=Настройки СУ +(long)(&sw.AutoOffset), //[5114h.04h], Название=АЦП авто смещ., ТекстПУ=АЦПсмещ, EngText=AutoOffset, группа=Настройки СУ +(long)(&sw.Reboot), //[5114h.05h], Название=Перезагрузка, ТекстПУ=Перезагрузка, EngText=Reboot, группа=Настройки СУ +(long)(&sw.excitation_ena), //[5114h.06h], Название=Возбудитель, ТекстПУ=Возб, EngText=, группа=Настройки СУ +(long)(&adc.Imeas_a_gain), //[5116h.01h], Название=Коэффициент тока фазы А, ТекстПУ=IaУсил, EngText=Phase A Current Max. Scale, группа=АЦП +(long)(&adc.Imeas_a_offset), //[5116h.02h], Название=Смещение тока фазы А, ТекстПУ=IaСмещ, EngText=Phase A Current Offset, группа=АЦП +(long)(&adc.Imeas_a), //[5116h.03h], Название=Ток фазы А, ТекстПУ=Ia_мгн, EngText=Phase A Current, группа=АЦП +(long)(&adc.Imeas_b_gain), //[5116h.04h], Название=Коэффициент тока фазы В, ТекстПУ=IbУсил, EngText=Phase B Current Max. Scale, группа=АЦП +(long)(&adc.Imeas_b_offset), //[5116h.05h], Название=Смещение тока фазы В, ТекстПУ=IbСмещ, EngText=Phase B Current Offset, группа=АЦП +(long)(&adc.Imeas_b), //[5116h.06h], Название=Ток фазы В, ТекстПУ=Ib_мгн, EngText=Phase B Current, группа=АЦП +(long)(&adc.Imeas_c_gain), //[5116h.07h], Название=Коэффициент тока фазы C, ТекстПУ=IcУсил, EngText=Коэффициент тока фазы C, группа=АЦП +(long)(&adc.Imeas_c_offset), //[5116h.08h], Название=Смещение тока фазы C, ТекстПУ=IcСмещ, EngText=Смещение тока фазы C, группа=АЦП +(long)(&adc.Imeas_c), //[5116h.09h], Название=Ток фазы С, ТекстПУ=Ic_мгн, EngText=Phase C Current, группа=АЦП +(long)(&adc.Udc_meas_gain), //[5116h.0Ah], Название=Коэффициент напряжения ЗПТ, ТекстПУ=UdУсил, EngText=Udc Max. Scale, группа=АЦП +(long)(&adc.Udc_meas_offset), //[5116h.0Bh], Название=Смещение напряж. ЗПТ, ТекстПУ=Udсмещ, EngText=Udc Offset, группа=АЦП +(long)(&adc.Udc_meas), //[5116h.0Ch], Название=Напряжение ЗПТ, ТекстПУ=Ud, EngText=Напряжение ЗПТ, группа=АЦП +(long)(&adc.T_meas_gain), //[5116h.0Dh], Название=Коэффициент температуры, ТекстПУ=t_gain, EngText=temperature_gain, группа=АЦП +(long)(&adc.T_meas), //[5116h.0Eh], Название=Температура, ТекстПУ=t, EngText=temperature, группа=АЦП +(long)(&vhz.freq), //[511Ah.01h], Название=Выходная частота, ТекстПУ=F_вых, EngText=Выходная частота, группа=Кривая U-f +(long)(&vhz.vout), //[511Ah.02h], Название=Выходное напряжение, ТекстПУ=U_вых, EngText=Выходное напряжение, группа=Кривая U-f +(long)(&vhz.FL), //[511Ah.03h], Название=Нулевая опроная частота, ТекстПУ=f [0], EngText=Нулевая опроная частота, группа=Кривая U-f +(long)(&vhz.Vmin), //[511Ah.04h], Название=Нулевое опорное напряжение, ТекстПУ=U [0], EngText=Нулевое опорное напряжение, группа=Кривая U-f +(long)(&vhz.FH), //[511Ah.05h], Название=Первая опорная частота, ТекстПУ=f [1], EngText=Первая опорная частота, группа=Кривая U-f +(long)(&vhz.Vmax), //[511Ah.06h], Название=Первое опорное напряжение, ТекстПУ=U [1], EngText=Первое опорное напряжение, группа=Кривая U-f +(long)(&vhz.Fmax), //[511Ah.07h], Название=Максимальная частота, ТекстПУ=f max, EngText=Максимальная частота, группа=Кривая U-f +(long)(&cur_par.speed), //[5138h.01h], Название=Скорость, ТекстПУ=скор, EngText=Speed, группа=Наблюдаемые +(long)(&cur_par.power), //[5138h.02h], Название=Акт. мощность, ТекстПУ=АктМощ, EngText=main_pInd, группа=Наблюдаемые +(long)(&cur_par.Is), //[5138h.03h], Название=Ток статора, ТекстПУ=ТокСт, EngText=Ток статора, группа=Наблюдаемые +(long)(&cur_par.ThetaRefCurr), //[5138h.04h], Название=ЭлУголЗад, ТекстПУ=ЭлУголЗад, EngText=ЭлУголЗад, группа=Наблюдаемые +(long)(&cur_par.ThetaCurr), //[5138h.05h], Название=ЭлУгол, ТекстПУ=ЭлУгол, EngText=ЭлУгол, группа=Наблюдаемые +(long)(&cur_par.IsRef), //[5138h.06h], Название=Ток статора зад, ТекстПУ=ТокСтЗад, EngText=Ток статора зад, группа=Наблюдаемые +(long)(&global_time.PowerOn_time_min), //[5138h.07h], Название=Время запитанного состояния, мин, ТекстПУ=Power On Time, EngText=Power On Time, группа=Наблюдаемые +(long)(&global_time.operational_time_min), //[5138h.08h], Название=Вреря работы привода, мин, ТекстПУ=Work Time, EngText=Work Time, группа=Наблюдаемые +(long)(&dlog.mode_reset), //[5150h.01h], Название=dlog.mode_reset, ТекстПУ=mode, EngText=dlog.mode_reset, группа=dlog +(long)(&dlog.control), //[5150h.02h], Название=dlog.control, ТекстПУ=dlcont, EngText=dlog.control, группа=dlog +(long)(&dlog.ind_subind1), //[5150h.03h], Название=dlog.ind_subind1, ТекстПУ=dlisi1, EngText=dlog.ind_subind1, группа=dlog +(long)(&dlog.ind_subind2), //[5150h.04h], Название=dlog.ind_subind2, ТекстПУ=dlisi2, EngText=dlog.ind_subind2, группа=dlog +(long)(&dlog.ind_subind3), //[5150h.05h], Название=dlog.ind_subind3, ТекстПУ=dlisi3, EngText=dlog.ind_subind3, группа=dlog +(long)(&dlog.ind_subind4), //[5150h.06h], Название=dlog.ind_subind4, ТекстПУ=dlisi4, EngText=dlog.ind_subind4, группа=dlog +(long)(&dlog.StartBits), //[5150h.07h], Название=StartBitL, ТекстПУ=StrtBL, EngText=StartBitL, группа=dlog +(long)(&dlog.StartBits), //[5150h.08h], Название=StartBitH, ТекстПУ=StrtBH, EngText=StartBitH, группа=dlog +(long)(&dlog.OneShotOperation), //[5150h.09h], Название=OneShotOperation, ТекстПУ=OneShotOp, EngText=OneShotOperation, группа=dlog +(long)(&dlog.trig_shift), //[5150h.0Ah], Название=Количество точек предыстории, ТекстПУ=N предыст., EngText=Prehistory Points Number, группа=dlog +(long)(&dlog.next_value_var), //[5151h.00h], Название=dlog.next_value_var, ТекстПУ=dlnval, EngText=dlog.next_value_var, группа=ВНЕ ГРУПП +(long)(&posspeedEqep.resol), //[5152h.01h], Название=Кол-во периодов, ТекстПУ=Кол-во периодов, EngText=Resolution, группа=ДПР-Энкодер +(long)(&posspeedEqep.Posspeed_CTL.all), //[5152h.02h], Название=Наличие репера, ТекстПУ=Наличие репера, EngText=index_en, группа=ДПР-Энкодер +(long)(&posspeedEqep.SpeedCalcType), //[5152h.03h], Название=Рассчитывать скорость программно, ТекстПУ=SpeedCalcType, EngText=SpeedCalcType, группа=ДПР-Энкодер +(long)(&posspeedEqep.AngleOffset), //[5152h.04h], Название=СмещУгол, ТекстПУ=СмещУг, EngText=thetae_offset, группа=ДПР-Энкодер +(long)(&posspeedEqep.Poscnt_res), //[5152h.05h], Название=Механическ.угол в метках, ТекстПУ=Механическ.угол в ме, EngText=Ang_mech, группа=ДПР-Энкодер +(long)(&posspeedEqep.Poscnt_res16), //[5152h.06h], Название=Механическ.угол в метках, ТекстПУ=Механическ.угол в ме, EngText=Ang_mech, группа=ДПР-Энкодер +(long)(&posspeedEqep.speed_elec), //[5152h.07h], Название=Скорость , ТекстПУ=Скорость, EngText=Speed, группа=ДПР-Энкодер +(long)(&posspeedEqep.theta_elec), //[5152h.08h], Название=Угол. электр., ТекстПУ=Угол. электр., EngText=Electrical angle, группа=ДПР-Энкодер +(long)(&posspeedEqep.theta_mech), //[5152h.09h], Название=Угол мех., ТекстПУ=Угол мех., EngText=theta_mech_tmp, группа=ДПР-Энкодер +(long)(&posspeedEqep.Posspeed_CTL.all), //[5152h.0Ah], Название=Команда иниц., ТекстПУ=Команда иниц., EngText=Reinit Command, группа=ДПР-Энкодер +(long)(&posspeedEqep.speed_filter.T), //[5152h.0Bh], Название=К быстродействия фильтра скорости, ТекстПУ=Кф. скорости, EngText=, группа=ДПР-Энкодер +(long)(&posspeedEqep.Posspeed_FLG1.all), //[5152h.0Ch], Название=Posspeed_FLG1, ТекстПУ=Posspeed_FLG1, EngText=Posspeed_FLG1, группа=ДПР-Энкодер +(long)(&posspeedEqep.GPIOsValue), //[5152h.0Dh], Название=GPIOsValue, ТекстПУ=GPIOsValue, EngText=GPIOsValue, группа=ДПР-Энкодер +(long)(&posspeedEqep.UPPS_forWatch), //[5152h.0Eh], Название=UPPS, ТекстПУ=UPPS, EngText=UPPS, группа=ДПР-Энкодер +(long)(&posspeedEqep.Qcprdlat_tmp), //[5152h.0Fh], Название=QCPRD, ТекстПУ=QCPRD, EngText=QCPRD, группа=ДПР-Энкодер +(long)(&posspeedEqep.Qcprdlat16_tmp), //[5152h.10h], Название=QCPRD, ТекстПУ=QCPRD, EngText=QCPRD, группа=ДПР-Энкодер +(long)(&posspeedEqep.QEPSTS), //[5152h.11h], Название=QEPSTS, ТекстПУ=QEPSTS, EngText=QEPSTS, группа=ДПР-Энкодер +(long)(&posspeedEqep.RevolutionCounter), //[5152h.12h], Название=Число оборотов, ТекстПУ=revolCounter, EngText=Total Revolutions, группа=ДПР-Энкодер +(long)(&posspeedEqep.Poscnt_resContinouosInt8), //[5152h.13h], Название=Абс. положение в метках, ТекстПУ=qcAbsPos, EngText=Absolute position (qc), группа=ДПР-Энкодер +(long)(&posspeedEqep.Poscnt_resContinouosInt), //[5152h.14h], Название=Абс. положение в метках, ТекстПУ=qcAbsPos, EngText=Absolute position (qc), группа=ДПР-Энкодер +(long)(&posspeedEqep.Poscnt_resContinouosLong), //[5152h.15h], Название=Абс. положение в метках, ТекстПУ=qcAbsPos, EngText=Absolute position (qc), группа=ДПР-Энкодер +(long)(&posspeedEqep.theta_mechContinouos), //[5152h.16h], Название=Угол механический не огранич., ТекстПУ=Уг.мех.не_огр, EngText=theta_mechContinouos, группа=ДПР-Энкодер +(long)(&posspeedEqep.theta_elecContinouos), //[5152h.17h], Название=Угол электрический не огранич., ТекстПУ=Уг.эл.не_огр, EngText=theta_elecContinouos, группа=ДПР-Энкодер +(long)(&DPReCAP.enabled), //[5155h.01h], Название=Включен, ТекстПУ=Вкл, EngText=Enabled, группа=ДПР-Холл +(long)(&DPReCAP.Angle), //[5155h.02h], Название=ЭлУгол, ТекстПУ=ЭлУгол, EngText=ЭлУгол, группа=ДПР-Холл +(long)(&DPReCAP.speed), //[5155h.03h], Название=Скорость , ТекстПУ=Скорость, EngText=Speed, группа=ДПР-Холл +(long)(&DPReCAP.speedMIN), //[5155h.04h], Название=Уставка Скорости, ТекстПУ=Уставка Скорости, EngText=speedMIN, группа=ДПР-Холл +(long)(&DPReCAP.Angle6), //[5155h.05h], Название=ЭлУгол6, ТекстПУ=ЭлУгол6, EngText=Angle6, группа=ДПР-Холл +(long)(&DPReCAP.DPReCAP_FLG1.all), //[5155h.06h], Название=Инт-полятор вкл, ТекстПУ=Инт-полятор вкл, EngText=Инт-полятор вкл, группа=ДПР-Холл +(long)(&DPReCAP.milsecREF), //[5155h.07h], Название=Уставка обнуления скорости, ТекстПУ=Уставка обнуления ск, EngText=, группа=ДПР-Холл +(long)(&DPReCAP.speedMinREF), //[5155h.08h], Название=Скорость Мин., ТекстПУ=Скорость Мин., EngText=speed min, группа=ДПР-Холл +(long)(&DPReCAP.CAP_WrongEdgeCnt), //[5155h.09h], Название=Ложные фронты, ТекстПУ=Ложные фронты, EngText=CAP_WrongEdgeCnt, группа=ДПР-Холл +(long)(&DPReCAP.HallCode), //[5155h.0Ah], Название=Дискретные входы, ТекстПУ=Входы, EngText=Digital Inputs, группа=ДПР-Холл +(long)(&DPReCAP.AngleOffset), //[5155h.0Bh], Название=СмещУгол, ТекстПУ=СмещУг, EngText=thetae_offset, группа=ДПР-Холл +(long)(&DPReCAP.ErrorLevel), //[5155h.0Ch], Название=Уровень помех, ТекстПУ=Уровень помех, EngText=, группа=ДПР-Холл +(long)(&DPReCAP.CAP_WrongEdgeCnt1), //[5155h.0Dh], Название=Ошибка 1 канала, ТекстПУ=Ошиб_1_к., EngText=, группа=ДПР-Холл +(long)(&DPReCAP.CAP_WrongEdgeCnt2), //[5155h.0Eh], Название=Ошибка 2 канала, ТекстПУ=Ошиб_2_к., EngText=, группа=ДПР-Холл +(long)(&DPReCAP.CAP_WrongEdgeCnt3), //[5155h.0Fh], Название=Ошибка 3 канала, ТекстПУ=Ошиб_3_к., EngText=, группа=ДПР-Холл +(long)(&DPReCAP.UserDirection), //[5155h.10h], Название=Направление вращения, ТекстПУ=НапрВр, EngText=Направление вращения, группа=ДПР-Холл +(long)(&DPReCAP.WrongCodeCounterLimitPerSec), //[5155h.11h], Название=Макс.число ошибок ДПР, ТекстПУ=Макс.ош.ДПР, EngText=, группа=ДПР-Холл +(long)(&DPReCAP.WrongCodeCounter), //[5155h.12h], Название=Кол-во ошибок неверной последовательности , ТекстПУ=Ошибки последоват., EngText=, группа=ДПР-Холл +(long)(&CounterCAP_isr), //[5155h.13h], Название=Счётчик прерываний по приему, ТекстПУ=Счёт.Rx.Int., EngText=, группа=ДПР-Холл +(long)(&cap0_counter), //[5155h.14h], Название=Счётчик прерываний CAP1, ТекстПУ=Сч.прерыв.CAP1, EngText=, группа=ДПР-Холл +(long)(&cap1_counter), //[5155h.15h], Название=Счётчик прерываний CAP2, ТекстПУ=Сч.прерыв.CAP2, EngText=, группа=ДПР-Холл +(long)(&cap2_counter), //[5155h.16h], Название=Счётчик прерываний CAP3, ТекстПУ=Сч.прерыв.CAP3, EngText=, группа=ДПР-Холл +(long)(&SSI_Encoder.resol), //[5157h.01h], Название=Количество импульсов на оборот, ТекстПУ=qepTik, EngText=Количество импульсов на оборот, группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.AngleOffset), //[5157h.02h], Название=СмещУгол, ТекстПУ=СмещУг, EngText=thetae_offset, группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.Poscnt_res), //[5157h.03h], Название=Механическ.угол в метках, ТекстПУ=Механическ.угол в ме, EngText=Ang_mech, группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.speed_elec), //[5157h.04h], Название=Скорость , ТекстПУ=Скорость, EngText=Speed, группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.theta_elec), //[5157h.05h], Название=Угол. электр., ТекстПУ=Угол. электр., EngText=Electrical angle, группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.theta_mech), //[5157h.06h], Название=Угол мех., ТекстПУ=Угол мех., EngText=theta_mech_tmp, группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.theta_mech_filtered), //[5157h.07h], Название=Угол мех. фильтрованный, ТекстПУ=theta_mech_filtered, EngText=theta_mech_filtered, группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.theta_mech_filterK), //[5157h.08h], Название=К быстродействия фильтра угла, ТекстПУ=Кф. угла, EngText=, группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.RevolutionCounter), //[5157h.09h], Название=Число оборотов, ТекстПУ=revolCounter, EngText=Total Revolutions, группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.Poscnt_resContinouosLong), //[5157h.0Ah], Название=Абс. положение в метках, ТекстПУ=qcAbsPos, EngText=Absolute position (qc), группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.Poscnt_resContinouosInt8), //[5157h.0Bh], Название=Абс. положение в метках, ТекстПУ=qcAbsPos, EngText=Absolute position (qc), группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.Poscnt_resContinouosInt), //[5157h.0Ch], Название=Абс. положение в метках, ТекстПУ=qcAbsPos, EngText=Absolute position (qc), группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.theta_mechContinouos), //[5157h.0Dh], Название=Угол механический не огранич., ТекстПУ=Уг.мех.не_огр, EngText=theta_mechContinouos, группа=ДПР-SSI энкодер +(long)(&SSI_Encoder.theta_elecContinouos), //[5157h.0Eh], Название=Угол электрический не огранич., ТекстПУ=Уг.эл.не_огр, EngText=theta_elecContinouos, группа=ДПР-SSI энкодер +(long)(&Debug1), //[5174h.01h], Название=DebugL1, ТекстПУ=DebugL1, EngText=DebugL1, группа=Для отладки +(long)(&Debug1), //[5174h.02h], Название=DebugL1, ТекстПУ=DebugL1, EngText=DebugL1, группа=Для отладки +(long)(&Debug2), //[5174h.03h], Название=DebugL2, ТекстПУ=DebugL2, EngText=DebugL2, группа=Для отладки +(long)(&Debug2), //[5174h.04h], Название=DebugL2, ТекстПУ=DebugL2, EngText=DebugL2, группа=Для отладки +(long)(&Debug3), //[5174h.05h], Название=DebugI3, ТекстПУ=DebugI3, EngText=DebugI3, группа=Для отладки +(long)(&Debug3), //[5174h.06h], Название=DebugI3, ТекстПУ=DebugI3, EngText=DebugI3, группа=Для отладки +(long)(&Debug4), //[5174h.07h], Название=DebugI4, ТекстПУ=DebugI4, EngText=DebugI4, группа=Для отладки +(long)(&Debug4), //[5174h.08h], Название=DebugI4, ТекстПУ=DebugI4, EngText=DebugI4, группа=Для отладки +(long)(&DebugW1), //[5174h.09h], Название=DebugW1, ТекстПУ=DebugW1, EngText=DebugW1, группа=Для отладки +(long)(&DebugW1), //[5174h.0Ah], Название=DebugW1, ТекстПУ=DebugW1, EngText=DebugW1, группа=Для отладки +(long)(&DebugW2), //[5174h.0Bh], Название=DebugW2, ТекстПУ=DebugW2, EngText=DebugW2, группа=Для отладки +(long)(&DebugW2), //[5174h.0Ch], Название=DebugW2, ТекстПУ=DebugW2, EngText=DebugW2, группа=Для отладки +(long)(&DebugW3), //[5174h.0Dh], Название=DebugW3, ТекстПУ=DebugW3, EngText=DebugW3, группа=Для отладки +(long)(&DebugW3), //[5174h.0Eh], Название=DebugW3, ТекстПУ=DebugW3, EngText=DebugW3, группа=Для отладки +(long)(&DebugW4), //[5174h.0Fh], Название=DebugW4, ТекстПУ=DebugW4, EngText=, группа=Для отладки +(long)(&DebugW4), //[5174h.10h], Название=DebugW4, ТекстПУ=DebugW4, EngText=, группа=Для отладки +(long)(&DebugF1), //[5174h.11h], Название=DebugF1, ТекстПУ=DebugF1, EngText=, группа=Для отладки +(long)(&DebugF2), //[5174h.12h], Название=DebugF2, ТекстПУ=DebugF2, EngText=, группа=Для отладки +(long)(&DebugF3), //[5174h.13h], Название=DebugF3, ТекстПУ=DebugF3, EngText=, группа=Для отладки +(long)(&DebugF4), //[5174h.14h], Название=DebugF4, ТекстПУ=DebugF4, EngText=, группа=Для отладки +(long)(&refs.DCMspeed_ref), //[5185h.01h], Название=Задание скорости (Подч. Рег.), ТекстПУ=Зад. Скор., EngText=SpeeD Ref, группа=ДПТ Сист. Упр. +(long)(&refs.ua_ref), //[5185h.02h], Название=Заданное напряжение якоря, ТекстПУ=Ua_ref, EngText=Ua_ref, группа=ДПТ Сист. Упр. +(long)(&refs.uf_ref), //[5185h.03h], Название=Заданное напряжение ОВ, ТекстПУ=Uf_ref, EngText=Uf_ref, группа=ДПТ Сист. Упр. +(long)(&RotorObserver.Tr), //[5B04h.01h], Название=Пост. времени ротора, ТекстПУ=Tr, EngText=Tr, группа=Наблюдатель ротора АД +(long)(&RotorObserver.FluxCurrentRatio), //[5B04h.02h], Название=Соотношение тока возб. X к току Y, ТекстПУ=FluxCurrentRatio, EngText=FluxCurrentRatio, группа=Наблюдатель ротора АД +(long)(&RotorObserver.FluxCurrentMin), //[5B04h.03h], Название=Минимальный ток возбуждения, ТекстПУ=FluxCurrentMin, EngText=FluxCurrentMin, группа=Наблюдатель ротора АД +(long)(&RotorObserver.id), //[5B04h.04h], Название=Ток статора по оси D, ТекстПУ=IsD, EngText=Stator current D-Axis, группа=Наблюдатель ротора АД +(long)(&RotorObserver.iq), //[5B04h.05h], Название=Ток статора по оси Q, ТекстПУ=IsQ, EngText=Stator current Q-Axis, группа=Наблюдатель ротора АД +(long)(&RotorObserver.psi_d), //[5B04h.06h], Название=Поток ротора по оси D, ТекстПУ=PsiRD, EngText=Rotor flux D-axis, группа=Наблюдатель ротора АД +(long)(&RotorObserver.psi_q), //[5B04h.07h], Название=Поток ротора по оси Q, ТекстПУ=PsiRQ, EngText=Rotor flux Q-axis, группа=Наблюдатель ротора АД +(long)(&RotorObserver.theta_psi_elec), //[5B04h.08h], Название=Угол потока ротора, ТекстПУ=psiRalpha, EngText=Rotor flux angle, группа=Наблюдатель ротора АД +}; +Uint16 const CO1_OD_TBL2[] = { +32045, 1, 0, + +31021, 2, 1, + +32041, 3, 2, + +32013, 4, 3, + +28814, 5, 3, + +64769, 5, 4, +(Uint16)(2000), (((Uint32)2000)>>16), + +64257, 6, 5, +(Uint16)(1000), + +28801, 7, 1, + +32013, 8, 6, + +32013, 9, 7, + +32013, 10, 8, + +32013, 11, 9, + +19631, 12, 1, + +31021, 13, 10, + +31021, 14, 11, + +19632, 15, 1, + +30765, 16, 12, + +30765, 17, 13, + +29741, 18, 14, + +18607, 19, 3, + +64813, 20, 15, +(Uint16)(0x180), (((Uint32)0x180)>>16), + +28973, 21, 16, +0, +0, + +18607, 22, 3, + +64813, 23, 17, +(Uint16)(0x280), (((Uint32)0x280)>>16), + +28973, 21, 18, +0, +0, + +18607, 24, 3, + +64809, 25, 19, +(Uint16)(0x0401), (((Uint32)0x0401)>>16), + +28969, 21, 20, +0, +0, + +18607, 26, 3, + +64809, 27, 21, +(Uint16)(0x0501), (((Uint32)0x0501)>>16), + +28969, 21, 22, +0, +0, + +18607, 28, 3, + +64813, 29, 23, +(Uint16)(0x0501), (((Uint32)0x0501)>>16), + +28973, 21, 24, +0, +0, + +18607, 30, 3, + +64813, 31, 25, +(Uint16)(0x0501), (((Uint32)0x0501)>>16), + +28973, 21, 26, +0, +0, + +18607, 32, 3, + +64801, 33, 27, +(Uint16)(0x0501), (((Uint32)0x0501)>>16), + +28961, 21, 28, +0, +0, + +18607, 34, 3, + +64801, 35, 29, +(Uint16)(0x0501), (((Uint32)0x0501)>>16), + +28961, 21, 30, +0, +0, + +19633, 36, 3, + +61741, 37, 31, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 38, 32, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 39, 33, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 40, 34, +(Uint16)(0), (((Uint32)0)>>16), + +19633, 41, 3, + +61741, 42, 35, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 43, 36, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 44, 37, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 45, 38, +(Uint16)(0), (((Uint32)0)>>16), + +19629, 46, 3, + +61737, 47, 39, +(Uint16)(0), (((Uint32)0)>>16), + +61737, 48, 40, +(Uint16)(0), (((Uint32)0)>>16), + +61737, 49, 41, +(Uint16)(0), (((Uint32)0)>>16), + +61737, 50, 42, +(Uint16)(0), (((Uint32)0)>>16), + +19629, 51, 3, + +61737, 52, 43, +(Uint16)(0), (((Uint32)0)>>16), + +61737, 53, 44, +(Uint16)(0), (((Uint32)0)>>16), + +61737, 54, 45, +(Uint16)(0), (((Uint32)0)>>16), + +61737, 55, 46, +(Uint16)(0), (((Uint32)0)>>16), + +19625, 56, 3, + +61741, 57, 47, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 58, 48, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 59, 49, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 60, 50, +(Uint16)(0), (((Uint32)0)>>16), + +19625, 61, 3, + +61741, 62, 51, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 63, 52, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 64, 53, +(Uint16)(0), (((Uint32)0)>>16), + +61741, 65, 54, +(Uint16)(0), (((Uint32)0)>>16), + +19629, 66, 3, + +61729, 67, 55, +(Uint16)(0), (((Uint32)0)>>16), + +61729, 68, 56, +(Uint16)(0), (((Uint32)0)>>16), + +61729, 69, 57, +(Uint16)(0), (((Uint32)0)>>16), + +61729, 70, 58, +(Uint16)(0), (((Uint32)0)>>16), + +19629, 71, 3, + +61729, 72, 59, +(Uint16)(0), (((Uint32)0)>>16), + +61729, 73, 60, +(Uint16)(0), (((Uint32)0)>>16), + +61729, 74, 61, +(Uint16)(0), (((Uint32)0)>>16), + +61729, 75, 62, +(Uint16)(0), (((Uint32)0)>>16), + +16562, 76, 2, + +32045, 77, 63, +0, + +31021, 21, 64, +0, + +64301, 78, 65, +(Uint16)(100), + +47405, 79, 66, +(Uint16)(0), + +64301, 80, 67, +(Uint16)(100), + +16560, 81, 2, + +32045, 82, 68, +0, + +31021, 21, 69, +0, + +64301, 83, 70, +(Uint16)(100), + +47405, 79, 71, +(Uint16)(0), + +64301, 84, 72, +(Uint16)(1000), + +16562, 85, 2, + +32041, 86, 73, +0, + +31017, 21, 74, +0, + +64297, 87, 75, +(Uint16)(100), + +47401, 79, 76, +(Uint16)(0), + +64297, 88, 77, +(Uint16)(1000), + +16556, 89, 2, + +32041, 90, 78, +0, + +31017, 21, 79, +0, + +64297, 91, 80, +(Uint16)(100), + +47401, 79, 81, +(Uint16)(0), + +64297, 92, 82, +(Uint16)(1000), + +16554, 93, 2, + +32045, 94, 83, +0, + +31021, 21, 84, +0, + +64301, 95, 85, +(Uint16)(100), + +47405, 79, 86, +(Uint16)(0), + +64301, 96, 87, +(Uint16)(1000), + +16552, 97, 2, + +32045, 98, 88, +0, + +31021, 21, 89, +0, + +64301, 99, 90, +(Uint16)(100), + +47405, 79, 91, +(Uint16)(0), + +64301, 100, 92, +(Uint16)(1000), + +16554, 101, 2, + +32033, 102, 93, +0, + +31009, 21, 94, +0, + +64289, 103, 95, +(Uint16)(100), + +47393, 79, 96, +(Uint16)(0), + +64289, 104, 97, +(Uint16)(1000), + +16556, 105, 2, + +32033, 106, 98, +0, + +31009, 21, 99, +0, + +64289, 107, 100, +(Uint16)(100), + +47393, 79, 101, +(Uint16)(0), + +64289, 108, 102, +(Uint16)(1000), + +19633, 109, 3, + +63789, 110, 103, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 111, 104, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 112, 105, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 113, 106, +(Uint16)(0), (((Uint32)0)>>16), + +19633, 114, 3, + +63789, 115, 107, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 116, 108, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 117, 109, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 118, 110, +(Uint16)(0), (((Uint32)0)>>16), + +19629, 119, 3, + +63785, 120, 111, +(Uint16)(0), (((Uint32)0)>>16), + +63785, 121, 112, +(Uint16)(0), (((Uint32)0)>>16), + +63785, 122, 113, +(Uint16)(0), (((Uint32)0)>>16), + +63785, 123, 114, +(Uint16)(0), (((Uint32)0)>>16), + +19629, 124, 3, + +63785, 125, 115, +(Uint16)(0), (((Uint32)0)>>16), + +63785, 126, 116, +(Uint16)(0), (((Uint32)0)>>16), + +63785, 127, 117, +(Uint16)(0), (((Uint32)0)>>16), + +63785, 128, 118, +(Uint16)(0), (((Uint32)0)>>16), + +19625, 129, 3, + +63789, 130, 119, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 131, 120, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 132, 121, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 133, 122, +(Uint16)(0), (((Uint32)0)>>16), + +19625, 134, 3, + +63789, 135, 123, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 136, 124, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 137, 125, +(Uint16)(0), (((Uint32)0)>>16), + +63789, 138, 126, +(Uint16)(0), (((Uint32)0)>>16), + +19629, 139, 3, + +63777, 140, 127, +(Uint16)(0), (((Uint32)0)>>16), + +63777, 141, 128, +(Uint16)(0), (((Uint32)0)>>16), + +63777, 142, 129, +(Uint16)(0), (((Uint32)0)>>16), + +63777, 143, 130, +(Uint16)(0), (((Uint32)0)>>16), + +19629, 144, 3, + +63777, 145, 131, +(Uint16)(0), (((Uint32)0)>>16), + +63777, 146, 132, +(Uint16)(0), (((Uint32)0)>>16), + +63777, 147, 133, +(Uint16)(0), (((Uint32)0)>>16), + +63777, 148, 134, +(Uint16)(0), (((Uint32)0)>>16), + +64173, 149, 135, +(Uint16)(1), +1, 127, + +53469, 150, 136, +(Uint16)(3), + +28845, 7, 1, + +32041, 8, 137, + +32041, 9, 138, + +32041, 10, 139, + +32041, 11, 140, + +28845, 151, 1, + +31529, 152, 141, + +31529, 153, 142, + +31529, 154, 143, + +31529, 155, 144, + +64813, 156, 145, +(Uint16)(0), (((Uint32)0)>>16), + +20669, 157, 146, + +28845, 158, 1, + +32033, 159, 147, + +32033, 160, 148, + +32033, 161, 149, + +32033, 162, 150, + +28849, 163, 1, + +32013, 164, 151, + +32013, 165, 152, + +32013, 166, 153, + +32013, 167, 154, + +28849, 168, 3, + +64781, 169, 155, +(Uint16)(0), (((Uint32)0)>>16), + +64781, 170, 156, +(Uint16)(0), (((Uint32)0)>>16), + +64781, 171, 157, +(Uint16)(0), (((Uint32)0)>>16), + +64781, 172, 158, +(Uint16)(0), (((Uint32)0)>>16), + +53433, 173, 159, +(Uint16)(1), + +53437, 174, 160, +(Uint16)(1), + +30989, 175, 161, + +31489, 176, 162, + +32001, 177, 163, + +28859, 178, 2, + +47661, 179, 164, +(Uint16)(0), + +47661, 180, 165, +(Uint16)(0x2000), + +47661, 181, 166, +(Uint16)(0), + +31277, 182, 167, +0, + +31277, 183, 168, +0, + +31277, 184, 169, +0, + +31277, 185, 170, +0, + +31277, 186, 171, +0, + +31277, 187, 172, +0, + +31277, 188, 173, +0, + +31277, 189, 174, +0, + +31277, 190, 175, +0, + +31277, 190, 176, +0, + +31277, 191, 177, +0, + +31277, 192, 178, + +28847, 193, 3, + +48169, 194, 179, +(Uint16)(0x30000000), (((Uint32)0x30000000)>>16), + +48169, 195, 180, +(Uint16)(0x30000000), (((Uint32)0x30000000)>>16), + +28857, 196, 2, + +36905, 197, 181, +(Uint16)(0), + +36913, 198, 182, +(Uint16)(0), + +36905, 199, 183, +(Uint16)(0), + +36913, 200, 184, +(Uint16)(0), + +36905, 201, 185, +(Uint16)(0), + +36913, 202, 186, +(Uint16)(0), + +36905, 203, 187, +(Uint16)(0), + +36913, 204, 188, +(Uint16)(0), + +36905, 205, 189, +(Uint16)(0), + +36913, 206, 190, +(Uint16)(0), + +36905, 207, 191, +(Uint16)(0), + +36913, 208, 192, +(Uint16)(0), + +36905, 209, 193, +(Uint16)(0), + +36913, 210, 194, +(Uint16)(0), + +36905, 211, 195, +(Uint16)(0), + +36913, 212, 196, +(Uint16)(0), + +28339, 213, 2, + +31533, 214, 197, +0, + +47917, 215, 198, +(Uint16)(32), + +37117, 216, 199, +(Uint16)(0), + +37074, 217, 200, +(Uint16)(1), + +36580, 218, 201, +(Uint16)(0), + +37143, 219, 202, +(Uint16)(0), + +28339, 220, 2, + +31533, 221, 203, +0, + +47917, 222, 204, +(Uint16)(4128), + +37117, 216, 205, +(Uint16)(0), + +37072, 217, 206, +(Uint16)(1), + +36578, 218, 207, +(Uint16)(0), + +37143, 219, 208, +(Uint16)(4), + +28339, 223, 2, + +31529, 224, 209, +0, + +47913, 225, 210, +(Uint16)(3136), + +37113, 216, 211, +(Uint16)(0), + +37074, 217, 212, +(Uint16)(2), + +36576, 218, 213, +(Uint16)(0), + +37143, 219, 214, +(Uint16)(3), + +28339, 226, 2, + +31529, 227, 215, +0, + +47913, 228, 216, +(Uint16)(2112), + +37113, 216, 217, +(Uint16)(0), + +37068, 217, 218, +(Uint16)(2), + +36578, 218, 219, +(Uint16)(0), + +37143, 219, 220, +(Uint16)(2), + +28331, 229, 2, + +31533, 230, 221, +0, + +47917, 231, 222, +(Uint16)(1056), + +37117, 216, 223, +(Uint16)(0), + +37066, 217, 224, +(Uint16)(1), + +36580, 218, 225, +(Uint16)(0), + +37143, 219, 226, +(Uint16)(1), + +28331, 232, 2, + +31533, 233, 227, +0, + +47917, 234, 228, +(Uint16)(1056), + +37117, 216, 229, +(Uint16)(0), + +37064, 217, 230, +(Uint16)(1), + +36570, 218, 231, +(Uint16)(0), + +37143, 219, 232, +(Uint16)(1), + +28331, 235, 2, + +31521, 236, 233, +0, + +47905, 237, 234, +(Uint16)(1088), + +37105, 216, 235, +(Uint16)(0), + +37066, 217, 236, +(Uint16)(2), + +36568, 218, 237, +(Uint16)(0), + +37143, 219, 238, +(Uint16)(1), + +28331, 238, 2, + +31521, 239, 239, +0, + +47905, 240, 240, +(Uint16)(2112), + +37105, 216, 241, +(Uint16)(0), + +37068, 217, 242, +(Uint16)(2), + +36570, 218, 243, +(Uint16)(0), + +37143, 219, 244, +(Uint16)(2), + +28323, 241, 2, + +31533, 242, 245, +0, + +47917, 243, 246, +(Uint16)(9286), + +37117, 216, 247, +(Uint16)(6), + +37058, 217, 248, +(Uint16)(2), + +36564, 218, 249, +(Uint16)(0), + +37127, 219, 250, +(Uint16)(9), + +28323, 244, 2, + +31533, 245, 251, +0, + +47917, 246, 252, +(Uint16)(5184), + +37117, 216, 253, +(Uint16)(0), + +37056, 217, 254, +(Uint16)(2), + +36562, 218, 255, +(Uint16)(0), + +37127, 219, 256, +(Uint16)(5), + +28323, 247, 2, + +31529, 248, 257, +0, + +47913, 249, 258, +(Uint16)(12320), + +37113, 216, 259, +(Uint16)(0), + +37058, 217, 260, +(Uint16)(1), + +36560, 218, 261, +(Uint16)(0), + +37127, 219, 262, +(Uint16)(12), + +28323, 250, 2, + +31529, 251, 263, +0, + +47913, 252, 264, +(Uint16)(6144), + +37113, 216, 265, +(Uint16)(0), + +37068, 217, 266, +(Uint16)(0), + +36562, 218, 267, +(Uint16)(0), + +37127, 219, 268, +(Uint16)(6), + +28331, 253, 2, + +31533, 254, 269, +0, + +47917, 255, 270, +(Uint16)(7168), + +37117, 216, 271, +(Uint16)(0), + +37066, 217, 272, +(Uint16)(0), + +36564, 218, 273, +(Uint16)(0), + +37127, 219, 274, +(Uint16)(7), + +28331, 256, 2, + +31533, 257, 275, +0, + +47917, 258, 276, +(Uint16)(2048), + +37117, 216, 277, +(Uint16)(0), + +37064, 217, 278, +(Uint16)(0), + +36570, 218, 279, +(Uint16)(0), + +37127, 219, 280, +(Uint16)(2), + +28331, 259, 2, + +31505, 260, 281, +0, + +47889, 261, 282, +(Uint16)(1024), + +37089, 216, 283, +(Uint16)(0), + +37066, 217, 284, +(Uint16)(0), + +36568, 218, 285, +(Uint16)(0), + +37127, 219, 286, +(Uint16)(1), + +28331, 262, 2, + +31505, 263, 287, +0, + +47889, 264, 288, +(Uint16)(96), + +37089, 216, 289, +(Uint16)(0), + +37068, 217, 290, +(Uint16)(3), + +36570, 218, 291, +(Uint16)(0), + +37127, 219, 292, +(Uint16)(0), + +28339, 265, 2, + +31501, 266, 293, +0, + +47885, 267, 294, +(Uint16)(3136), + +37117, 216, 295, +(Uint16)(0), + +37074, 217, 296, +(Uint16)(2), + +36548, 218, 297, +(Uint16)(0), + +37143, 219, 298, +(Uint16)(3), + +28339, 268, 2, + +31501, 269, 299, +0, + +47885, 270, 300, +(Uint16)(9408), + +37117, 216, 301, +(Uint16)(0), + +37072, 217, 302, +(Uint16)(2), + +36546, 218, 303, +(Uint16)(1), + +37143, 219, 304, +(Uint16)(9), + +28339, 271, 2, + +31497, 272, 305, +0, + +47881, 273, 306, +(Uint16)(9414), + +37113, 216, 307, +(Uint16)(6), + +37074, 217, 308, +(Uint16)(2), + +36544, 218, 309, +(Uint16)(1), + +37143, 219, 310, +(Uint16)(9), + +28339, 274, 2, + +31497, 275, 311, +0, + +47881, 276, 312, +(Uint16)(12352), + +37113, 216, 313, +(Uint16)(0), + +37036, 217, 314, +(Uint16)(2), + +36546, 218, 315, +(Uint16)(0), + +37143, 219, 316, +(Uint16)(12), + +28299, 277, 2, + +31501, 278, 317, +0, + +47885, 279, 318, +(Uint16)(13344), + +37117, 216, 319, +(Uint16)(0), + +37034, 217, 320, +(Uint16)(1), + +36548, 218, 321, +(Uint16)(0), + +37143, 219, 322, +(Uint16)(13), + +28299, 280, 2, + +31501, 281, 323, +0, + +47885, 282, 324, +(Uint16)(10240), + +37117, 216, 325, +(Uint16)(0), + +37032, 217, 326, +(Uint16)(0), + +36570, 218, 327, +(Uint16)(0), + +37143, 219, 328, +(Uint16)(10), + +28299, 283, 2, + +31489, 284, 329, +0, + +47873, 285, 330, +(Uint16)(14400), + +37105, 216, 331, +(Uint16)(0), + +37034, 217, 332, +(Uint16)(2), + +36568, 218, 333, +(Uint16)(0), + +37143, 219, 334, +(Uint16)(14), + +28299, 286, 2, + +31489, 287, 335, +0, + +47873, 288, 336, +(Uint16)(15430), + +37105, 216, 337, +(Uint16)(6), + +37036, 217, 338, +(Uint16)(2), + +36570, 218, 339, +(Uint16)(0), + +37143, 219, 340, +(Uint16)(15), + +28291, 289, 2, + +31501, 290, 341, +0, + +47885, 291, 342, +(Uint16)(16448), + +37117, 216, 343, +(Uint16)(0), + +37026, 217, 344, +(Uint16)(2), + +36564, 218, 345, +(Uint16)(0), + +36583, 219, 346, +(Uint16)(16), + +28291, 292, 2, + +31501, 293, 347, +0, + +47885, 294, 348, +(Uint16)(13312), + +37117, 216, 349, +(Uint16)(0), + +37024, 217, 350, +(Uint16)(0), + +36562, 218, 351, +(Uint16)(0), + +36583, 219, 352, +(Uint16)(13), + +28291, 295, 2, + +31497, 296, 353, +0, + +47881, 297, 354, +(Uint16)(14336), + +37113, 216, 355, +(Uint16)(0), + +37026, 217, 356, +(Uint16)(0), + +36560, 218, 357, +(Uint16)(0), + +36583, 219, 358, +(Uint16)(14), + +28291, 298, 2, + +31497, 299, 359, +0, + +47881, 300, 360, +(Uint16)(12384), + +37113, 216, 361, +(Uint16)(0), + +37036, 217, 362, +(Uint16)(3), + +36562, 218, 363, +(Uint16)(0), + +36583, 219, 364, +(Uint16)(12), + +28299, 301, 2, + +31501, 302, 365, +0, + +47885, 303, 366, +(Uint16)(0), + +37117, 216, 367, +(Uint16)(0), + +37034, 217, 368, +(Uint16)(0), + +36564, 218, 369, +(Uint16)(0), + +36583, 219, 370, +(Uint16)(0), + +28299, 304, 2, + +31501, 305, 371, +0, + +47885, 306, 372, +(Uint16)(0), + +37117, 216, 373, +(Uint16)(0), + +37032, 217, 374, +(Uint16)(0), + +36570, 218, 375, +(Uint16)(0), + +36583, 219, 376, +(Uint16)(0), + +28333, 307, 4, + +36537, 308, 377, +(Uint16)(256), +0, +0, + +36542, 309, 378, +(Uint16)(256), +0, +0, + +36543, 310, 379, +(Uint16)(256), +0, +0, + +45225, 307, 380, +(Uint16)(0), +0, 1, + +28333, 756, 3, + +48417, 581, 381, +(Uint16)(0), (((Uint32)0)>>16), + +48417, 582, 382, +(Uint16)(0), (((Uint32)0)>>16), + +48417, 754, 383, +(Uint16)(0), (((Uint32)0)>>16), + +48417, 753, 384, +(Uint16)(0), (((Uint32)0)>>16), + +48401, 311, 385, +(Uint16)(438392299), (((Uint32)438392299)>>16), + +28236, 312, 1, + +20169, 313, 386, + +18737, 314, 387, + +20153, 312, 388, + +28238, 315, 2, + +45261, 316, 389, +(Uint16)(15), + +27822, 577, 3, + +45357, 577, 390, +(Uint16)(0x11111111), (((Uint32)0x11111111)>>16), + +20749, 317, 391, + +3762, 312, 2, + +47917, 318, 392, +(Uint16)(58002), + +47917, 319, 393, +(Uint16)(14349), + +47917, 320, 394, +(Uint16)(64364), + +47917, 321, 395, +(Uint16)(3745), + +47917, 322, 396, +(Uint16)(1832), + +28848, 323, 7, + +58853, 324, 397, +(Uint16)(16777216), (((Uint32)16777216)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(_IQ(120.0)), (((Uint32)_IQ(120.0))>>16), + +26437, 325, 398, +0, +0, +0, +0, +0, +0, + +26437, 326, 399, +0, +0, +0, +0, +0, +0, + +20154, 327, 7, + +25925, 328, 400, +0, +0, +0, +0, +0, +0, + +25925, 329, 401, +0, +0, +0, +0, +0, +0, + +9381, 330, 402, +(Uint16)(335544), (((Uint32)335544)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9509, 331, 403, +(Uint16)(16777216), (((Uint32)16777216)>>16), +(Uint16)(_IQ(-1.0)), (((Uint32)_IQ(-1.0))>>16), (Uint16)(_IQ(1.0)), (((Uint32)_IQ(1.0))>>16), + +9509, 332, 404, +(Uint16)(-16777216), (((Uint32)-16777216)>>16), +(Uint16)(_IQ(-1.0)), (((Uint32)_IQ(-1.0))>>16), (Uint16)(_IQ(1.0)), (((Uint32)_IQ(1.0))>>16), + +9381, 333, 405, +(Uint16)(2684354), (((Uint32)2684354)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9381, 334, 406, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9381, 335, 407, +(Uint16)(8388608), (((Uint32)8388608)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +25925, 336, 408, +0, +0, +0, +0, +0, +0, + +25893, 337, 409, +0, +0, +0, +0, +0, +0, + +25893, 338, 410, +0, +0, +0, +0, +0, +0, + +25893, 339, 411, +0, +0, +0, +0, +0, +0, + +25893, 340, 412, +0, +0, +0, +0, +0, +0, + +20155, 341, 7, + +26437, 342, 413, +0, +0, +0, +0, +0, +0, + +26437, 343, 414, +0, +0, +0, +0, +0, +0, + +9381, 330, 415, +(Uint16)(3355443), (((Uint32)3355443)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9541, 331, 416, +(Uint16)(13421772), (((Uint32)13421772)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9541, 332, 417, +(Uint16)(-13421772), (((Uint32)-13421772)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9381, 333, 418, +(Uint16)(16777), (((Uint32)16777)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9381, 344, 419, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9381, 335, 420, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +26437, 336, 421, +0, +0, +0, +0, +0, +0, + +25925, 345, 422, +0, +0, +0, +0, +0, +0, + +25925, 338, 423, +0, +0, +0, +0, +0, +0, + +25925, 339, 424, +0, +0, +0, +0, +0, +0, + +25925, 340, 425, +0, +0, +0, +0, +0, +0, + +25925, 346, 426, +0, +0, +0, +0, +0, +0, + +20154, 347, 7, + +25921, 348, 427, +0, +0, +0, +0, +0, +0, + +25921, 349, 428, +0, +0, +0, +0, +0, +0, + +9377, 350, 429, +(Uint16)(335544), (((Uint32)335544)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9505, 351, 430, +(Uint16)(16777216), (((Uint32)16777216)>>16), +(Uint16)(_IQ(-1.0)), (((Uint32)_IQ(-1.0))>>16), (Uint16)(_IQ(1.0)), (((Uint32)_IQ(1.0))>>16), + +9505, 352, 431, +(Uint16)(-16777216), (((Uint32)-16777216)>>16), +(Uint16)(_IQ(-1.0)), (((Uint32)_IQ(-1.0))>>16), (Uint16)(_IQ(1.0)), (((Uint32)_IQ(1.0))>>16), + +9377, 353, 432, +(Uint16)(2684354), (((Uint32)2684354)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9377, 354, 433, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9377, 335, 434, +(Uint16)(8388608), (((Uint32)8388608)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +25921, 336, 435, +0, +0, +0, +0, +0, +0, + +25889, 355, 436, +0, +0, +0, +0, +0, +0, + +25889, 338, 437, +0, +0, +0, +0, +0, +0, + +25889, 339, 438, +0, +0, +0, +0, +0, +0, + +25889, 340, 439, +0, +0, +0, +0, +0, +0, + +20157, 356, 7, + +15401, 342, 440, +(Uint16)(0), (((Uint32)0)>>16), +0, +0, +0, +0, + +10017, 342, 441, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +26401, 343, 442, +0, +0, +0, +0, +0, +0, + +31785, 343, 443, +0, +0, +0, +0, +0, +0, + +9377, 330, 444, +(Uint16)(1174405120), (((Uint32)1174405120)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +10049, 331, 445, +(Uint16)(100663296), (((Uint32)100663296)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +10049, 332, 446, +(Uint16)(-100663296), (((Uint32)-100663296)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9377, 333, 447, +(Uint16)(83886), (((Uint32)83886)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9377, 344, 448, +(Uint16)(167772160), (((Uint32)167772160)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +15401, 357, 449, +(Uint16)(0), (((Uint32)0)>>16), +0, +0, +0, +0, + +9377, 358, 450, +(Uint16)(8388608), (((Uint32)8388608)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9377, 335, 451, +(Uint16)(8388608), (((Uint32)8388608)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +10017, 359, 452, +(Uint16)(13981), (((Uint32)13981)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +26401, 336, 453, +0, +0, +0, +0, +0, +0, + +25761, 346, 454, +0, +0, +0, +0, +0, +0, + +26433, 345, 455, +0, +0, +0, +0, +0, +0, + +26433, 338, 456, +0, +0, +0, +0, +0, +0, + +26433, 339, 457, +0, +0, +0, +0, +0, +0, + +26433, 340, 458, +0, +0, +0, +0, +0, +0, + +26401, 360, 459, +0, +0, +0, +0, +0, +0, + +20156, 362, 7, + +25893, 363, 460, +0, +0, +0, +0, +0, +0, + +25893, 364, 461, +0, +0, +0, +0, +0, +0, + +8901, 365, 462, +(Uint16)(14529069), (((Uint32)14529069)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0x01000000), (((Uint32)0x01000000)>>16), + +31533, 366, 463, +0, +0, +0, +0, +0, +0, + +31533, 367, 464, +0, +0, +0, +0, +0, +0, + +31533, 368, 465, +0, +0, +0, +0, +0, +0, + +31533, 369, 466, +0, +0, +0, +0, +0, +0, + +11429, 370, 467, +(Uint16)(33554432), (((Uint32)33554432)>>16), +(Uint16)(_IQ(2.0)), (((Uint32)_IQ(2.0))>>16), (Uint16)(_IQ(10.0)), (((Uint32)_IQ(10.0))>>16), + +11429, 371, 468, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(_IQ(10)), (((Uint32)_IQ(10))>>16), + +8901, 372, 469, +(Uint16)(16777216), (((Uint32)16777216)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +11965, 373, 470, +(Uint16)(1), +0, +0, +0, +0, +0, + +15149, 374, 471, +(Uint16)(1), +0, +0, +0, +0, +0, + +31661, 375, 472, +0, +0, +0, +0, +0, +0, + +9367, 376, 473, +(Uint16)(20480), (((Uint32)20480)>>16), +(Uint16)(2048), (((Uint32)2048)>>16), (Uint16)(10240), (((Uint32)10240)>>16), + +31277, 377, 474, +0, +0, +0, +0, +0, +0, + +25893, 378, 475, +0, +0, +0, +0, +0, +0, + +31533, 379, 476, +0, +0, +0, +0, +0, +0, + +20143, 380, 2, + +31273, 381, 477, +0, + +53545, 382, 478, +(Uint16)(1), + +20132, 383, 7, + +15121, 384, 479, +(Uint16)(0), +0, +0, +0, +0, +0, + +15121, 385, 480, +(Uint16)(0), +0, +0, +0, +0, +0, + +53265, 386, 481, +(Uint16)(255), +0, +0, +0, +0, +0, + +53289, 387, 482, +(Uint16)(255), +0, +0, +0, +0, +0, + +53265, 388, 483, +(Uint16)(255), +0, +0, +0, +0, +0, + +53289, 389, 484, +(Uint16)(255), +0, +0, +0, +0, +0, + +9529, 390, 485, +(Uint16)(16777216), (((Uint32)16777216)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9625, 391, 486, +(Uint16)(18454938), (((Uint32)18454938)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9625, 392, 487, +(Uint16)(6990506), (((Uint32)6990506)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +10041, 393, 488, +(Uint16)(100663296), (((Uint32)100663296)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9721, 639, 489, +(Uint16)(75497472), (((Uint32)75497472)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +20146, 394, 7, + +10017, 395, 490, +(Uint16)(67108), (((Uint32)67108)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9505, 396, 491, +(Uint16)(3355443), (((Uint32)3355443)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9505, 397, 492, +(Uint16)(3355443), (((Uint32)3355443)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9985, 398, 493, +(Uint16)(720992), (((Uint32)720992)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9601, 559, 494, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +20144, 399, 7, + +15241, 400, 495, +(Uint16)(2), +1, 50, +0, +0, +0, + +8265, 401, 496, +(Uint16)(5), +0, 0, +0, +0, +0, + +24617, 402, 497, +0, +0, +0, +0, +0, +0, + +9129, 403, 498, +(Uint16)(500), +0, 0, +0, +0, +0, + +8233, 404, 499, +(Uint16)(36), +0, 1000, +0, +0, +0, + +10113, 405, 500, +(Uint16)(1048576), (((Uint32)1048576)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +10145, 406, 501, +(Uint16)(16777), (((Uint32)16777)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +24713, 407, 502, +0, +0, +0, +0, +0, +0, + +11993, 408, 503, +(Uint16)(1), +0, +0, +0, +0, +0, + +20107, 409, 4, + +4365, 410, 504, +0, +0, +0, + +15117, 411, 505, +(Uint16)(4), +0, +0, + +15117, 412, 506, +(Uint16)(0), +0, +0, + +15117, 413, 507, +(Uint16)(1), +0, +0, + +14477, 414, 508, +(Uint16)(0), +0, 1, + +15117, 590, 509, +(Uint16)(0), +0, +0, + +20147, 415, 4, + +8257, 416, 510, +(Uint16)(-81), +0, 0, + +16001, 417, 511, +(Uint16)(-14592), +0, 0, + +25913, 418, 512, +0, +0, +0, + +8257, 419, 513, +(Uint16)(-81), +0, 0, + +16001, 420, 514, +(Uint16)(-14592), +0, 0, + +25913, 421, 515, +0, +0, +0, + +8257, 422, 516, +(Uint16)(40), +0, 0, + +16001, 423, 517, +(Uint16)(62836), +0, 0, + +25913, 424, 518, +0, +0, +0, + +8225, 425, 519, +(Uint16)(2050), +0, 0, + +16001, 426, 520, +(Uint16)(0), +0, 0, + +26009, 427, 521, +0, +0, +0, + +9185, 633, 522, +(Uint16)(0), +0, 0, + +26105, 634, 523, +0, +0, +0, + +20096, 428, 7, + +26417, 429, 524, +0, +0, +0, +0, +0, +0, + +25873, 430, 525, +0, +0, +0, +0, +0, +0, + +10033, 431, 526, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9489, 432, 527, +(Uint16)(419430), (((Uint32)419430)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +10033, 433, 528, +(Uint16)(100663296), (((Uint32)100663296)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9489, 434, 529, +(Uint16)(12582912), (((Uint32)12582912)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +10033, 435, 530, +(Uint16)(100663296), (((Uint32)100663296)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +20037, 436, 1, + +26421, 437, 531, + +26037, 438, 532, + +25909, 439, 533, + +25813, 440, 534, + +25813, 441, 535, + +25909, 442, 536, + +28141, 613, 537, + +28141, 614, 538, + +20023, 443, 7, + +14477, 444, 539, +(Uint16)(0), +0, +0, +0, +0, +0, + +14989, 445, 540, +(Uint16)(192), (((Uint32)192)>>16), +0, +0, +0, +0, + +14989, 446, 541, +(Uint16)(1359151123), (((Uint32)1359151123)>>16), +0, +0, +0, +0, + +14989, 447, 542, +(Uint16)(1359085569), (((Uint32)1359085569)>>16), +0, +0, +0, +0, + +14989, 448, 543, +(Uint16)(1359151122), (((Uint32)1359151122)>>16), +0, +0, +0, +0, + +14989, 449, 544, +(Uint16)(1359020033), (((Uint32)1359020033)>>16), +0, +0, +0, +0, + +53645, 450, 545, +(Uint16)(0), +0, +0, +0, +0, +0, + +53685, 451, 546, +(Uint16)(1), +0, +0, +0, +0, +0, + +11837, 452, 547, +(Uint16)(0), +0, +0, +0, +0, +0, + +10949, 453, 548, +(Uint16)(6710886), (((Uint32)6710886)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +15757, 454, 549, +(Uint16)(50461787), (((Uint32)50461787)>>16), + +20000, 455, 7, + +14985, 456, 550, +(Uint16)(1000), (((Uint32)1000)>>16), +0, +0, +0, +0, + +11839, 457, 551, +(Uint16)(2), +0, +0, +0, +0, +0, + +14473, 458, 552, +(Uint16)(1), +0, +0, +0, +0, +0, + +9345, 459, 553, +(Uint16)(9298387), (((Uint32)9298387)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +31369, 460, 554, +0, +0, +0, +0, +0, +0, + +30857, 460, 555, +0, +0, +0, +0, +0, +0, + +25761, 461, 556, +0, +0, +0, +0, +0, +0, + +25729, 462, 557, +0, +0, +0, +0, +0, +0, + +25729, 463, 558, +0, +0, +0, +0, +0, +0, + +53565, 464, 559, +(Uint16)(0), +0, +0, +0, +0, +0, + +9217, 465, 560, +(Uint16)(838860), (((Uint32)838860)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(65535), (((Uint32)65535)>>16), + +30857, 466, 561, +0, +0, +0, +0, +0, +0, + +30857, 467, 562, +0, +0, +0, +0, +0, +0, + +30857, 468, 563, +0, +0, +0, +0, +0, +0, + +31369, 469, 564, +0, +0, +0, +0, +0, +0, + +30857, 469, 565, +0, +0, +0, +0, +0, +0, + +30857, 470, 566, +0, +0, +0, +0, +0, +0, + +15241, 471, 567, +(Uint16)(0), +0, +0, +0, +0, +0, + +15241, 472, 568, +(Uint16)(7), +0, +0, +0, +0, +0, + +15241, 472, 569, +(Uint16)(7335), +0, +0, +0, +0, +0, + +15753, 472, 570, +(Uint16)(1973415), (((Uint32)1973415)>>16), +0, +0, +0, +0, + +25729, 473, 571, +0, +0, +0, +0, +0, +0, + +25729, 474, 572, +0, +0, +0, +0, +0, +0, + +20027, 475, 7, + +15245, 589, 573, +(Uint16)(0), +0, +0, +0, +0, +0, + +25733, 441, 574, +0, +0, +0, +0, +0, +0, + +25765, 461, 575, +0, +0, +0, +0, +0, +0, + +9381, 476, 576, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +25733, 477, 577, +0, +0, +0, +0, +0, +0, + +11837, 478, 578, +(Uint16)(81), +0, +0, +0, +0, +0, + +14989, 479, 579, +(Uint16)(500), (((Uint32)500)>>16), +0, +0, +0, +0, + +25765, 480, 580, +0, +0, +0, +0, +0, +0, + +30861, 481, 581, +0, +0, +0, +0, +0, +0, + +4573, 482, 582, +0, +0, +0, +0, +0, +0, + +9349, 459, 583, +(Uint16)(4869970), (((Uint32)4869970)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +30861, 483, 584, +0, +0, +0, +0, +0, +0, + +30861, 484, 585, +0, +0, +0, +0, +0, +0, + +30861, 485, 586, +0, +0, +0, +0, +0, +0, + +30861, 486, 587, +0, +0, +0, +0, +0, +0, + +53567, 487, 588, +(Uint16)(0), +0, +0, +0, +0, +0, + +14477, 488, 589, +(Uint16)(10), +0, +0, +0, +0, +0, + +30861, 489, 590, +0, +0, +0, +0, +0, +0, + +30861, 490, 591, +0, +0, +0, +0, +0, +0, + +30861, 491, 592, +0, +0, +0, +0, +0, +0, + +30861, 492, 593, +0, +0, +0, +0, +0, +0, + +30861, 493, 594, +0, +0, +0, +0, +0, +0, + +20019, 455, 7, + +14977, 494, 595, +(Uint16)(4096), (((Uint32)4096)>>16), +0, +0, +0, +0, + +9369, 459, 596, +(Uint16)(9298387), (((Uint32)9298387)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +30849, 460, 597, +0, +0, +0, +0, +0, +0, + +25785, 461, 598, +0, +0, +0, +0, +0, +0, + +25753, 462, 599, +0, +0, +0, +0, +0, +0, + +25753, 463, 600, +0, +0, +0, +0, +0, +0, + +25753, 495, 601, +0, +0, +0, +0, +0, +0, + +9241, 496, 602, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +15233, 471, 603, +(Uint16)(0), +0, +0, +0, +0, +0, + +15745, 472, 604, +(Uint16)(1973415), (((Uint32)1973415)>>16), +0, +0, +0, +0, + +15233, 472, 605, +(Uint16)(7), +0, +0, +0, +0, +0, + +15233, 472, 606, +(Uint16)(7335), +0, +0, +0, +0, +0, + +25753, 473, 607, +0, +0, +0, +0, +0, +0, + +25753, 474, 608, +0, +0, +0, +0, +0, +0, + +20025, 497, 7, + +25669, 498, 609, +0, +0, +0, +0, +0, +0, + +32205, 498, 610, +0, +0, +0, +0, +0, +0, + +25669, 499, 611, +0, +0, +0, +0, +0, +0, + +32205, 499, 612, +0, +0, +0, +0, +0, +0, + +30925, 500, 613, +0, +0, +0, +0, +0, +0, + +31693, 500, 614, +0, +0, +0, +0, +0, +0, + +30925, 501, 615, +0, +0, +0, +0, +0, +0, + +31693, 501, 616, +0, +0, +0, +0, +0, +0, + +9285, 502, 617, +(Uint16)(16777), (((Uint32)16777)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +15821, 502, 618, +(Uint16)(16777), (((Uint32)16777)>>16), +0, +0, +0, +0, + +9285, 503, 619, +(Uint16)(-190048), (((Uint32)-190048)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +15821, 503, 620, +(Uint16)(-190048), (((Uint32)-190048)>>16), +0, +0, +0, +0, + +9285, 504, 621, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +15821, 504, 622, +(Uint16)(0), (((Uint32)0)>>16), +0, +0, +0, +0, + +9285, 505, 623, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +15821, 505, 624, +(Uint16)(0), (((Uint32)0)>>16), +0, +0, +0, +0, + +50253, 506, 625, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +50253, 507, 626, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +50253, 508, 627, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +50253, 509, 628, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +20142, 556, 7, + +9285, 557, 629, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9637, 558, 630, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +9637, 559, 631, +(Uint16)(0), (((Uint32)0)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +20149, 399, 7, + +12453, 571, 632, +(Uint16)(16777216), (((Uint32)16777216)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +12453, 572, 633, +(Uint16)(5033165), (((Uint32)5033165)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +12613, 573, 634, +(Uint16)(5033165), (((Uint32)5033165)>>16), +(Uint16)(0), (((Uint32)0)>>16), (Uint16)(0), (((Uint32)0)>>16), + +28997, 574, 635, +0, +0, +0, +0, +0, +0, + +28997, 575, 636, +0, +0, +0, +0, +0, +0, + +28837, 536, 637, +0, +0, +0, +0, +0, +0, + +28837, 537, 638, +0, +0, +0, +0, +0, +0, + +30501, 576, 639, +0, +0, +0, +0, +0, +0, +}; +int16 const CO1_OD_TBL1[] = { 4096, 0, +4097, 3, +4098, 6, +4116, 9, +4118, 12, +4119, 20, +4120, 24, +4608, 39, +4736, 48, +5120, 60, +5121, 73, +5122, 86, +5123, 99, +5124, 112, +5125, 125, +5126, 138, +5127, 151, +5632, 164, +5633, 187, +5634, 210, +5635, 233, +5636, 256, +5637, 279, +5638, 302, +5639, 325, +6144, 348, +6145, 371, +6146, 394, +6147, 417, +6148, 440, +6149, 463, +6150, 486, +6151, 509, +6656, 532, +6657, 555, +6658, 578, +6659, 601, +6660, 624, +6661, 647, +6662, 670, +6663, 693, +8192, 716, +8193, 722, +8194, 726, +8195, 741, +8196, 756, +8197, 761, +8199, 764, +8208, 779, +8209, 794, +8210, 817, +8212, 821, +8213, 825, +8214, 828, +8215, 831, +8320, 834, +8321, 893, +8322, 896, +8323, 909, +8448, 976, +8449, 1003, +8450, 1030, +8451, 1057, +8452, 1084, +8453, 1111, +8454, 1138, +8455, 1165, +8456, 1192, +8457, 1219, +8458, 1246, +8459, 1273, +8460, 1300, +8461, 1327, +8462, 1354, +8463, 1381, +8464, 1408, +8465, 1435, +8466, 1462, +8467, 1489, +8468, 1516, +8469, 1543, +8470, 1570, +8471, 1597, +8472, 1624, +8473, 1651, +8474, 1678, +8475, 1705, +8476, 1732, +8477, 1759, +9474, 1786, +9478, 1813, +9487, 1836, +9522, 1841, +9524, 1853, +9728, 1860, +12288, 1868, +12544, 1871, +20480, 1894, +20736, 1924, +20737, 2044, +20738, 2173, +20739, 2293, +20741, 2476, +20747, 2632, +20750, 2643, +20754, 2745, +20755, 2793, +20756, 2877, +20758, 2916, +20762, 3003, +20792, 3069, +20816, 3096, +20817, 3189, +20818, 3194, +20821, 3404, +20823, 3605, +20852, 3734, +20869, 3917, +23300, 3947, +}; +Uint16 const co1_SPIrange1rw = CO1_SPI_START_ADDR+0; +Uint16 const co1_SPIrange1rwCRC = CO1_SPI_START_ADDR+8; +Uint16 const co1_SPIrange1rwp = CO1_SPI_START_ADDR+10; +Uint16 const co1_SPIrange1rwpCRC = CO1_SPI_START_ADDR+336; +Uint16 const co1_SPIrange1rwps = CO1_SPI_START_ADDR+338; +Uint16 const co1_SPIrange1rwpsCRC = CO1_SPI_START_ADDR+338; +Uint16 const co1_SPIrange2rw = CO1_SPI_START_ADDR+340; +Uint16 const co1_SPIrange2rwCRC = CO1_SPI_START_ADDR+581; +Uint16 const co1_SPIrange2rwp = CO1_SPI_START_ADDR+583; +Uint16 const co1_SPIrange2rwpCRC = CO1_SPI_START_ADDR+608; +Uint16 const co1_SPIrange2rwps = CO1_SPI_START_ADDR+610; +Uint16 const co1_SPIrange2rwpsCRC = CO1_SPI_START_ADDR+610; +Uint16 const co1_SPIrange3rw = CO1_SPI_START_ADDR+612; +Uint16 const co1_SPIrange3rwCRC = CO1_SPI_START_ADDR+622; +Uint16 const co1_SPIrange3rwp = CO1_SPI_START_ADDR+624; +Uint16 const co1_SPIrange3rwpCRC = CO1_SPI_START_ADDR+624; +Uint16 const co1_SPIrange3rwps = CO1_SPI_START_ADDR+626; +Uint16 const co1_SPIrange3rwpsCRC = CO1_SPI_START_ADDR+626; +Uint16 const co1_SPIrange4rw = CO1_SPI_START_ADDR+628; +Uint16 const co1_SPIrange4rwCRC = CO1_SPI_START_ADDR+628; +Uint16 const co1_SPIrange4rwp = CO1_SPI_START_ADDR+630; +Uint16 const co1_SPIrange4rwpCRC = CO1_SPI_START_ADDR+630; +Uint16 const co1_SPIrange4rwps = CO1_SPI_START_ADDR+632; +Uint16 const co1_SPIrange4rwpsCRC = CO1_SPI_START_ADDR+632; +Uint16 const co1_SPIrange5rw = CO1_SPI_START_ADDR+634; +Uint16 const co1_SPIrange5rwCRC = CO1_SPI_START_ADDR+1058; +Uint16 const co1_SPIrange5rwp = CO1_SPI_START_ADDR+1060; +Uint16 const co1_SPIrange5rwpCRC = CO1_SPI_START_ADDR+1064; +Uint16 const co1_SPIrange5rwps = CO1_SPI_START_ADDR+1066; +Uint16 const co1_SPIrange5rwpsCRC = CO1_SPI_START_ADDR+1066; +Uint16 const co1_first1000 = 0; +Uint16 const co1_first2000 = 82; +Uint16 const co1_first3000 = 190; +Uint16 const co1_first4000 = 194; +Uint16 const co1_first5000 = 194; +//Таблица групп + +Uint16 const CO1_TYPE_DEF_TABLE[] = { (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)4,\ + (Uint16)5,\ + (Uint16)0,\ + (Uint16)-1,\ + (Uint16)10,\ + (Uint16)4,\ + (Uint16)0,\ + (Uint16)0,\ + (Uint16)40,\ + (Uint16)17,\ + (Uint16)6,\ + (Uint16)8,\ + (Uint16)7,\ + (Uint16)9,\ + (Uint16)15,\ + (Uint16)36,\ + (Uint16)16,\ + (Uint16)1,\ + (Uint16)13,\ + (Uint16)12,\ + (Uint16)14,\ + (Uint16)18,\ + (Uint16)-1,\ + (Uint16)28,\ + (Uint16)0,\ + (Uint16)24,\ + (Uint16)23,\ + (Uint16)25,\ + (Uint16)27,\ + (Uint16)19,\ + (Uint16)20,\ +}; +//Таблица CALLBACK-функций + +//************************************************************** +long const CO1_OD_CALLBACK_TBL[]={0,//1000h.00h +0,//1001h.00h +0,//1002h.00h +0,//1014h.00h +0,//1016h.00h +0,//1017h.00h +0,//1018h.00h +0,//1200h.00h +0,//1280h.00h +0,//1400h.00h +0,//1401h.00h +0,//1402h.00h +0,//1403h.00h +0,//1404h.00h +0,//1405h.00h +0,//1406h.00h +0,//1407h.00h +0,//1600h.00h +0,//1601h.00h +0,//1602h.00h +0,//1603h.00h +0,//1604h.00h +0,//1605h.00h +0,//1606h.00h +0,//1607h.00h +0,//1800h.00h +0,//1801h.00h +0,//1802h.00h +0,//1803h.00h +0,//1804h.00h +0,//1805h.00h +0,//1806h.00h +0,//1807h.00h +0,//1A00h.00h +0,//1A01h.00h +0,//1A02h.00h +0,//1A03h.00h +0,//1A04h.00h +0,//1A05h.00h +0,//1A06h.00h +0,//1A07h.00h +0,//2000h.00h +0,//2001h.00h +0,//2002h.00h +0,//2003h.00h +0,//2004h.00h +0,//2005h.00h +0,//2007h.00h +0,//2010h.00h +0,//2011h.00h +0,//2012h.00h +0,//2014h.00h +0,//2015h.00h +0,//2016h.00h +0,//2017h.00h +0,//2080h.00h +0,//2081h.00h +0,//2082h.00h +0,//2083h.00h +0,//2100h.00h +0,//2101h.00h +0,//2102h.00h +0,//2103h.00h +0,//2104h.00h +0,//2105h.00h +0,//2106h.00h +0,//2107h.00h +0,//2108h.00h +0,//2109h.00h +0,//210Ah.00h +0,//210Bh.00h +0,//210Ch.00h +0,//210Dh.00h +0,//210Eh.00h +0,//210Fh.00h +0,//2110h.00h +0,//2111h.00h +0,//2112h.00h +0,//2113h.00h +0,//2114h.00h +0,//2115h.00h +0,//2116h.00h +0,//2117h.00h +0,//2118h.00h +0,//2119h.00h +0,//211Ah.00h +0,//211Bh.00h +0,//211Ch.00h +0,//211Dh.00h +0,//2502h.00h +0,//2506h.00h +(long)((void(*)(long))callback_RTC),//250Fh.00h +0,//2532h.00h +0,//2534h.00h +0,//2600h.00h +0,//3000h.00h +0,//3100h.00h +0,//5000h.00h +0,//5100h.00h +0,//5101h.00h +0,//5102h.00h +0,//5103h.00h +0,//5105h.00h +0,//510Bh.00h +0,//510Eh.00h +0,//5112h.00h +0,//5113h.00h +0,//5114h.00h +0,//5116h.00h +0,//511Ah.00h +0,//5138h.00h +0,//5150h.00h +(long)((void(*)(long))callback_dlog),//5151h.00h +0,//5152h.00h +0,//5155h.00h +0,//5157h.00h +0,//5174h.00h +0,//5185h.00h +0,//5B04h.00h +}; + diff --git a/Vsrc/filter.c b/Vsrc/filter.c new file mode 100644 index 0000000..d3be38c --- /dev/null +++ b/Vsrc/filter.c @@ -0,0 +1,43 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file filter.c + \brief Инерционное звено в IQ математике (см. TFilter) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + */ + +/** \addtogroup filter */ +/*@{*/ + +#include "DSP.h" +#include "filter.h" +#include "V_IQmath.h" + +//! Инерционное звено 1/(Tp+1) +//! Используется как фильтр первого порядка + +//!Должна вызываться с заданной дискретизацией. Предварительно необходимо определить +//! переменную, связанную с постоянной времени: +//! T=Ts/Tfiltra где - Tfiltra постоянная времени фильтра, а +//! Ts - время дискретизации вызова фунции +//! \memberof TFilter +void TFilter_Calc(TFilter *p) { + p->output = _IQmpy(p->T,(p->input-p->output)) + p->output; +} + +/*@}*/ + diff --git a/Vsrc/ipark.c b/Vsrc/ipark.c new file mode 100644 index 0000000..76eb020 --- /dev/null +++ b/Vsrc/ipark.c @@ -0,0 +1,45 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file ipark.c + \brief Модуль инверсных координатных преобразований координат (см. TIPark) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup IPark + @{ + */ + +#include "V_IQmath.h" /* Include header for IQmath library */ +#include "ipark.h" + +//! Функция инверсных преобразований координат + +//!На входе угол ang, вектор (de,qe). +//!На выходе повернутый на заданный угол вектор (ds,qs) +//! \memberof TIPark +void ipark_calc(TIPark *v) { + + _iq cos_ang, sin_ang; + + sin_ang = _IQsinPU(v->ang); + cos_ang = _IQcosPU(v->ang); + + v->ds = _IQmpy(v->de,cos_ang) - _IQmpy(v->qe, sin_ang); + v->qs = _IQmpy(v->qe,cos_ang) + _IQmpy(v->de, sin_ang); +} + +/*@}*/ + diff --git a/Vsrc/main.c b/Vsrc/main.c new file mode 100644 index 0000000..85ec58a --- /dev/null +++ b/Vsrc/main.c @@ -0,0 +1,322 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file main.c + \brief Главный файл проекта. Содержит main(), а также обработчики прерываний. + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + */ + +/** \addtogroup MAIN */ +/*@{*/ +#include "main.h" +#include //для memcpy + + +TClarke clarke = CLARKE_DEFAULTS; //!<Фазные преобразования +TPark park = PARK_DEFAULTS; //!<Координатные преобразования +TIPark ipark = IPARK_DEFAULTS; //!<Обратные координатные преобразования +TPidReg3 pid_id = PIDREG3_DEFAULTS; //!<Рег. тока по оси d +TPidReg3 pid_iq = PIDREG3_DEFAULTS; //!<Рег. тока по оси q +TPidReg3 pid_ia = PIDREG3_DEFAULTS; //!<Рег. тока якоря ДПТ +TPidReg3 pid_spd = PIDREG3_DEFAULTS; //!<Рег. скорости +TPidReg3_pos pid_pos = PIDREG3_DEFAULTS_POS; //!<Рег. положения +TVhzProf vhz = VHZPROF_DEFAULTS; //!< закон U/f=const +TSM_Sys sm_sys = SM_Sys_DEFAULTS; //!< Главная оболочка для вызова всех модулей +Uint16 disp_group_number = 0; //!< Необходимо для драйвера CANOpen и Unicon +TDataLog dlog = DATALOG_DEFAULTS; //!< Модуль осциллографирования переменных CANOpen +TSM_Protect sm_prot = SM_PROTECT_DEFAULTS; //!< Модуль защит +TBitsToEnumNums pult_faults_lister = BITS_TO_ENUM_NUMS_DEFAULTS; //!<Листалка аварий для Unicon +TSM_Ctrl sm_ctrl = SM_CTRL_DEFAULTS; //!< Главный дискретный автомат, реализует структуру управления +TSM_CmdLogic sm_cmd_logic = SM_CMD_LOGIC_DEFAULTS; //!< Обработка пользовательских команд управления +TSM_Net sm_net = SM_NET_DEFAULTS; //!< Оболочка для вызова сетевых драйверов +TRMPCtrl rmp = V_RMP_CTRL_DEFAULTS; //!< Задатчик интенсивности +TAdcDrv adc = ADC_DRV_DEFAULTS; //!< Модуль АЦП +TPWM_Module pwm = PWM_Module_DEFAULTS; //!< Модуль ШИМ +TDPReCAP DPReCAP = DPRECAP_DEFAULTS; //!< Модуль ДПР на элементах Холла +TposspeedEqep posspeedEqep = POSSPEED_DEFAULTS; //!< Модуль ДПР типа энкодер +TCurPar cur_par = TCUR_PAR_DEFAULTS; //!< Модуль расчета и хранения текущих показателей привода - мощность, скорость +TUserMemory UserMem = USERMEMORY_DEFAULTS; //!< Модуль работы с энергонезависимой памятью. +Tled leds = LED_DEFAULTS; //!< модуль для красивого мигания светодиодами +//TCanBTInterface Can2BTInterface = T_CANBT_INTERFACE_DEFAULTS;//!<Пакетная передача CANopen +TRTCClock RTCclock = RTC_CLOCK_DEFAULTS; //!< Модуль работы с часами реальноговремени. "spi" - по историческим причинам совместимости +TAutoOffset AutoOffset = AUTO_OFFSET_DEFAULTS; //!<Автоматическая подстройка смещения токов АЦП +TSSI_Encoder SSI_Encoder = SSI_ENCODER_DEFAULTS; //!<Драйвер обработки датчика положения с SSI интерфейсом +//TMotorModel model = MOTOR_MODEL_DEFAULTS; //!< Модели электродвигателей для отладки "на столе" в режиме симулятора +TRotorObserver RotorObserver = ROTOR_OBSERVER_DEFAULTS; //!<Датчиковый наблюдатель потокосцепления ротора асинхронного двигателя +TCANtoRS CANtoRS = CAN_TO_RS_DEFAULTS; //!<Модуль для работы с драйвером CANopen через UART (RS). Посылки CAN запаковываются в UART +//TModBus ModBus = MODBUS_DEFAULTS; //!<Драйвер для работы по протоколу MODBUS +//TMBVarsConv MBVarsConv = MBVARSCONV_DEFAULTS;//!< Модуль преобразования данных из формата 16 разрядов Modbus в формат системы управления (IQ 24) +TDrvInterface drv_interface = DRV_INTERFACE_DEFAULTS; //!<Интерфейс длЯ работы с банками аварий, событий и т.п. +TLogger FaultLog = LOGGER_DEFAULTS; //!<Протоколирование аварий +TGlobalTime global_time = GLOBAL_TIME_DEFAULTS; //!<Работа с часами + +TRefs refs; //!< Структура с заданиями (токи, скорости) +TCmd cmd = { 0 }; //!< Структура с командами управления +TDrvStatus drv_status = { 0 }; //!< Текущий статус привода +TDrvParams drv_params; //!< Параметры двигателя +TSysSwitches sw; //!< Различные дискретные настройки системы управления + +Uint32 VendorToken=0x11111111;//!< Уникальный ключ производителя, нужный для программы UniCON и COODEdit для различных наборов текстов разных произхводителей +int drv_status_code; //!<Статус системы управления в виде константы (ГОТОВ, РАБОТА и т.п.) + +//Переменные для отладки - выведены в словарь CANOpen, +//В них можно присваивать любую другую переменную и наблюдать её +//в UniCon, а также использовать их напрямую в ПО для отладки и менять на ходу. +volatile long Debug1 = 0; +volatile long Debug2 = 0; +volatile Uint16 Debug3 = 0; +volatile Uint16 Debug4 = 0; +volatile long DebugW1 = 0; +volatile long DebugW2 = 0; +volatile long DebugW3 = 0; +volatile long DebugW4 = 0; +volatile float DebugF1 = 0; +volatile float DebugF2 = 0; +volatile float DebugF3 = 0; +volatile float DebugF4 = 0; + +//Счетчики прерываний модуля захвата +Uint16 CounterCAP_isr = 0; +Uint16 cap0_counter = 0; +Uint16 cap1_counter = 0; +Uint16 cap2_counter = 0; + +Uint16 LoopCounter = 0; //!< Счетчик итераций фонового цикла + +//!С этой функции начинается запуск программы +//! \memberof MAIN_C +int main(void) { + + co1_vars.co_productCode = 51; + co1_vars.co_revisionNumber = 1; + + /* Настройка тактирования, включение периферии */ + SystemInit(); // Настройка клоков + SystemCoreClockUpdate(); // Апдейти системных переменных настроенными клоками (хз зачем, необязательно) + // Копирование некоторых функций и всех прерываний в RAM +#if defined (__GNUC__) + memcpy(&__isr_vector_ram_start, &__isr_vector_flash_start, + ((Uint32) (&__isr_vector_ram_end) + - (Uint32) (&__isr_vector_ram_start))); +#elif defined (__CMCPPARM__) + // Для CodeMaster непонятно, как разместить таблицу прерываний во флеше, а обращатся к ней в раме, + // так что пока так. +#endif + + pwm.Off(&pwm); //выключить ШИМ (на всякий случай) + DINT; + //Инициализация, собственно, всего. + sm_sys.init(&sm_sys); + EINT;//разрешение прерываний + + //тип и версия устройства для драйвера CANOpen + + while (1) { //Фоновый цикл + LoopCounter++; + sm_sys.slow_calc(&sm_sys); //Фоновый расчет + } +} + +unsigned long CpuTimerIsr1 = 0; +Uint16 TIsr1 = 0; +Uint16 msCounter = 0; + +//! Прервыние, вызываемое по таймеру с частотой 1кГц +//! \memberof MAIN_C +void TMR1_IRQHandler(void) { + CpuTimerIsr1 = TMR2->VALUE; //Засекается время выполнения функции + sm_sys.ms_calc(&sm_sys); //миллисекундный расчет всего + + msCounter++; + + TIsr1 = (CpuTimerIsr1 - TMR2->VALUE) & 0xFFFFFF; //время выполнения функции + if (TIsr1 > 97000) { + sm_prot.bit_fault1 |= F_PROGRAM_1K; //если расчет слишком долгий, ошибка + } + + TMR1->INTSTATUS_bit.INT = 1; //сброс прерывания +} + +Uint16 FastCounter = 0; +unsigned long CpuTimerIsr10 = 0; +Uint16 TIsr10 = 0; + +//! Прервыние, вызываемое по таймеру с частотой 10кГц +//! \memberof MAIN_C +void TMR0_IRQHandler(void) { + CpuTimerIsr10 = TMR2->VALUE; //Засекается время выполнения функции + sm_sys.fast_calc(&sm_sys); //расчет 10кГц всего + + FastCounter++; + TIsr10 = (CpuTimerIsr10 - TMR2->VALUE) & 0xFFFFFF; //время выполнения функции + if (TIsr10 > 9700) { + sm_prot.bit_fault1 |= F_PROGRAM_10K; //если расчет слишком долгий, ошибка + } + TMR0->INTSTATUS_bit.INT = 1; //сброс прерывания +} + +Uint16 ePWM0_TZ_isr_counter = 0; +//!Прерывание, возникающее при аппаратной аварии +//! \memberof MAIN_C +#if defined (__GNUC__) +void PWM0_TZ_IRQHandler(void) +#elif defined (__CMCPPARM__) +void PWM0_TZ_IRQHandler(void) +#endif +{ + //Так как аппаратная авария возникает при включении ШИМ + //и удерживается пока заряжаются будстрепные конденсаторы, + //в прерывании на нее не реагируем + //Хотя в "настоящем" инверторе на высокое напряжение это, конечно, надо делать + //Здесь микросхема драйверов защитит всё сама, такого выхода у неё нет + ePWM0_TZ_isr_counter++; + /* + pwm12.Off(&pwm12); + + if (sm_ctrl.state!=CTRL_STOP) + { + sm_prot.bit_fault1|= F_PDPINT; + } + sm_ctrl.state=CTRL_STOP; + //сбрасываем флаги прерываний по этой ножке + */ +} + + +//!Прерывание, возникающее по событиям захвата модуля CAP0 +//! \memberof MAIN_C +#if defined (__GNUC__) +void ECAP0_IRQHandler(void) +#elif defined (__CMCPPARM__) +void CAP0_IRQHandler(void) +#endif +{ + //Подтверждаем это прерывание для NVIC - иначе при выходе из функции оно возникнет опять + ECAP0->PEINT = 1; + + if (DPReCAP.CAPCalcEna1 == 0) { //если функция вызвалась повторно + DPReCAP.CAP_WrongEdgeCnt = (++DPReCAP.CAP_WrongEdgeCnt) & 0xFF; + DPReCAP.CAP_WrongEdgeCnt1++; + return; + } + DPReCAP.CAPCalcEna1 = 0;//расчет будет разрешен, когда тикнет прерывание 10кГц. Чаще считать нет смысла, это помехи + + CounterCAP_isr++;//общий счётчик всех прерываний модуля захвата + CounterCAP_isr = CounterCAP_isr & 0xF; + cap0_counter++;//счётчик прерываний именно этого канала + //исходя из состояния ног трех датчиков Холла высчитывает текущий угол с точностью 60 градусов. + //выходом функции является DPReCAP.Angle6 - угол с точностью 60 градусов. + DPReCAP.Angle6Calc(&DPReCAP); + //обработчик модуля захвата канала1 (0, если считать с нуля, но не переименовывать же какждый раз функции, в зависимости от версии заголовочных файлов...). + //Засекает время между этим импульсом и предыдущими для расчета интерполятора угла и частоты вращения (скорости) + DPReCAP.CAP1Calc(&DPReCAP); + + //Подтверждение прерываний + ECAP0->ECCLR_bit.CEVT0 = 1; + ECAP0->ECCLR_bit.CEVT1 = 1; + ECAP0->ECCLR_bit.INT = 1; + +} + +//!Прерывание, возникающее по событиям захвата модуля CAP1 +//! \memberof MAIN_C +#if defined (__GNUC__) +void ECAP1_IRQHandler(void) +#elif defined (__CMCPPARM__) +void CAP1_IRQHandler(void) +#endif +{ + //Подтверждаем это прерывание для NVIC - иначе при выходе из функции оно возникнет опять + ECAP1->PEINT = 1; + + if (DPReCAP.CAPCalcEna2 == 0) { //если функция вызвалась повторно + DPReCAP.CAP_WrongEdgeCnt = (++DPReCAP.CAP_WrongEdgeCnt) & 0xFF; + DPReCAP.CAP_WrongEdgeCnt2++; + return; + } + DPReCAP.CAPCalcEna2 = 0; + + CounterCAP_isr++; + CounterCAP_isr = CounterCAP_isr & 0xF; + cap1_counter++; + DPReCAP.Angle6Calc(&DPReCAP); + DPReCAP.CAP2Calc(&DPReCAP); + + //Подтверждение прерываний + ECAP1->ECCLR_bit.CEVT0 = 1; + ECAP1->ECCLR_bit.CEVT1 = 1; + ECAP1->ECCLR_bit.INT = 1; +} + + +//!Прерывание, возникающее по событиям захвата модуля CAP2 +//! \memberof MAIN_C +#if defined (__GNUC__) +void ECAP2_IRQHandler(void) +#elif defined (__CMCPPARM__) +void CAP2_IRQHandler(void) +#endif +{ + //Подтверждаем это прерывание для NVIC - иначе при выходе из функции оно возникнет опять + ECAP2->PEINT = 1; + + if (DPReCAP.CAPCalcEna3 == 0) { //если функция вызвалась повторно + DPReCAP.CAP_WrongEdgeCnt = (++DPReCAP.CAP_WrongEdgeCnt) & 0xFF; + DPReCAP.CAP_WrongEdgeCnt3++; + return; + } + DPReCAP.CAPCalcEna3 = 0; + + CounterCAP_isr++; + CounterCAP_isr = CounterCAP_isr & 0xF; + cap2_counter++; + DPReCAP.Angle6Calc(&DPReCAP); //если убрать, то в момент прихода метки на один период ШИМ косяк, так как прерывание посчиталось, а Angle6Calc нет + DPReCAP.CAP3Calc(&DPReCAP); + + //Подтверждение прерываний + ECAP2->ECCLR_bit.CEVT0 = 1; + ECAP2->ECCLR_bit.CEVT1 = 1; + ECAP2->ECCLR_bit.INT = 1; +} + +//!Прерывание, возникающее по событию реперной метки(индекса) модуля QEP +//! \memberof MAIN_C +//! Но - на двигателе ACM601V36-1000 нет индексной метки. +//Так что этого прерывания c таким двигателем не будет (или будет от помех, как повезет) +#if defined (__GNUC__) +void QEP_IRQHandler(void) +#elif defined (__CMCPPARM__) +void QEP1_IRQHandler(void) +#endif +{ + //Обработка репера + posspeedEqep.index(&posspeedEqep); + //Подтверждаем это прерывание для NVIC + QEP->INTCLR = 1; + QEP->QCLR_bit.IEL = 1; + QEP->QCLR_bit.INT = 1; +} + +//Прерывание вызывается один раз на периоде ШИМ и забирает 4 результата за период +void ADC_SEQ0_IRQHandler (void) { + adc.fast_calc(&adc); + + dlog.update(&dlog); //Осциллографирование данных + ADC->IC_bit.SEQIC0 = 1; +} +/*@}*/ + diff --git a/Vsrc/park.c b/Vsrc/park.c new file mode 100644 index 0000000..5e8a067 --- /dev/null +++ b/Vsrc/park.c @@ -0,0 +1,47 @@ +/*! + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + \file park.c + \brief Модуль координатных преобразований координат (см. TPark) + \author ООО "НПФ Вектор". http://motorcontrol.ru + \version v 2.0 25/03/2016 + + \addtogroup Park + @{ + */ + +#include "V_IQmath.h" /* Include header for IQmath library */ +#include "park.h" + +//! Функция преобразований координат + +//!На входе угол ang, вектор (ds,qs). +//!На выходе повернутый на заданный угол вектор (de,qe) +//! \memberof TPark +void park_calc(TPark *v) { + + _iq cos_ang, sin_ang; + + /* Using look-up IQ sine table */ + sin_ang = _IQsinPU(v->ang); + cos_ang = _IQcosPU(v->ang); + + v->de = _IQmpy(v->ds,cos_ang) + _IQmpy(v->qs, sin_ang); + v->qe = _IQmpy(v->qs,cos_ang) - _IQmpy(v->ds, sin_ang); + +} + +/*@}*/ + diff --git a/asm/startup_K1921VK035_vector.S b/asm/startup_K1921VK035_vector.S new file mode 100644 index 0000000..40cd656 --- /dev/null +++ b/asm/startup_K1921VK035_vector.S @@ -0,0 +1,307 @@ +/** + ****************************************************************************** + * @file startup_MCP.s + * @author Vector / NIIET + * @version V1.0.0 + * @date 28 - September - 2014 + * @brief NIIET MC01 vector table for Sourcery Codebench. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * - enables FPU (COMING SOON!) + * After Reset the Cortex-M4 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + */ + + .syntax unified + .cpu cortex-m3 + .fpu vfpv4 + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + + +/* Включение плавоточки*/ + + ldr.w R0, =0xE000ED88 + ldr R1, [R0] + orr R1, R1, #(0xF << 20) + str R1, [R0] + dsb + isb /*reset pipeline now the FPU is enabled*/ + + ldr r0, = _estack /* Эти две строки - загрузка SP адресом 2000а000 в случае, если флешка потёрта. Если проект шьётся во флеш - удалить.*/ + msr msp, r0 /* ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + + + .word WDT_IRQHandler + .word RCU_IRQHandler + .word MFLASH_IRQHandler + .word GPIOA_IRQHandler + .word GPIOB_IRQHandler + .word DMA_CH0_IRQHandler + .word DMA_CH1_IRQHandler + .word DMA_CH2_IRQHandler + .word DMA_CH3_IRQHandler + .word DMA_CH4_IRQHandler + .word DMA_CH5_IRQHandler + .word DMA_CH6_IRQHandler + .word DMA_CH7_IRQHandler + .word DMA_CH8_IRQHandler + .word DMA_CH9_IRQHandler + .word DMA_CH10_IRQHandler + .word DMA_CH11_IRQHandler + .word DMA_CH12_IRQHandler + .word DMA_CH13_IRQHandler + .word DMA_CH14_IRQHandler + .word DMA_CH15_IRQHandler + .word TMR0_IRQHandler + .word TMR1_IRQHandler + .word TMR2_IRQHandler + .word TMR3_IRQHandler + .word UART0_TD_IRQHandler + .word UART0_RX_IRQHandler + .word UART0_TX_IRQHandler + .word UART0_E_RT_IRQHandler + .word UART1_TD_IRQHandler + .word UART1_RX_IRQHandler + .word UART1_TX_IRQHandler + .word UART1_E_RT_IRQHandler + .word SPI_RO_RT_IRQHandler + .word SPI_RX_IRQHandler + .word SPI_TX_IRQHandler + .word I2C_IRQHandler + .word ECAP0_IRQHandler + .word ECAP1_IRQHandler + .word ECAP2_IRQHandler + .word PWM0_IRQHandler + .word PWM0_HD_IRQHandler + .word PWM0_TZ_IRQHandler + .word PWM1_IRQHandler + .word PWM1_HD_IRQHandler + .word PWM1_TZ_IRQHandler + .word PWM2_IRQHandler + .word PWM2_HD_IRQHandler + .word PWM2_TZ_IRQHandler + .word QEP_IRQHandler + .word ADC_SEQ0_IRQHandler + .word ADC_SEQ1_IRQHandler + .word ADC_DC_IRQHandler + .word CAN0_IRQHandler + .word CAN1_IRQHandler + .word CAN2_IRQHandler + .word CAN3_IRQHandler + .word CAN4_IRQHandler + .word CAN5_IRQHandler + .word CAN6_IRQHandler + .word CAN7_IRQHandler + .word CAN8_IRQHandler + .word CAN9_IRQHandler + .word CAN10_IRQHandler + .word CAN11_IRQHandler + .word CAN12_IRQHandler + .word CAN13_IRQHandler + .word CAN14_IRQHandler + .word CAN15_IRQHandler + .word FPU_IRQHandler + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ +/* Macro to define default handlers. Default handler + * will be weak symbol and just dead loops. They can be + * overwritten by other handlers */ + .macro def_irq_handler handler_name + .weak \handler_name + .thumb_set \handler_name, Default_Handler + .endm + + def_irq_handler NMI_Handler + def_irq_handler HardFault_Handler + def_irq_handler MemManage_Handler + def_irq_handler BusFault_Handler + def_irq_handler UsageFault_Handler + def_irq_handler SVC_Handler + def_irq_handler DebugMon_Handler + def_irq_handler PendSV_Handler + def_irq_handler SysTick_Handler + + /* External Interrupt Handlers */ + def_irq_handler WDT_IRQHandler + def_irq_handler RCU_IRQHandler + def_irq_handler MFLASH_IRQHandler + def_irq_handler GPIOA_IRQHandler + def_irq_handler GPIOB_IRQHandler + def_irq_handler DMA_CH0_IRQHandler + def_irq_handler DMA_CH1_IRQHandler + def_irq_handler DMA_CH2_IRQHandler + def_irq_handler DMA_CH3_IRQHandler + def_irq_handler DMA_CH4_IRQHandler + def_irq_handler DMA_CH5_IRQHandler + def_irq_handler DMA_CH6_IRQHandler + def_irq_handler DMA_CH7_IRQHandler + def_irq_handler DMA_CH8_IRQHandler + def_irq_handler DMA_CH9_IRQHandler + def_irq_handler DMA_CH10_IRQHandler + def_irq_handler DMA_CH11_IRQHandler + def_irq_handler DMA_CH12_IRQHandler + def_irq_handler DMA_CH13_IRQHandler + def_irq_handler DMA_CH14_IRQHandler + def_irq_handler DMA_CH15_IRQHandler + def_irq_handler TMR0_IRQHandler + def_irq_handler TMR1_IRQHandler + def_irq_handler TMR2_IRQHandler + def_irq_handler TMR3_IRQHandler + def_irq_handler UART0_TD_IRQHandler + def_irq_handler UART0_RX_IRQHandler + def_irq_handler UART0_TX_IRQHandler + def_irq_handler UART0_E_RT_IRQHandler + def_irq_handler UART1_TD_IRQHandler + def_irq_handler UART1_RX_IRQHandler + def_irq_handler UART1_TX_IRQHandler + def_irq_handler UART1_E_RT_IRQHandler + def_irq_handler SPI_RO_RT_IRQHandler + def_irq_handler SPI_RX_IRQHandler + def_irq_handler SPI_TX_IRQHandler + def_irq_handler I2C_IRQHandler + def_irq_handler ECAP0_IRQHandler + def_irq_handler ECAP1_IRQHandler + def_irq_handler ECAP2_IRQHandler + def_irq_handler PWM0_IRQHandler + def_irq_handler PWM0_HD_IRQHandler + def_irq_handler PWM0_TZ_IRQHandler + def_irq_handler PWM1_IRQHandler + def_irq_handler PWM1_HD_IRQHandler + def_irq_handler PWM1_TZ_IRQHandler + def_irq_handler PWM2_IRQHandler + def_irq_handler PWM2_HD_IRQHandler + def_irq_handler PWM2_TZ_IRQHandler + def_irq_handler QEP_IRQHandler + def_irq_handler ADC_SEQ0_IRQHandler + def_irq_handler ADC_SEQ1_IRQHandler + def_irq_handler ADC_DC_IRQHandler + def_irq_handler CAN0_IRQHandler + def_irq_handler CAN1_IRQHandler + def_irq_handler CAN2_IRQHandler + def_irq_handler CAN3_IRQHandler + def_irq_handler CAN4_IRQHandler + def_irq_handler CAN5_IRQHandler + def_irq_handler CAN6_IRQHandler + def_irq_handler CAN7_IRQHandler + def_irq_handler CAN8_IRQHandler + def_irq_handler CAN9_IRQHandler + def_irq_handler CAN10_IRQHandler + def_irq_handler CAN11_IRQHandler + def_irq_handler CAN12_IRQHandler + def_irq_handler CAN13_IRQHandler + def_irq_handler CAN14_IRQHandler + def_irq_handler CAN15_IRQHandler + def_irq_handler FPU_IRQHandler diff --git a/cmd/build.ld b/cmd/build.ld new file mode 100644 index 0000000..72c31a7 --- /dev/null +++ b/cmd/build.ld @@ -0,0 +1,242 @@ +/****************************************************************************** + Copyright 2017 АО "НИИЭТ" и ООО "НПФ ВЕКТОР" + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + * @file build.ld + * @brief Файл распределения памяти для выполнения из FLASH + * @version v1.0 + * @date 11 декабря 2015 + * + * @author ООО "НПФ Вектор", http://motorcontrol.ru + * + ******************************************************************************/ + +/* Entry Point */ +ENTRY(Reset_Handler) + + +/* Generate a link error if heap and stack don't fit into RAM */ +_Stack_Size = 0x1000; /* required amount of stack */ + +/* Specify the memory areas */ +/* Буквы в скобках определяют атрибуты: доступ на чтение, + * запись, исполнение, выделение памяти. */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 0x10000 + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 0x4000 +} +/* Конец РАМы на НИИЭТЕ (с запасиком) - отсюда внутрь будет расти стек*/ +_estack = ORIGIN(RAM) + LENGTH(RAM) - 4; + + +/* Define output sections */ +SECTIONS +{ + . = ORIGIN(RAM); + /* таблица векторов прерываний, обязана быть выровнена по 0х80 */ + .isr_vector ALIGN(0x80): + { + __isr_vector_flash_start = LOADADDR (.isr_vector); /* Берем адрес, где на флеше лежит эта таблица */ + __isr_vector_ram_start = .; + KEEP(*(.isr_vector)) /* Startup code - KEEP запрещает удалить секцию сборщику мусора */ + . = ALIGN(4); + __isr_vector_ram_end = .; /* конец оперативки, куда будет скопирован код */ + } >RAM AT>FLASH + + /* Секция для кода, который исполняется в оперативке, а лежит на флеше. + * В начале мейна он копируется из ROM в RAM.*/ + .fastcode ALIGN(4): { + __fastcode_flash_start = LOADADDR (.fastcode); /* Берем адрес, где на флеше лежит код. */ + /* Точка - это курсор текущего размещения в памяти. Т.е. в + * __fastcode_ram_start будет лежать адрес оперативки, где будет исполняться скопированный код.*/ + __fastcode_ram_start = .; + *(.glue_7t) *(.glue_7) + *(.fastcode) + *(.fastcode*) + . = ALIGN (4); + __fastcode_ram_end = .; /* конец оперативки, куда будет скопирован код */ + } >RAM AT>FLASH + + /* The program code and other data goes into RAM */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + + /* define a global symbols at end of code - указатель на конец кода, + т.к. точка - это переменная с инкрементирующимся значением адреса (называют её курсор)*/ + _etext = .; + } >FLASH + + + /* .preinit_array - секция для указателей на функции пре-инициализации, + * вызываемых перед любыми другими функциями + * инициализации (перед выполнением кода из секции + * '.init' и вызовами функций из секции '.init_array'). + * + * Специальная секция с именем '.preinit_array' и вышеназванным + * назначением описана в System V gABI. Вызов функций, указатели на + * которые содержатся в секции '.preinit_array', возлагается на библиотеку + * времени выполнения (runtime library) -- например, на C runtime. Если в + * библиотеке не предусмотрен такой вызов, то функции из секции + * '.preinit_array' не будут вызваны. + * + * Секция '.preinit_array' предназначена для пре-инициализации + * исполняемого файла (executable), выполняемой перед инициализацией + * динамически скомпонованных с ним разделяемых объектов (shared objects). + * + * Символы __preinit_array_start и __preinit_array_end используются + * библиотекой C времени выполнения (newlib, glibc). + */ + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + + /* .init_array - секции с указателями на функции инициализации, + * выполняющиеся перед вызовом входной точки программы, т.е. + * перед вызовом функции main. + * + * Специальная секция с именем '.init_array' и вышеназванным назначением + * описана в System V gABI. Вызов функций, указатели на которые содержатся в + * секции '.init_array', возлагается на библиотеку времени выполнения + * (runtime library) -- например, на C runtime. Если в библиотеке не + * предусмотрен такой вызов, то функции из секции '.init_array' не будут + * вызваны. + * + * GCC использует секцию '.init_array' для обеспечения вызова статических + * конструкторов: функций, объявленных с __attribute__((constructor)). + * + * Для статических конструкторов с объявленным приоритетом PRIORITY, + * используются секции с именем '.init_array.PRIORITY' + * + * Также GCC использует секцию '.init_array' для вызова конструкторов + * статических объектов C++. + * + * Символы __init_array_start и __init_array_end используются библиотекой + * C времени выполнения (newlib, glibc). + */ + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + /* .fini_array - секции с указателями на функции терминации, + * выполняющиеся по завершению программы (после возврата из + * входной точки программы, т.е. из функции main). + * + * Специальная секция с именем '.fini_array' и вышеназванным назначением + * описана в System V gABI. Вызов функций, указатели на которые содержатся в + * секции '.fini_array', возлагается на библиотеку времени выполнения + * (runtime library) -- например, на C runtime. Если в библиотеке не + * предусмотрен такой вызов, то функции из секции '.fini_array' не будут + * вызваны. + * + * GCC использует секцию '.fini_array' для обеспечения вызова статических + * деструкторов: функций, объявленных с __attribute__((destructor)). + * + * Для статических деструкторов с объявленным приоритетом PRIORITY, + * используются секции с именем '.fini_array.PRIORITY' + * + * Символы __fini_array_start и __fini_array_end используются библиотекой + * C времени выполнения (newlib, glibc). + */ + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(.fini_array*)) + KEEP (*(SORT(.fini_array.*))) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = .; + + + /* Выражение _sidata, которое следует за ключевым словом AT, + * определяет адрес загрузки секции. По умолчанию, если Вы + * не использовали ключевое слово AT, адрес загрузки равен адресу перемещения. + * Так как _sidata до этого было равно точке (указатель на текущий адрес), + * то .data пойдет сразу дальше после неё. Как бы динамическое смещение такое. + * */ + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : AT ( _sidata ) + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM + _________________________ZHOPA__________________________ = .; + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + + /* Функци проверяет, что после всего кода осталось место под стек. + * Стек сделан снизу оперативки! + * Не размещайте свои секции после этой функции, только перед!*/ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Stack_Size + 4; + . = ALIGN(4); + } >RAM + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + /* Тут какие-то атрибуты об особенностях компиляции, специфичная инфа производителя и хз еще что, читайте + * 4.3.6 Build Attributes http://infocenter.arm.com/help/topic/com.arm.doc.ihi0044e/IHI0044E_aaelf.pdf */ + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/cood.xml b/cood.xml new file mode 100644 index 0000000..2e3faa6 --- /dev/null +++ b/cood.xml @@ -0,0 +1,4547 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/include/K1921VK035.h b/include/K1921VK035.h new file mode 100644 index 0000000..d511459 --- /dev/null +++ b/include/K1921VK035.h @@ -0,0 +1,10232 @@ +/******************************************************************************* + * @file: K1921VK035.h + * @author NIIET + * @version: V2.3 + * @date: 31.05.2018 + * @brief: K1921VK035 header file + ******************************************************************************* + *

+ * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, NIIET NOT BE HELD LIABLE FOR ANY DIRECT, + * INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2018 NIIET

+ ******************************************************************************* + * FILE K1921VK035.h + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __K1921VK035_H +#define __K1921VK035_H + +#define __I volatile const /*!< defines 'read only' permissions */ +#define __O volatile /*!< defines 'write only' permissions */ +#define __IO volatile /*!< defines 'read / write' permissions */ + +/* Start of section using anonymous unions */ +#if defined (__CC_ARM) + #pragma push + #pragma anon_unions +#elif defined (__ICCARM__) + #pragma language=extended +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wc11-extensions" + #pragma clang diagnostic ignored "-Wreserved-id-macro" +#elif defined (__GNUC__) + /* anonymous unions are enabled by default */ +#elif defined (__TMS470__) + /* anonymous unions are enabled by default */ +#elif defined (__TASKING__) + #pragma warning 586 +#elif defined (__CSMC__) + /* anonymous unions are enabled by default */ +#elif defined (__CMCPPARM__) + /* anonymous unions are enabled by default */ +#else + #warning Not supported compiler type +#endif + +/* Configuration of the Cortex-M4F Processor and Core Peripherals */ +#define __CM4_REV 0x0001 /*!< Cortex-M4F Core Revision r0p1 */ +#define __MPU_PRESENT 1 /*!< MPU present or not */ +#define __NVIC_PRIO_BITS 3 /*!< Number of Bits used for Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ +#define __FPU_PRESENT 1 /*!< FPU present or not */ + +#include "stdint.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/******************************************************************************/ +/* Interrupt Number Definition */ +/******************************************************************************/ + +typedef enum IRQn +{ +/*-- Cortex-M4F Processor Exceptions Numbers ---------------------------------*/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + HardFault_IRQn = -13, /*!< 3 Hard Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 SV Call Interrupt */ + PendSV_IRQn = -2, /*!< 14 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 System Tick Timer Interrupt */ +/*-- Device specific Interrupt Numbers ---------------------------------------*/ + WDT_IRQn = 0, /*!< Watchdog timer interrupt */ + RCU_IRQn = 1, /*!< Reset and clock unit interrupt */ + MFLASH_IRQn = 2, /*!< MFLASH interrupt */ + GPIOA_IRQn = 3, /*!< GPIO A interrupt */ + GPIOB_IRQn = 4, /*!< GPIO B interrupt */ + DMA_CH0_IRQn = 5, /*!< DMA channel 0 interrupt */ + DMA_CH1_IRQn = 6, /*!< DMA channel 1 interrupt */ + DMA_CH2_IRQn = 7, /*!< DMA channel 2 interrupt */ + DMA_CH3_IRQn = 8, /*!< DMA channel 3 interrupt */ + DMA_CH4_IRQn = 9, /*!< DMA channel 4 interrupt */ + DMA_CH5_IRQn = 10, /*!< DMA channel 5 interrupt */ + DMA_CH6_IRQn = 11, /*!< DMA channel 6 interrupt */ + DMA_CH7_IRQn = 12, /*!< DMA channel 7 interrupt */ + DMA_CH8_IRQn = 13, /*!< DMA channel 8 interrupt */ + DMA_CH9_IRQn = 14, /*!< DMA channel 9 interrupt */ + DMA_CH10_IRQn = 15, /*!< DMA channel 10 interrupt */ + DMA_CH11_IRQn = 16, /*!< DMA channel 11 interrupt */ + DMA_CH12_IRQn = 17, /*!< DMA channel 12 interrupt */ + DMA_CH13_IRQn = 18, /*!< DMA channel 13 interrupt */ + DMA_CH14_IRQn = 19, /*!< DMA channel 14 interrupt */ + DMA_CH15_IRQn = 20, /*!< DMA channel 15 interrupt */ + TMR0_IRQn = 21, /*!< Timer 0 interrupt */ + TMR1_IRQn = 22, /*!< Timer 1 interrupt */ + TMR2_IRQn = 23, /*!< Timer 2 interrupt */ + TMR3_IRQn = 24, /*!< Timer 3 interrupt */ + UART0_TD_IRQn = 25, /*!< UART0 Transmit Done interrupt */ + UART0_RX_IRQn = 26, /*!< UART0 Recieve interrupt */ + UART0_TX_IRQn = 27, /*!< UART0 Transmit interrupt */ + UART0_E_RT_IRQn = 28, /*!< UART0 Error and Receive Timeout interrupt*/ + UART1_TD_IRQn = 29, /*!< UART1 Transmit Done interrupt */ + UART1_RX_IRQn = 30, /*!< UART1 Recieve interrupt */ + UART1_TX_IRQn = 31, /*!< UART1 Transmit interrupt */ + UART1_E_RT_IRQn = 32, /*!< UART1 Error and Receive Timeout interrupt*/ + SPI_RO_RT_IRQn = 33, /*!< SPI RX FIFO overrun and Receive Timeout interrupt*/ + SPI_RX_IRQn = 34, /*!< SPI Receive interrupt */ + SPI_TX_IRQn = 35, /*!< SPI Transmit interrupt */ + I2C_IRQn = 36, /*!< I2C interrupt */ + ECAP0_IRQn = 37, /*!< ECAP0 interrupt */ + ECAP1_IRQn = 38, /*!< ECAP1 interrupt */ + ECAP2_IRQn = 39, /*!< ECAP2 interrupt */ + PWM0_IRQn = 40, /*!< PWM0 interrupt */ + PWM0_HD_IRQn = 41, /*!< PWM0 HD interrupt */ + PWM0_TZ_IRQn = 42, /*!< PWM0 TZ interrupt */ + PWM1_IRQn = 43, /*!< PWM1 interrupt */ + PWM1_HD_IRQn = 44, /*!< PWM1 HD interrupt */ + PWM1_TZ_IRQn = 45, /*!< PWM1 TZ interrupt */ + PWM2_IRQn = 46, /*!< PWM2 interrupt */ + PWM2_HD_IRQn = 47, /*!< PWM2 HD interrupt */ + PWM2_TZ_IRQn = 48, /*!< PWM2 TZ interrupt */ + QEP_IRQn = 49, /*!< QEP interrupt */ + ADC_SEQ0_IRQn = 50, /*!< ADC Sequencer 0 interrupt */ + ADC_SEQ1_IRQn = 51, /*!< ADC Sequencer 1 interrupt */ + ADC_DC_IRQn = 52, /*!< ADC Digital Comparator interrupt */ + CAN0_IRQn = 53, /*!< CAN0 interrupt */ + CAN1_IRQn = 54, /*!< CAN1 interrupt */ + CAN2_IRQn = 55, /*!< CAN2 interrupt */ + CAN3_IRQn = 56, /*!< CAN3 interrupt */ + CAN4_IRQn = 57, /*!< CAN4 interrupt */ + CAN5_IRQn = 58, /*!< CAN5 interrupt */ + CAN6_IRQn = 59, /*!< CAN6 interrupt */ + CAN7_IRQn = 60, /*!< CAN7 interrupt */ + CAN8_IRQn = 61, /*!< CAN8 interrupt */ + CAN9_IRQn = 62, /*!< CAN9 interrupt */ + CAN10_IRQn = 63, /*!< CAN10 interrupt */ + CAN11_IRQn = 64, /*!< CAN11 interrupt */ + CAN12_IRQn = 65, /*!< CAN12 interrupt */ + CAN13_IRQn = 66, /*!< CAN13 interrupt */ + CAN14_IRQn = 67, /*!< CAN14 interrupt */ + CAN15_IRQn = 68, /*!< CAN15 interrupt */ + FPU_IRQn = 69, /*!< FPU exception interrupt */ +} IRQn_Type; + +#include /* Cortex-M4 processor and core peripherals */ +#include /* System initialization */ + +/******************************************************************************/ +/* System Specific Defenitions */ +/******************************************************************************/ +/*-- System memory ----------------------------------------------------------*/ +#define MEM_MFLASH_BASE 0x00000000UL +#define MEM_MFLASH_BUS_WIDTH_WORDS 2UL +#define MEM_MFLASH_PAGE_SIZE 1024UL +#define MEM_MFLASH_PAGE_SIZE_LOG2 10UL +#define MEM_MFLASH_PAGE_TOTAL 64UL +#define MEM_MFLASH_SIZE (MEM_MFLASH_PAGE_TOTAL*MEM_MFLASH_PAGE_SIZE) +#define MEM_MFLASH_NVR_PAGE_SIZE (MEM_MFLASH_PAGE_SIZE) +#define MEM_MFLASH_NVR_PAGE_SIZE_LOG2 (MEM_MFLASH_PAGE_SIZE_LOG2) +#define MEM_MFLASH_NVR_PAGE_TOTAL 4UL +#define MEM_MFLASH_NVR_SIZE (MEM_MFLASH_NVR_PAGE_TOTAL*MEM_MFLASH_NVR_PAGE_SIZE) +#define MEM_RAM_BASE 0x20000000UL +#define MEM_RAM_SIZE 0x4000UL + +/*-- CFGWORD: System configure word -----------------------------------------*/ +#define CFGWORD_BASE 0x00000C00UL + +typedef struct { + uint32_t JTAGEN : 1; /*!< Enable JTAG pins (default 1 - enabled) */ + uint32_t DEBUGEN : 1; /*!< Enable core debug (default 1 - enabled) */ + uint32_t NVRWE : 1; /*!< NVR flash region write enable (default 1 - enabled) */ + uint32_t FLASHWE : 1; /*!< Main flash region write enable (default 1 - enabled) */ + uint32_t BMODEDIS : 1; /*!< Bootloader disable (default 1 - disabled) */ +} CFGWORD_bits; + +/* Bit field positions: */ +#define CFGWORD_JTAGEN_Pos 0 /*!< Enable JTAG pins (default 1 - enabled) */ +#define CFGWORD_DEBUGEN_Pos 1 /*!< Enable core debug (default 1 - enabled) */ +#define CFGWORD_NVRWE_Pos 2 /*!< NVR flash region write enable (default 1 - enabled) */ +#define CFGWORD_FLASHWE_Pos 3 /*!< Main flash region write enable (default 1 - enabled) */ +#define CFGWORD_BMODEDIS_Pos 4 /*!< Bootloader disable (default 1 - disabled) */ + +/* Bit field masks: */ +#define CFGWORD_JTAGEN_Msk 0x00000001UL /*!< Enable JTAG pins (default 1 - enabled) */ +#define CFGWORD_DEBUGEN_Msk 0x00000002UL /*!< Enable core debug (default 1 - enabled) */ +#define CFGWORD_NVRWE_Msk 0x00000004UL /*!< NVR flash region write enable (default 1 - enabled) */ +#define CFGWORD_FLASHWE_Msk 0x00000008UL /*!< Main flash region write enable (default 1 - enabled) */ +#define CFGWORD_BMODEDIS_Msk 0x00000010UL /*!< Bootloader disable (default 1 - disabled) */ + +/*-- CHANNEL_CFG: DMA channel configure word --------------------------------*/ +typedef struct { + uint32_t CYCLE_CTRL : 3; /*!< The operating mode of the DMA cycle */ + uint32_t NEXT_USEBURST : 1; /*!< Controls if the DMA->USEBURSTSET bit is set to a 1 */ + uint32_t N_MINUS_1 : 10; /*!< The total number of DMA transfers that the DMA cycle contains */ + uint32_t R_POWER : 4; /*!< Control how many DMA transfers can occur before the controller rearbitrates (2^R_POWER, 1024 max) */ + uint32_t SRC_PROT_PRIV : 1; /*!< Bus protection when the controller reads the source data: privileged access */ + uint32_t SRC_PROT_BUFF : 1; /*!< Bus protection when the controller reads the source data: bufferable access */ + uint32_t SRC_PROT_CACHE : 1; /*!< Bus protection when the controller reads the source data: cacheable access */ + uint32_t DST_PROT_PRIV : 1; /*!< Bus protection when the controller writes the destination data: privileged access */ + uint32_t DST_PROT_BUFF : 1; /*!< Bus protection when the controller writes the destination data: bufferable access */ + uint32_t DST_PROT_CACHE : 1; /*!< Bus protection when the controller writes the destination data: cacheable access */ + uint32_t SRC_SIZE : 2; /*!< Size of the source data */ + uint32_t SRC_INC : 2; /*!< Source address increment */ + uint32_t DST_SIZE : 2; /*!< Destination data size */ + uint32_t DST_INC : 2; /*!< Destination address increment */ +} _CHANNEL_CFG_bits; + +/* Bit field positions: */ +#define DMA_CHANNEL_CFG_CYCLE_CTRL_Pos 0 /*!< The operating mode of the DMA cycle */ +#define DMA_CHANNEL_CFG_NEXT_USEBURST_Pos 3 /*!< Controls if the DMA->USEBURSTSET bit is set to a 1 */ +#define DMA_CHANNEL_CFG_N_MINUS_1_Pos 4 /*!< The total number of DMA transfers that the DMA cycle contains */ +#define DMA_CHANNEL_CFG_R_POWER_Pos 14 /*!< Control how many DMA transfers can occur before the controller rearbitrates */ +#define DMA_CHANNEL_CFG_SRC_PROT_PRIV_Pos 18 /*!< Bus protection when the controller reads the source data: privileged access */ +#define DMA_CHANNEL_CFG_SRC_PROT_BUFF_Pos 19 /*!< Bus protection when the controller reads the source data: bufferable access */ +#define DMA_CHANNEL_CFG_SRC_PROT_CACHE_Pos 20 /*!< Bus protection when the controller reads the source data: cacheable access */ +#define DMA_CHANNEL_CFG_DST_PROT_PRIV_Pos 21 /*!< Bus protection when the controller writes the destination data: privileged access */ +#define DMA_CHANNEL_CFG_DST_PROT_BUFF_Pos 22 /*!< Bus protection when the controller writes the destination data: bufferable access */ +#define DMA_CHANNEL_CFG_DST_PROT_CACHE_Pos 23 /*!< Bus protection when the controller writes the destination data: cacheable access */ +#define DMA_CHANNEL_CFG_SRC_SIZE_Pos 24 /*!< Size of the source data */ +#define DMA_CHANNEL_CFG_SRC_INC_Pos 26 /*!< Source address increment */ +#define DMA_CHANNEL_CFG_DST_SIZE_Pos 28 /*!< Destination data size */ +#define DMA_CHANNEL_CFG_DST_INC_Pos 30 /*!< Destination address increment */ + +/* Bit field masks: */ +#define DMA_CHANNEL_CFG_CYCLE_CTRL_Msk 0x00000007UL /*!< The operating mode of the DMA cycle */ +#define DMA_CHANNEL_CFG_NEXT_USEBURST_Msk 0x00000008UL /*!< Controls if the DMA->USEBURSTSET bit is set to a 1 */ +#define DMA_CHANNEL_CFG_N_MINUS_1_Msk 0x00003FF0UL /*!< The total number of DMA transfers that the DMA cycle contains */ +#define DMA_CHANNEL_CFG_R_POWER_Msk 0x0003C000UL /*!< Control how many DMA transfers can occur before the controller rearbitrates */ +#define DMA_CHANNEL_CFG_SRC_PROT_PRIV_Msk 0x00040000UL /*!< Bus protection when the controller reads the source data: privileged access */ +#define DMA_CHANNEL_CFG_SRC_PROT_BUFF_Msk 0x00080000UL /*!< Bus protection when the controller reads the source data: bufferable access */ +#define DMA_CHANNEL_CFG_SRC_PROT_CACHE_Msk 0x00100000UL /*!< Bus protection when the controller reads the source data: cacheable access */ +#define DMA_CHANNEL_CFG_DST_PROT_PRIV_Msk 0x00200000UL /*!< Bus protection when the controller writes the destination data: privileged access */ +#define DMA_CHANNEL_CFG_DST_PROT_BUFF_Msk 0x00400000UL /*!< Bus protection when the controller writes the destination data: bufferable access */ +#define DMA_CHANNEL_CFG_DST_PROT_CACHE_Msk 0x00800000UL /*!< Bus protection when the controller writes the destination data: cacheable access */ +#define DMA_CHANNEL_CFG_SRC_SIZE_Msk 0x03000000UL /*!< Size of the source data */ +#define DMA_CHANNEL_CFG_SRC_INC_Msk 0x0C000000UL /*!< Source address increment */ +#define DMA_CHANNEL_CFG_DST_SIZE_Msk 0x30000000UL /*!< Destination data size */ +#define DMA_CHANNEL_CFG_DST_INC_Msk 0xC0000000UL /*!< Destination address increment */ + +/* Bit field enums: */ +typedef enum { + DMA_CHANNEL_CFG_CYCLE_CTRL_Stop = 0x0UL, /*!< Stop */ + DMA_CHANNEL_CFG_CYCLE_CTRL_Basic = 0x1UL, /*!< Basic */ + DMA_CHANNEL_CFG_CYCLE_CTRL_AutoReq = 0x2UL, /*!< Auto-request */ + DMA_CHANNEL_CFG_CYCLE_CTRL_PingPong = 0x3UL, /*!< Ping-pong */ + DMA_CHANNEL_CFG_CYCLE_CTRL_MemScatGathPrim = 0x4UL, /*!< Memory scatter-gather for primary structure */ + DMA_CHANNEL_CFG_CYCLE_CTRL_MemScatGathAlt = 0x5UL, /*!< Memory scatter-gather for alternative structure */ + DMA_CHANNEL_CFG_CYCLE_CTRL_PeriphScatGathPrim = 0x6UL, /*!< Peripheral scatter-gather for primary structure */ + DMA_CHANNEL_CFG_CYCLE_CTRL_PeriphScatGathAlt = 0x7UL, /*!< Peripheral scatter-gather for alternative structure */ +} DMA_CHANNEL_CFG_CYCLE_CTRL_Enum; + +typedef enum { + DMA_CHANNEL_CFG_SRC_SIZE_Byte = 0x0UL, /*!< 8 bit */ + DMA_CHANNEL_CFG_SRC_SIZE_Halfword = 0x1UL, /*!< 16 bit */ + DMA_CHANNEL_CFG_SRC_SIZE_Word = 0x2UL, /*!< 32 bit */ +} DMA_CHANNEL_CFG_SRC_SIZE_Enum; + +typedef enum { + DMA_CHANNEL_CFG_SRC_INC_Byte = 0x0UL, /*!< 8 bit */ + DMA_CHANNEL_CFG_SRC_INC_Halfword = 0x1UL, /*!< 16 bit */ + DMA_CHANNEL_CFG_SRC_INC_Word = 0x2UL, /*!< 32 bit */ + DMA_CHANNEL_CFG_SRC_INC_None = 0x3UL, /*!< No increment */ +} DMA_CHANNEL_CFG_SRC_INC_Enum; + +typedef enum { + DMA_CHANNEL_CFG_DST_SIZE_Byte = 0x0UL, /*!< 8 bit */ + DMA_CHANNEL_CFG_DST_SIZE_Halfword = 0x1UL, /*!< 16 bit */ + DMA_CHANNEL_CFG_DST_SIZE_Word = 0x2UL, /*!< 32 bit */ +} DMA_CHANNEL_CFG_DST_SIZE_Enum; + +typedef enum { + DMA_CHANNEL_CFG_DST_INC_Byte = 0x0UL, /*!< 8 bit */ + DMA_CHANNEL_CFG_DST_INC_Halfword = 0x1UL, /*!< 16 bit */ + DMA_CHANNEL_CFG_DST_INC_Word = 0x2UL, /*!< 32 bit */ + DMA_CHANNEL_CFG_DST_INC_None = 0x3UL, /*!< No increment */ +} DMA_CHANNEL_CFG_DST_INC_Enum; + +/*-- DMA channel structure --------------------------------------------------*/ +typedef struct +{ + __IO uint32_t SRC_DATA_END_PTR; /*!< Source data end pointer */ + __IO uint32_t DST_DATA_END_PTR; /*!< Destination data end pointer */ + union { + __IO uint32_t CHANNEL_CFG; /*!< Channel configure word */ + __IO _CHANNEL_CFG_bits CHANNEL_CFG_bit; /*!< channel configure word: bit access */ + }; + __IO uint32_t RESERVED; +} DMA_Channel_TypeDef; + +/*-- DMA control structure --------------------------------------------------*/ +typedef struct +{ + DMA_Channel_TypeDef CH[16]; /*!< Control structure channels */ +} DMA_CtrlStruct_TypeDef; + +#define DMA_CH_UART0TX 0 /*!< UART0 TX DMA channel */ +#define DMA_CH_UART1TX 1 /*!< UART1 TX DMA channel */ +#define DMA_CH_UART0RX 2 /*!< UART0 RX DMA channel */ +#define DMA_CH_UART1RX 3 /*!< UART1 RX DMA channel */ +#define DMA_CH_ADCSEQ0 4 /*!< ADC sequencer 0 DMA channel */ +#define DMA_CH_ADCSEQ1 5 /*!< ADC sequencer 1 DMA channel */ +#define DMA_CH_SPITX 6 /*!< SPI TX DMA channel */ +#define DMA_CH_SPIRX 7 /*!< SPI RX DMA channel */ +#define DMA_CH_QEP 8 /*!< QEP DMA channel */ +#define DMA_CH_GPIOA 8 /*!< GPIOA DMA channel */ +#define DMA_CH_GPIOB 9 /*!< GPIOB DMA channel */ +#define DMA_CH_TMR0 9 /*!< TMR0 DMA channel */ +#define DMA_CH_TMR1 10 /*!< TMR1 DMA channel */ +#define DMA_CH_TMR2 11 /*!< TMR2 DMA channel */ +#define DMA_CH_TMR3 12 /*!< TMR3 DMA channel */ +#define DMA_CH_PWM0B 10 /*!< PWM0B DMA channel */ +#define DMA_CH_PWM1B 11 /*!< PWM1B DMA channel */ +#define DMA_CH_PWM2B 12 /*!< PWM2B DMA channel */ +#define DMA_CH_PWM0A 13 /*!< PWM0A DMA channel */ +#define DMA_CH_PWM1A 14 /*!< PWM1A DMA channel */ +#define DMA_CH_PWM2A 15 /*!< PWM2A DMA channel */ + +/*-- DMA control data summary -----------------------------------------------*/ +/*!< WARNING: struct should be 512 byte aligned! Allowed addresses 0xXXXXX000, 0xXXXXX200, 0xXXXXX400, etc */ +typedef struct +{ + DMA_CtrlStruct_TypeDef PRM_DATA; /*!< Primary control structure */ + DMA_CtrlStruct_TypeDef ALT_DATA; /*!< Alternative control structure */ +} DMA_CtrlData_TypeDef; + + +/******************************************************************************/ +/* SIU registers */ +/******************************************************************************/ + +/*-- PWMSYNC: PWM syncronization control register ------------------------------------------------------------*/ +typedef struct { + uint32_t :8; /*!< RESERVED */ + uint32_t PRESCRST :3; /*!< PWM prescalers reset control */ +} _SIU_PWMSYNC_bits; + +/* Bit field positions: */ +#define SIU_PWMSYNC_PRESCRST_Pos 8 /*!< PWM prescalers reset control */ + +/* Bit field masks: */ +#define SIU_PWMSYNC_PRESCRST_Msk 0x00000700UL /*!< PWM prescalers reset control */ + +/*-- SERVCTL: Service mode control register ------------------------------------------------------------------*/ +typedef struct { + uint32_t CHIPCLR :1; /*!< On-chip memories full clear task start */ + uint32_t DONE :1; /*!< Status of clear task */ + uint32_t :29; /*!< RESERVED */ + uint32_t SERVEN :1; /*!< */ +} _SIU_SERVCTL_bits; + +/* Bit field positions: */ +#define SIU_SERVCTL_CHIPCLR_Pos 0 /*!< On-chip memories full clear task start */ +#define SIU_SERVCTL_DONE_Pos 1 /*!< Status of clear task */ +#define SIU_SERVCTL_SERVEN_Pos 31 /*!< */ + +/* Bit field masks: */ +#define SIU_SERVCTL_CHIPCLR_Msk 0x00000001UL /*!< On-chip memories full clear task start */ +#define SIU_SERVCTL_DONE_Msk 0x00000002UL /*!< Status of clear task */ +#define SIU_SERVCTL_SERVEN_Msk 0x80000000UL /*!< */ + +/*-- CLKOUTCTL: Clock out control register -------------------------------------------------------------------*/ +typedef struct { + uint32_t CLKOUTEN :1; /*!< Enable clockout pin */ +} _SIU_CLKOUTCTL_bits; + +/* Bit field positions: */ +#define SIU_CLKOUTCTL_CLKOUTEN_Pos 0 /*!< Enable clockout pin */ + +/* Bit field masks: */ +#define SIU_CLKOUTCTL_CLKOUTEN_Msk 0x00000001UL /*!< Enable clockout pin */ + +/*-- REMAPAF: QEP altfunc control ----------------------------------------------------------------------------*/ +typedef struct { + uint32_t QEPEN :1; /*!< Enable QEP altfunc */ + uint32_t ECAP0EN :1; /*!< Enable ECAP0 altfunc */ + uint32_t ECAP1EN :1; /*!< Enable ECAP1 altfunc */ + uint32_t ECAP2EN :1; /*!< Enable ECAP2 altfunc */ +} _SIU_REMAPAF_bits; + +/* Bit field positions: */ +#define SIU_REMAPAF_QEPEN_Pos 0 /*!< Enable QEP altfunc */ +#define SIU_REMAPAF_ECAP0EN_Pos 1 /*!< Enable ECAP0 altfunc */ +#define SIU_REMAPAF_ECAP1EN_Pos 2 /*!< Enable ECAP1 altfunc */ +#define SIU_REMAPAF_ECAP2EN_Pos 3 /*!< Enable ECAP2 altfunc */ + +/* Bit field masks: */ +#define SIU_REMAPAF_QEPEN_Msk 0x00000001UL /*!< Enable QEP altfunc */ +#define SIU_REMAPAF_ECAP0EN_Msk 0x00000002UL /*!< Enable ECAP0 altfunc */ +#define SIU_REMAPAF_ECAP1EN_Msk 0x00000004UL /*!< Enable ECAP1 altfunc */ +#define SIU_REMAPAF_ECAP2EN_Msk 0x00000008UL /*!< Enable ECAP2 altfunc */ + +/*-- DMAMUX: DMA external requests mux control register ------------------------------------------------------*/ +typedef struct { + uint32_t SRCSEL8 :1; /*!< Request source select for DMA channel 8 */ + uint32_t :3; /*!< RESERVED */ + uint32_t SRCSEL9 :1; /*!< Request source select for DMA channel 9 */ + uint32_t :3; /*!< RESERVED */ + uint32_t SRCSEL10 :1; /*!< Request source select for DMA channel 10 */ + uint32_t :3; /*!< RESERVED */ + uint32_t SRCSEL11 :1; /*!< Request source select for DMA channel 11 */ + uint32_t :3; /*!< RESERVED */ + uint32_t SRCSEL12 :1; /*!< Request source select for DMA channel 12 */ + uint32_t :3; /*!< RESERVED */ + uint32_t SRCSEL13 :1; /*!< Request source select for DMA channel 13 */ + uint32_t :3; /*!< RESERVED */ + uint32_t SRCSEL14 :1; /*!< Request source select for DMA channel 14 */ + uint32_t :3; /*!< RESERVED */ + uint32_t SRCSEL15 :1; /*!< Request source select for DMA channel 15 */ +} _SIU_DMAMUX_bits; + +/* Bit field positions: */ +#define SIU_DMAMUX_SRCSEL8_Pos 0 /*!< Request source select for DMA channel 8 */ +#define SIU_DMAMUX_SRCSEL9_Pos 4 /*!< Request source select for DMA channel 9 */ +#define SIU_DMAMUX_SRCSEL10_Pos 8 /*!< Request source select for DMA channel 10 */ +#define SIU_DMAMUX_SRCSEL11_Pos 12 /*!< Request source select for DMA channel 11 */ +#define SIU_DMAMUX_SRCSEL12_Pos 16 /*!< Request source select for DMA channel 12 */ +#define SIU_DMAMUX_SRCSEL13_Pos 20 /*!< Request source select for DMA channel 13 */ +#define SIU_DMAMUX_SRCSEL14_Pos 24 /*!< Request source select for DMA channel 14 */ +#define SIU_DMAMUX_SRCSEL15_Pos 28 /*!< Request source select for DMA channel 15 */ + +/* Bit field masks: */ +#define SIU_DMAMUX_SRCSEL8_Msk 0x00000001UL /*!< Request source select for DMA channel 8 */ +#define SIU_DMAMUX_SRCSEL9_Msk 0x00000010UL /*!< Request source select for DMA channel 9 */ +#define SIU_DMAMUX_SRCSEL10_Msk 0x00000100UL /*!< Request source select for DMA channel 10 */ +#define SIU_DMAMUX_SRCSEL11_Msk 0x00001000UL /*!< Request source select for DMA channel 11 */ +#define SIU_DMAMUX_SRCSEL12_Msk 0x00010000UL /*!< Request source select for DMA channel 12 */ +#define SIU_DMAMUX_SRCSEL13_Msk 0x00100000UL /*!< Request source select for DMA channel 13 */ +#define SIU_DMAMUX_SRCSEL14_Msk 0x01000000UL /*!< Request source select for DMA channel 14 */ +#define SIU_DMAMUX_SRCSEL15_Msk 0x10000000UL /*!< Request source select for DMA channel 15 */ + +/* Bit field enums: */ +typedef enum { + SIU_DMAMUX_SRCSEL8_QEP = 0x0UL, /*!< request by QEP */ + SIU_DMAMUX_SRCSEL8_GPIOA = 0x1UL, /*!< request by GPIOA */ +} SIU_DMAMUX_SRCSEL8_Enum; + +typedef enum { + SIU_DMAMUX_SRCSEL9_TMR0 = 0x0UL, /*!< request by TMR0 */ + SIU_DMAMUX_SRCSEL9_GPIOB = 0x1UL, /*!< request by GPIOB */ +} SIU_DMAMUX_SRCSEL9_Enum; + +typedef enum { + SIU_DMAMUX_SRCSEL10_TMR1 = 0x0UL, /*!< request by TMR1 */ + SIU_DMAMUX_SRCSEL10_PWM0B = 0x1UL, /*!< request by PWM0B */ +} SIU_DMAMUX_SRCSEL10_Enum; + +typedef enum { + SIU_DMAMUX_SRCSEL11_TMR2 = 0x0UL, /*!< request by TMR2 */ + SIU_DMAMUX_SRCSEL11_PWM1B = 0x1UL, /*!< request by PWM1B */ +} SIU_DMAMUX_SRCSEL11_Enum; + +typedef enum { + SIU_DMAMUX_SRCSEL12_TMR3 = 0x0UL, /*!< request by TMR3 */ + SIU_DMAMUX_SRCSEL12_PWM2B = 0x1UL, /*!< request by PWM2B */ +} SIU_DMAMUX_SRCSEL12_Enum; + +typedef enum { + SIU_DMAMUX_SRCSEL13_PWM0A = 0x0UL, /*!< request by PWM0A */ + SIU_DMAMUX_SRCSEL13_Reserved = 0x1UL, /*!< no source */ +} SIU_DMAMUX_SRCSEL13_Enum; + +typedef enum { + SIU_DMAMUX_SRCSEL14_PWM1A = 0x0UL, /*!< request by PWM1A */ + SIU_DMAMUX_SRCSEL14_Reserved = 0x1UL, /*!< no source */ +} SIU_DMAMUX_SRCSEL14_Enum; + +typedef enum { + SIU_DMAMUX_SRCSEL15_PWM2A = 0x0UL, /*!< request by PWM2A */ + SIU_DMAMUX_SRCSEL15_Reserved = 0x1UL, /*!< no source */ +} SIU_DMAMUX_SRCSEL15_Enum; + +/*-- CHIPID: Chip identifier ---------------------------------------------------------------------------------*/ +typedef struct { + uint32_t REV :4; /*!< Revision number */ + uint32_t ID :28; /*!< Model ID */ +} _SIU_CHIPID_bits; + +/* Bit field positions: */ +#define SIU_CHIPID_REV_Pos 0 /*!< Revision number */ +#define SIU_CHIPID_ID_Pos 4 /*!< Model ID */ + +/* Bit field masks: */ +#define SIU_CHIPID_REV_Msk 0x0000000FUL /*!< Revision number */ +#define SIU_CHIPID_ID_Msk 0xFFFFFFF0UL /*!< Model ID */ + +typedef struct { + __IO uint32_t Reserved0[4]; + union { /*!< PWM syncronization control register */ + __IO uint32_t PWMSYNC; /*!< PWMSYNC : type used for word access */ + __IO _SIU_PWMSYNC_bits PWMSYNC_bit; /*!< PWMSYNC_bit: structure used for bit access */ + }; + union { /*!< Service mode control register */ + __IO uint32_t SERVCTL; /*!< SERVCTL : type used for word access */ + __IO _SIU_SERVCTL_bits SERVCTL_bit; /*!< SERVCTL_bit: structure used for bit access */ + }; + union { /*!< Clock out control register */ + __IO uint32_t CLKOUTCTL; /*!< CLKOUTCTL : type used for word access */ + __IO _SIU_CLKOUTCTL_bits CLKOUTCTL_bit; /*!< CLKOUTCTL_bit: structure used for bit access */ + }; + union { /*!< QEP altfunc control */ + __IO uint32_t REMAPAF; /*!< REMAPAF : type used for word access */ + __IO _SIU_REMAPAF_bits REMAPAF_bit; /*!< REMAPAF_bit: structure used for bit access */ + }; + union { /*!< DMA external requests mux control register */ + __IO uint32_t DMAMUX; /*!< DMAMUX : type used for word access */ + __IO _SIU_DMAMUX_bits DMAMUX_bit; /*!< DMAMUX_bit: structure used for bit access */ + }; + __IO uint32_t Reserved1[1014]; + union { /*!< Chip identifier */ + __I uint32_t CHIPID; /*!< CHIPID : type used for word access */ + __I _SIU_CHIPID_bits CHIPID_bit; /*!< CHIPID_bit: structure used for bit access */ + }; +} SIU_TypeDef; + + +/******************************************************************************/ +/* RCU registers */ +/******************************************************************************/ + +/*-- OSICFG: Internal oscillator configuration register ------------------------------------------------------*/ +typedef struct { + uint32_t EN :1; /*!< Oscillator 8MHz enable */ + uint32_t :15; /*!< RESERVED */ + uint32_t CAL :10; /*!< Oscillator 8MHz calibration value */ +} _RCU_OSICFG_bits; + +/* Bit field positions: */ +#define RCU_OSICFG_EN_Pos 0 /*!< Oscillator 8MHz enable */ +#define RCU_OSICFG_CAL_Pos 16 /*!< Oscillator 8MHz calibration value */ + +/* Bit field masks: */ +#define RCU_OSICFG_EN_Msk 0x00000001UL /*!< Oscillator 8MHz enable */ +#define RCU_OSICFG_CAL_Msk 0x03FF0000UL /*!< Oscillator 8MHz calibration value */ + +/*-- OSECFG: External oscillator configuration register ------------------------------------------------------*/ +typedef struct { + uint32_t XOEN :1; /*!< Enable output XO_OSC from external oscillator */ + uint32_t EN :1; /*!< Enable external oscallator */ +} _RCU_OSECFG_bits; + +/* Bit field positions: */ +#define RCU_OSECFG_XOEN_Pos 0 /*!< Enable output XO_OSC from external oscillator */ +#define RCU_OSECFG_EN_Pos 1 /*!< Enable external oscallator */ + +/* Bit field masks: */ +#define RCU_OSECFG_XOEN_Msk 0x00000001UL /*!< Enable output XO_OSC from external oscillator */ +#define RCU_OSECFG_EN_Msk 0x00000002UL /*!< Enable external oscallator */ + +/*-- PLLCFG: PLL configuration register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t M :6; /*!< PLL M Coefficient */ + uint32_t :2; /*!< RESERVED */ + uint32_t N :6; /*!< PLL N Coefficient */ + uint32_t :2; /*!< RESERVED */ + uint32_t OD :2; /*!< PLL OD Coefficient */ + uint32_t :2; /*!< RESERVED */ + uint32_t REFSRC :1; /*!< PLL Reference source select bit */ + uint32_t :3; /*!< RESERVED */ + uint32_t BYPASS :1; /*!< PLL Bypass enable */ + uint32_t :1; /*!< RESERVED */ + uint32_t OUTEN :1; /*!< Enable PLL out */ + uint32_t :1; /*!< RESERVED */ + uint32_t LOCK :1; /*!< PLL status lock */ +} _RCU_PLLCFG_bits; + +/* Bit field positions: */ +#define RCU_PLLCFG_M_Pos 0 /*!< PLL M Coefficient */ +#define RCU_PLLCFG_N_Pos 8 /*!< PLL N Coefficient */ +#define RCU_PLLCFG_OD_Pos 16 /*!< PLL OD Coefficient */ +#define RCU_PLLCFG_REFSRC_Pos 20 /*!< PLL Reference source select bit */ +#define RCU_PLLCFG_BYPASS_Pos 24 /*!< PLL Bypass enable */ +#define RCU_PLLCFG_OUTEN_Pos 26 /*!< Enable PLL out */ +#define RCU_PLLCFG_LOCK_Pos 28 /*!< PLL status lock */ + +/* Bit field masks: */ +#define RCU_PLLCFG_M_Msk 0x0000003FUL /*!< PLL M Coefficient */ +#define RCU_PLLCFG_N_Msk 0x00003F00UL /*!< PLL N Coefficient */ +#define RCU_PLLCFG_OD_Msk 0x00030000UL /*!< PLL OD Coefficient */ +#define RCU_PLLCFG_REFSRC_Msk 0x00100000UL /*!< PLL Reference source select bit */ +#define RCU_PLLCFG_BYPASS_Msk 0x01000000UL /*!< PLL Bypass enable */ +#define RCU_PLLCFG_OUTEN_Msk 0x04000000UL /*!< Enable PLL out */ +#define RCU_PLLCFG_LOCK_Msk 0x10000000UL /*!< PLL status lock */ + +/* Bit field enums: */ +typedef enum { + RCU_PLLCFG_OD_Disable = 0x0UL, /*!< disabled */ + RCU_PLLCFG_OD_Div2 = 0x1UL, /*!< divide by 2 */ + RCU_PLLCFG_OD_Div4 = 0x2UL, /*!< divide by 4 */ + RCU_PLLCFG_OD_Div8 = 0x3UL, /*!< divide by 8 */ +} RCU_PLLCFG_OD_Enum; + +typedef enum { + RCU_PLLCFG_REFSRC_OSECLK = 0x0UL, /*!< external oscillator */ + RCU_PLLCFG_REFSRC_OSICLK = 0x1UL, /*!< internal oscillator */ +} RCU_PLLCFG_REFSRC_Enum; + +/*-- PLLDIV: PLL divider register ----------------------------------------------------------------------------*/ +typedef struct { + uint32_t DIVEN :1; /*!< PLL Divider enable bit */ + uint32_t :7; /*!< RESERVED */ + uint32_t DIV :6; /*!< PLL divider coefficent */ +} _RCU_PLLDIV_bits; + +/* Bit field positions: */ +#define RCU_PLLDIV_DIVEN_Pos 0 /*!< PLL Divider enable bit */ +#define RCU_PLLDIV_DIV_Pos 8 /*!< PLL divider coefficent */ + +/* Bit field masks: */ +#define RCU_PLLDIV_DIVEN_Msk 0x00000001UL /*!< PLL Divider enable bit */ +#define RCU_PLLDIV_DIV_Msk 0x00003F00UL /*!< PLL divider coefficent */ + +/*-- SYSCLKCFG: System clock configuration register ----------------------------------------------------------*/ +typedef struct { + uint32_t SYSSEL :2; /*!< System clock source selection */ + uint32_t :14; /*!< RESERVED */ + uint32_t SECEN :1; /*!< Enable clock security system */ +} _RCU_SYSCLKCFG_bits; + +/* Bit field positions: */ +#define RCU_SYSCLKCFG_SYSSEL_Pos 0 /*!< System clock source selection */ +#define RCU_SYSCLKCFG_SECEN_Pos 16 /*!< Enable clock security system */ + +/* Bit field masks: */ +#define RCU_SYSCLKCFG_SYSSEL_Msk 0x00000003UL /*!< System clock source selection */ +#define RCU_SYSCLKCFG_SECEN_Msk 0x00010000UL /*!< Enable clock security system */ + +/* Bit field enums: */ +typedef enum { + RCU_SYSCLKCFG_SYSSEL_OSICLK = 0x0UL, /*!< internal oscillator */ + RCU_SYSCLKCFG_SYSSEL_OSECLK = 0x1UL, /*!< external oscillator */ + RCU_SYSCLKCFG_SYSSEL_PLLCLK = 0x2UL, /*!< PLL output clock */ + RCU_SYSCLKCFG_SYSSEL_PLLDIVCLK = 0x3UL, /*!< PLL divided clock */ +} RCU_SYSCLKCFG_SYSSEL_Enum; + +/*-- SYSCLKSTAT: System clock status register ----------------------------------------------------------------*/ +typedef struct { + uint32_t SYSSTAT :2; /*!< Current system source clock */ + uint32_t :2; /*!< RESERVED */ + uint32_t BUSY :1; /*!< Clock manager is busy, for example, when change clock source */ + uint32_t :3; /*!< RESERVED */ + uint32_t SYSFAIL :1; /*!< Error in current clock was detected */ + uint32_t :8; /*!< RESERVED */ + uint32_t OSECLKFAIL :1; /*!< External oscillator clock fail */ + uint32_t PLLCLKFAIL :1; /*!< PLL source clock fail */ + uint32_t PLLDIVCLKFAIL :1; /*!< PLL divided clock fail */ + uint32_t :5; /*!< RESERVED */ + uint32_t OSECLKGOOD :1; /*!< External oscillator clock good */ + uint32_t PLLCLKGOOD :1; /*!< PLL clock good */ + uint32_t PLLDIVCLKGOOD :1; /*!< PLL divided clock good */ +} _RCU_SYSCLKSTAT_bits; + +/* Bit field positions: */ +#define RCU_SYSCLKSTAT_SYSSTAT_Pos 0 /*!< Current system source clock */ +#define RCU_SYSCLKSTAT_BUSY_Pos 4 /*!< Clock manager is busy, for example, when change clock source */ +#define RCU_SYSCLKSTAT_SYSFAIL_Pos 8 /*!< Error in current clock was detected */ +#define RCU_SYSCLKSTAT_OSECLKFAIL_Pos 17 /*!< External oscillator clock fail */ +#define RCU_SYSCLKSTAT_PLLCLKFAIL_Pos 18 /*!< PLL source clock fail */ +#define RCU_SYSCLKSTAT_PLLDIVCLKFAIL_Pos 19 /*!< PLL divided clock fail */ +#define RCU_SYSCLKSTAT_OSECLKGOOD_Pos 25 /*!< External oscillator clock good */ +#define RCU_SYSCLKSTAT_PLLCLKGOOD_Pos 26 /*!< PLL clock good */ +#define RCU_SYSCLKSTAT_PLLDIVCLKGOOD_Pos 27 /*!< PLL divided clock good */ + +/* Bit field masks: */ +#define RCU_SYSCLKSTAT_SYSSTAT_Msk 0x00000003UL /*!< Current system source clock */ +#define RCU_SYSCLKSTAT_BUSY_Msk 0x00000010UL /*!< Clock manager is busy, for example, when change clock source */ +#define RCU_SYSCLKSTAT_SYSFAIL_Msk 0x00000100UL /*!< Error in current clock was detected */ +#define RCU_SYSCLKSTAT_OSECLKFAIL_Msk 0x00020000UL /*!< External oscillator clock fail */ +#define RCU_SYSCLKSTAT_PLLCLKFAIL_Msk 0x00040000UL /*!< PLL source clock fail */ +#define RCU_SYSCLKSTAT_PLLDIVCLKFAIL_Msk 0x00080000UL /*!< PLL divided clock fail */ +#define RCU_SYSCLKSTAT_OSECLKGOOD_Msk 0x02000000UL /*!< External oscillator clock good */ +#define RCU_SYSCLKSTAT_PLLCLKGOOD_Msk 0x04000000UL /*!< PLL clock good */ +#define RCU_SYSCLKSTAT_PLLDIVCLKGOOD_Msk 0x08000000UL /*!< PLL divided clock good */ + +/* Bit field enums: */ +typedef enum { + RCU_SYSCLKSTAT_SYSSTAT_OSICLK = 0x0UL, /*!< internal oscillator */ + RCU_SYSCLKSTAT_SYSSTAT_OSECLK = 0x1UL, /*!< external oscillator */ + RCU_SYSCLKSTAT_SYSSTAT_PLLCLK = 0x2UL, /*!< PLL output clock */ + RCU_SYSCLKSTAT_SYSSTAT_PLLDIVCLK = 0x3UL, /*!< PLL divided clock */ +} RCU_SYSCLKSTAT_SYSSTAT_Enum; + +/*-- SECPRD: Security sysytem clock period register ----------------------------------------------------------*/ +typedef struct { + uint32_t :8; /*!< RESERVED */ + uint32_t OSECLK :8; /*!< Max counter value for external oscillator clock fail detection */ + uint32_t PLLCLK :8; /*!< Max counter value for PLL clock fail detection */ + uint32_t PLLDIVCLK :8; /*!< Max counter value for PLL clock fail detection */ +} _RCU_SECPRD_bits; + +/* Bit field positions: */ +#define RCU_SECPRD_OSECLK_Pos 8 /*!< Max counter value for external oscillator clock fail detection */ +#define RCU_SECPRD_PLLCLK_Pos 16 /*!< Max counter value for PLL clock fail detection */ +#define RCU_SECPRD_PLLDIVCLK_Pos 24 /*!< Max counter value for PLL clock fail detection */ + +/* Bit field masks: */ +#define RCU_SECPRD_OSECLK_Msk 0x0000FF00UL /*!< Max counter value for external oscillator clock fail detection */ +#define RCU_SECPRD_PLLCLK_Msk 0x00FF0000UL /*!< Max counter value for PLL clock fail detection */ +#define RCU_SECPRD_PLLDIVCLK_Msk 0xFF000000UL /*!< Max counter value for PLL clock fail detection */ + +/*-- SYSRSTCFG: System reset configuration register ----------------------------------------------------------*/ +typedef struct { + uint32_t LOCKUPEN :1; /*!< Enable reset when processor in LOCKUP state */ +} _RCU_SYSRSTCFG_bits; + +/* Bit field positions: */ +#define RCU_SYSRSTCFG_LOCKUPEN_Pos 0 /*!< Enable reset when processor in LOCKUP state */ + +/* Bit field masks: */ +#define RCU_SYSRSTCFG_LOCKUPEN_Msk 0x00000001UL /*!< Enable reset when processor in LOCKUP state */ + +/*-- SYSRSTSTAT: Reset status register -----------------------------------------------------------------------*/ +typedef struct { + uint32_t POR :1; /*!< PowerOn Reset status */ + uint32_t WDOG :1; /*!< WatchDog Reset status */ + uint32_t SYSRST :1; /*!< System Reset Status */ + uint32_t LOCKUP :1; /*!< Lockup Reset Status */ +} _RCU_SYSRSTSTAT_bits; + +/* Bit field positions: */ +#define RCU_SYSRSTSTAT_POR_Pos 0 /*!< PowerOn Reset status */ +#define RCU_SYSRSTSTAT_WDOG_Pos 1 /*!< WatchDog Reset status */ +#define RCU_SYSRSTSTAT_SYSRST_Pos 2 /*!< System Reset Status */ +#define RCU_SYSRSTSTAT_LOCKUP_Pos 3 /*!< Lockup Reset Status */ + +/* Bit field masks: */ +#define RCU_SYSRSTSTAT_POR_Msk 0x00000001UL /*!< PowerOn Reset status */ +#define RCU_SYSRSTSTAT_WDOG_Msk 0x00000002UL /*!< WatchDog Reset status */ +#define RCU_SYSRSTSTAT_SYSRST_Msk 0x00000004UL /*!< System Reset Status */ +#define RCU_SYSRSTSTAT_LOCKUP_Msk 0x00000008UL /*!< Lockup Reset Status */ + +/*-- INTEN: Interrupt enable register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t :1; /*!< RESERVED */ + uint32_t OSECLKFAIL :1; /*!< Enable OSECLK fail interrupt */ + uint32_t PLLCLKFAIL :1; /*!< Enable PLLCLK fail interrupt */ + uint32_t PLLDIVCLKFAIL :1; /*!< Enable PLLDIVCLK fail interrupt */ + uint32_t :5; /*!< RESERVED */ + uint32_t OSECLKGOOD :1; /*!< Enable OSECLK good interrupt */ + uint32_t PLLCLKGOOD :1; /*!< Enable PLLCLK good interrupt */ + uint32_t PLLDIVCLKGOOD :1; /*!< Enable PLLDIVCLK good interrupt */ + uint32_t :4; /*!< RESERVED */ + uint32_t PLLLOCK :1; /*!< Enable int from pll lock signal */ +} _RCU_INTEN_bits; + +/* Bit field positions: */ +#define RCU_INTEN_OSECLKFAIL_Pos 1 /*!< Enable OSECLK fail interrupt */ +#define RCU_INTEN_PLLCLKFAIL_Pos 2 /*!< Enable PLLCLK fail interrupt */ +#define RCU_INTEN_PLLDIVCLKFAIL_Pos 3 /*!< Enable PLLDIVCLK fail interrupt */ +#define RCU_INTEN_OSECLKGOOD_Pos 9 /*!< Enable OSECLK good interrupt */ +#define RCU_INTEN_PLLCLKGOOD_Pos 10 /*!< Enable PLLCLK good interrupt */ +#define RCU_INTEN_PLLDIVCLKGOOD_Pos 11 /*!< Enable PLLDIVCLK good interrupt */ +#define RCU_INTEN_PLLLOCK_Pos 16 /*!< Enable int from pll lock signal */ + +/* Bit field masks: */ +#define RCU_INTEN_OSECLKFAIL_Msk 0x00000002UL /*!< Enable OSECLK fail interrupt */ +#define RCU_INTEN_PLLCLKFAIL_Msk 0x00000004UL /*!< Enable PLLCLK fail interrupt */ +#define RCU_INTEN_PLLDIVCLKFAIL_Msk 0x00000008UL /*!< Enable PLLDIVCLK fail interrupt */ +#define RCU_INTEN_OSECLKGOOD_Msk 0x00000200UL /*!< Enable OSECLK good interrupt */ +#define RCU_INTEN_PLLCLKGOOD_Msk 0x00000400UL /*!< Enable PLLCLK good interrupt */ +#define RCU_INTEN_PLLDIVCLKGOOD_Msk 0x00000800UL /*!< Enable PLLDIVCLK good interrupt */ +#define RCU_INTEN_PLLLOCK_Msk 0x00010000UL /*!< Enable int from pll lock signal */ + +/*-- INTSTAT: Interrupt status register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t :1; /*!< RESERVED */ + uint32_t OSECLKFAIL :1; /*!< Status external oscillator clock fail signal */ + uint32_t PLLCLKFAIL :1; /*!< Status PLL clock fail signal */ + uint32_t PLLDIVCLKFAIL :1; /*!< Status PLLDIV clock fail signal */ + uint32_t :5; /*!< RESERVED */ + uint32_t OSECLKGOOD :1; /*!< Status external oscillator clock good signal */ + uint32_t PLLCLKGOOD :1; /*!< Status PLL clock good signal */ + uint32_t PLLDIVCLKGOOD :1; /*!< Status PLLDIV clock good signal */ + uint32_t :4; /*!< RESERVED */ + uint32_t PLLLOCK :1; /*!< Status pll lock signal */ + uint32_t :3; /*!< RESERVED */ + uint32_t SYSFAIL :1; /*!< Current clock failed status */ +} _RCU_INTSTAT_bits; + +/* Bit field positions: */ +#define RCU_INTSTAT_OSECLKFAIL_Pos 1 /*!< Status external oscillator clock fail signal */ +#define RCU_INTSTAT_PLLCLKFAIL_Pos 2 /*!< Status PLL clock fail signal */ +#define RCU_INTSTAT_PLLDIVCLKFAIL_Pos 3 /*!< Status PLLDIV clock fail signal */ +#define RCU_INTSTAT_OSECLKGOOD_Pos 9 /*!< Status external oscillator clock good signal */ +#define RCU_INTSTAT_PLLCLKGOOD_Pos 10 /*!< Status PLL clock good signal */ +#define RCU_INTSTAT_PLLDIVCLKGOOD_Pos 11 /*!< Status PLLDIV clock good signal */ +#define RCU_INTSTAT_PLLLOCK_Pos 16 /*!< Status pll lock signal */ +#define RCU_INTSTAT_SYSFAIL_Pos 20 /*!< Current clock failed status */ + +/* Bit field masks: */ +#define RCU_INTSTAT_OSECLKFAIL_Msk 0x00000002UL /*!< Status external oscillator clock fail signal */ +#define RCU_INTSTAT_PLLCLKFAIL_Msk 0x00000004UL /*!< Status PLL clock fail signal */ +#define RCU_INTSTAT_PLLDIVCLKFAIL_Msk 0x00000008UL /*!< Status PLLDIV clock fail signal */ +#define RCU_INTSTAT_OSECLKGOOD_Msk 0x00000200UL /*!< Status external oscillator clock good signal */ +#define RCU_INTSTAT_PLLCLKGOOD_Msk 0x00000400UL /*!< Status PLL clock good signal */ +#define RCU_INTSTAT_PLLDIVCLKGOOD_Msk 0x00000800UL /*!< Status PLLDIV clock good signal */ +#define RCU_INTSTAT_PLLLOCK_Msk 0x00010000UL /*!< Status pll lock signal */ +#define RCU_INTSTAT_SYSFAIL_Msk 0x00100000UL /*!< Current clock failed status */ + +/*-- TRACECFG: Trace clock configuration register ------------------------------------------------------------*/ +typedef struct { + uint32_t CLKEN :1; /*!< Clock enable */ + uint32_t :7; /*!< RESERVED */ + uint32_t CLKSEL :2; /*!< Clock source select */ + uint32_t :6; /*!< RESERVED */ + uint32_t DIVEN :1; /*!< Enable divider */ + uint32_t :7; /*!< RESERVED */ + uint32_t DIVN :6; /*!< Divider coefficient */ +} _RCU_TRACECFG_bits; + +/* Bit field positions: */ +#define RCU_TRACECFG_CLKEN_Pos 0 /*!< Clock enable */ +#define RCU_TRACECFG_CLKSEL_Pos 8 /*!< Clock source select */ +#define RCU_TRACECFG_DIVEN_Pos 16 /*!< Enable divider */ +#define RCU_TRACECFG_DIVN_Pos 24 /*!< Divider coefficient */ + +/* Bit field masks: */ +#define RCU_TRACECFG_CLKEN_Msk 0x00000001UL /*!< Clock enable */ +#define RCU_TRACECFG_CLKSEL_Msk 0x00000300UL /*!< Clock source select */ +#define RCU_TRACECFG_DIVEN_Msk 0x00010000UL /*!< Enable divider */ +#define RCU_TRACECFG_DIVN_Msk 0x3F000000UL /*!< Divider coefficient */ + +/* Bit field enums: */ +typedef enum { + RCU_TRACECFG_CLKSEL_OSICLK = 0x0UL, /*!< internal oscillator */ + RCU_TRACECFG_CLKSEL_OSECLK = 0x1UL, /*!< external oscillator */ + RCU_TRACECFG_CLKSEL_PLLCLK = 0x2UL, /*!< PLL output clock */ + RCU_TRACECFG_CLKSEL_PLLDIVCLK = 0x3UL, /*!< PLL divided clock */ +} RCU_TRACECFG_CLKSEL_Enum; + +/*-- CLKOUTCFG: Clockout configuration register --------------------------------------------------------------*/ +typedef struct { + uint32_t CLKEN :1; /*!< Clock enable */ + uint32_t :7; /*!< RESERVED */ + uint32_t CLKSEL :2; /*!< Clock source select */ + uint32_t :6; /*!< RESERVED */ + uint32_t DIVEN :1; /*!< Enable divider */ + uint32_t :7; /*!< RESERVED */ + uint32_t DIVN :3; /*!< Divider coefficient */ +} _RCU_CLKOUTCFG_bits; + +/* Bit field positions: */ +#define RCU_CLKOUTCFG_CLKEN_Pos 0 /*!< Clock enable */ +#define RCU_CLKOUTCFG_CLKSEL_Pos 8 /*!< Clock source select */ +#define RCU_CLKOUTCFG_DIVEN_Pos 16 /*!< Enable divider */ +#define RCU_CLKOUTCFG_DIVN_Pos 24 /*!< Divider coefficient */ + +/* Bit field masks: */ +#define RCU_CLKOUTCFG_CLKEN_Msk 0x00000001UL /*!< Clock enable */ +#define RCU_CLKOUTCFG_CLKSEL_Msk 0x00000300UL /*!< Clock source select */ +#define RCU_CLKOUTCFG_DIVEN_Msk 0x00010000UL /*!< Enable divider */ +#define RCU_CLKOUTCFG_DIVN_Msk 0x07000000UL /*!< Divider coefficient */ + +/* Bit field enums: */ +typedef enum { + RCU_CLKOUTCFG_CLKSEL_OSICLK = 0x0UL, /*!< internal oscillator */ + RCU_CLKOUTCFG_CLKSEL_OSECLK = 0x1UL, /*!< external oscillator */ + RCU_CLKOUTCFG_CLKSEL_PLLCLK = 0x2UL, /*!< PLL output clock */ + RCU_CLKOUTCFG_CLKSEL_PLLDIVCLK = 0x3UL, /*!< PLL divided clock */ +} RCU_CLKOUTCFG_CLKSEL_Enum; + +/*-- WDTCFG: WatchDog configuration register -----------------------------------------------------------------*/ +typedef struct { + uint32_t CLKEN :1; /*!< Clock enable */ + uint32_t :3; /*!< RESERVED */ + uint32_t RSTDIS :1; /*!< Reset disable */ + uint32_t :3; /*!< RESERVED */ + uint32_t CLKSEL :2; /*!< Clock source select */ + uint32_t :6; /*!< RESERVED */ + uint32_t DIVEN :1; /*!< Enable divider */ + uint32_t :7; /*!< RESERVED */ + uint32_t DIVN :6; /*!< Divider coefficient */ +} _RCU_WDTCFG_bits; + +/* Bit field positions: */ +#define RCU_WDTCFG_CLKEN_Pos 0 /*!< Clock enable */ +#define RCU_WDTCFG_RSTDIS_Pos 4 /*!< Reset disable */ +#define RCU_WDTCFG_CLKSEL_Pos 8 /*!< Clock source select */ +#define RCU_WDTCFG_DIVEN_Pos 16 /*!< Enable divider */ +#define RCU_WDTCFG_DIVN_Pos 24 /*!< Divider coefficient */ + +/* Bit field masks: */ +#define RCU_WDTCFG_CLKEN_Msk 0x00000001UL /*!< Clock enable */ +#define RCU_WDTCFG_RSTDIS_Msk 0x00000010UL /*!< Reset disable */ +#define RCU_WDTCFG_CLKSEL_Msk 0x00000300UL /*!< Clock source select */ +#define RCU_WDTCFG_DIVEN_Msk 0x00010000UL /*!< Enable divider */ +#define RCU_WDTCFG_DIVN_Msk 0x3F000000UL /*!< Divider coefficient */ + +/* Bit field enums: */ +typedef enum { + RCU_WDTCFG_CLKSEL_OSICLK = 0x0UL, /*!< internal oscillator */ + RCU_WDTCFG_CLKSEL_OSECLK = 0x1UL, /*!< external oscillator */ + RCU_WDTCFG_CLKSEL_PLLCLK = 0x2UL, /*!< PLL output clock */ + RCU_WDTCFG_CLKSEL_PLLDIVCLK = 0x3UL, /*!< PLL divided clock */ +} RCU_WDTCFG_CLKSEL_Enum; + +/*-- UARTCFG: UARTCFG: UART clock and reset configuration register --------------------------------------------*/ +typedef struct { + uint32_t CLKEN :1; /*!< Clock enable */ + uint32_t :3; /*!< RESERVED */ + uint32_t RSTDIS :1; /*!< Reset disable */ + uint32_t :3; /*!< RESERVED */ + uint32_t CLKSEL :2; /*!< Clock source select */ + uint32_t :6; /*!< RESERVED */ + uint32_t DIVEN :1; /*!< Enable divider */ + uint32_t :7; /*!< RESERVED */ + uint32_t DIVN :6; /*!< Divider coefficient */ +} _RCU_UARTCFG_UARTCFG_bits; + +/* Bit field positions: */ +#define RCU_UARTCFG_UARTCFG_CLKEN_Pos 0 /*!< Clock enable */ +#define RCU_UARTCFG_UARTCFG_RSTDIS_Pos 4 /*!< Reset disable */ +#define RCU_UARTCFG_UARTCFG_CLKSEL_Pos 8 /*!< Clock source select */ +#define RCU_UARTCFG_UARTCFG_DIVEN_Pos 16 /*!< Enable divider */ +#define RCU_UARTCFG_UARTCFG_DIVN_Pos 24 /*!< Divider coefficient */ + +/* Bit field masks: */ +#define RCU_UARTCFG_UARTCFG_CLKEN_Msk 0x00000001UL /*!< Clock enable */ +#define RCU_UARTCFG_UARTCFG_RSTDIS_Msk 0x00000010UL /*!< Reset disable */ +#define RCU_UARTCFG_UARTCFG_CLKSEL_Msk 0x00000300UL /*!< Clock source select */ +#define RCU_UARTCFG_UARTCFG_DIVEN_Msk 0x00010000UL /*!< Enable divider */ +#define RCU_UARTCFG_UARTCFG_DIVN_Msk 0x3F000000UL /*!< Divider coefficient */ + +/* Bit field enums: */ +typedef enum { + RCU_UARTCFG_UARTCFG_CLKSEL_OSECLK = 0x0UL, /*!< external oscillator */ + RCU_UARTCFG_UARTCFG_CLKSEL_PLLCLK = 0x1UL, /*!< PLL output clock */ + RCU_UARTCFG_UARTCFG_CLKSEL_PLLDIVCLK = 0x2UL, /*!< PLL divided clock */ + RCU_UARTCFG_UARTCFG_CLKSEL_OSICLK = 0x3UL, /*!< internal oscillator */ +} RCU_UARTCFG_UARTCFG_CLKSEL_Enum; + +/*-- SPICFG: SPI clock and reset configuration register ------------------------------------------------------*/ +typedef struct { + uint32_t CLKEN :1; /*!< Clock enable */ + uint32_t :3; /*!< RESERVED */ + uint32_t RSTDIS :1; /*!< Reset disable */ + uint32_t :3; /*!< RESERVED */ + uint32_t CLKSEL :2; /*!< Clock source select */ + uint32_t :6; /*!< RESERVED */ + uint32_t DIVEN :1; /*!< Enable divider */ + uint32_t :7; /*!< RESERVED */ + uint32_t DIVN :6; /*!< Divider coefficient */ +} _RCU_SPICFG_bits; + +/* Bit field positions: */ +#define RCU_SPICFG_CLKEN_Pos 0 /*!< Clock enable */ +#define RCU_SPICFG_RSTDIS_Pos 4 /*!< Reset disable */ +#define RCU_SPICFG_CLKSEL_Pos 8 /*!< Clock source select */ +#define RCU_SPICFG_DIVEN_Pos 16 /*!< Enable divider */ +#define RCU_SPICFG_DIVN_Pos 24 /*!< Divider coefficient */ + +/* Bit field masks: */ +#define RCU_SPICFG_CLKEN_Msk 0x00000001UL /*!< Clock enable */ +#define RCU_SPICFG_RSTDIS_Msk 0x00000010UL /*!< Reset disable */ +#define RCU_SPICFG_CLKSEL_Msk 0x00000300UL /*!< Clock source select */ +#define RCU_SPICFG_DIVEN_Msk 0x00010000UL /*!< Enable divider */ +#define RCU_SPICFG_DIVN_Msk 0x3F000000UL /*!< Divider coefficient */ + +/* Bit field enums: */ +typedef enum { + RCU_SPICFG_CLKSEL_OSECLK = 0x0UL, /*!< external oscillator */ + RCU_SPICFG_CLKSEL_PLLCLK = 0x1UL, /*!< PLL output clock */ + RCU_SPICFG_CLKSEL_PLLDIVCLK = 0x2UL, /*!< PLL divided clock */ + RCU_SPICFG_CLKSEL_OSICLK = 0x3UL, /*!< internal oscillator */ +} RCU_SPICFG_CLKSEL_Enum; + +/*-- ADCCFG: ADC clock and reset configuration register ------------------------------------------------------*/ +typedef struct { + uint32_t CLKEN :1; /*!< Clock enable */ + uint32_t :3; /*!< RESERVED */ + uint32_t RSTDIS :1; /*!< Reset disable */ + uint32_t :3; /*!< RESERVED */ + uint32_t CLKSEL :2; /*!< Clock source select */ + uint32_t :6; /*!< RESERVED */ + uint32_t DIVEN :1; /*!< Enable divider */ + uint32_t :7; /*!< RESERVED */ + uint32_t DIVN :6; /*!< Divider coefficient */ +} _RCU_ADCCFG_bits; + +/* Bit field positions: */ +#define RCU_ADCCFG_CLKEN_Pos 0 /*!< Clock enable */ +#define RCU_ADCCFG_RSTDIS_Pos 4 /*!< Reset disable */ +#define RCU_ADCCFG_CLKSEL_Pos 8 /*!< Clock source select */ +#define RCU_ADCCFG_DIVEN_Pos 16 /*!< Enable divider */ +#define RCU_ADCCFG_DIVN_Pos 24 /*!< Divider coefficient */ + +/* Bit field masks: */ +#define RCU_ADCCFG_CLKEN_Msk 0x00000001UL /*!< Clock enable */ +#define RCU_ADCCFG_RSTDIS_Msk 0x00000010UL /*!< Reset disable */ +#define RCU_ADCCFG_CLKSEL_Msk 0x00000300UL /*!< Clock source select */ +#define RCU_ADCCFG_DIVEN_Msk 0x00010000UL /*!< Enable divider */ +#define RCU_ADCCFG_DIVN_Msk 0x3F000000UL /*!< Divider coefficient */ + +/* Bit field enums: */ +typedef enum { + RCU_ADCCFG_CLKSEL_OSECLK = 0x0UL, /*!< external oscillator */ + RCU_ADCCFG_CLKSEL_PLLCLK = 0x1UL, /*!< PLL output clock */ + RCU_ADCCFG_CLKSEL_PLLDIVCLK = 0x2UL, /*!< PLL divided clock */ + RCU_ADCCFG_CLKSEL_OSICLK = 0x3UL, /*!< internal oscillator */ +} RCU_ADCCFG_CLKSEL_Enum; + +/*-- PCLKCFG: APB clock configuration register ---------------------------------------------------------------*/ +typedef struct { + uint32_t TMR0EN :1; /*!< Enable clock for TMR0 */ + uint32_t TMR1EN :1; /*!< Enable clock for TMR1 */ + uint32_t TMR2EN :1; /*!< Enable clock for TMR2 */ + uint32_t TMR3EN :1; /*!< Enable clock for TMR3 */ + uint32_t PWM0EN :1; /*!< Enable clock for PWM0 */ + uint32_t PWM1EN :1; /*!< Enable clock for PWM1 */ + uint32_t PWM2EN :1; /*!< Enable clock for PWM2 */ + uint32_t I2CEN :1; /*!< Enable clock for I2C */ + uint32_t QEPEN :1; /*!< Enable clock for QEP */ + uint32_t ECAP0EN :1; /*!< Enable clock for ECAP0 */ + uint32_t ECAP1EN :1; /*!< Enable clock for ECAP1 */ + uint32_t ECAP2EN :1; /*!< Enable clock for ECAP2 */ +} _RCU_PCLKCFG_bits; + +/* Bit field positions: */ +#define RCU_PCLKCFG_TMR0EN_Pos 0 /*!< Enable clock for TMR0 */ +#define RCU_PCLKCFG_TMR1EN_Pos 1 /*!< Enable clock for TMR1 */ +#define RCU_PCLKCFG_TMR2EN_Pos 2 /*!< Enable clock for TMR2 */ +#define RCU_PCLKCFG_TMR3EN_Pos 3 /*!< Enable clock for TMR3 */ +#define RCU_PCLKCFG_PWM0EN_Pos 4 /*!< Enable clock for PWM0 */ +#define RCU_PCLKCFG_PWM1EN_Pos 5 /*!< Enable clock for PWM1 */ +#define RCU_PCLKCFG_PWM2EN_Pos 6 /*!< Enable clock for PWM2 */ +#define RCU_PCLKCFG_I2CEN_Pos 7 /*!< Enable clock for I2C */ +#define RCU_PCLKCFG_QEPEN_Pos 8 /*!< Enable clock for QEP */ +#define RCU_PCLKCFG_ECAP0EN_Pos 9 /*!< Enable clock for ECAP0 */ +#define RCU_PCLKCFG_ECAP1EN_Pos 10 /*!< Enable clock for ECAP1 */ +#define RCU_PCLKCFG_ECAP2EN_Pos 11 /*!< Enable clock for ECAP2 */ + +/* Bit field masks: */ +#define RCU_PCLKCFG_TMR0EN_Msk 0x00000001UL /*!< Enable clock for TMR0 */ +#define RCU_PCLKCFG_TMR1EN_Msk 0x00000002UL /*!< Enable clock for TMR1 */ +#define RCU_PCLKCFG_TMR2EN_Msk 0x00000004UL /*!< Enable clock for TMR2 */ +#define RCU_PCLKCFG_TMR3EN_Msk 0x00000008UL /*!< Enable clock for TMR3 */ +#define RCU_PCLKCFG_PWM0EN_Msk 0x00000010UL /*!< Enable clock for PWM0 */ +#define RCU_PCLKCFG_PWM1EN_Msk 0x00000020UL /*!< Enable clock for PWM1 */ +#define RCU_PCLKCFG_PWM2EN_Msk 0x00000040UL /*!< Enable clock for PWM2 */ +#define RCU_PCLKCFG_I2CEN_Msk 0x00000080UL /*!< Enable clock for I2C */ +#define RCU_PCLKCFG_QEPEN_Msk 0x00000100UL /*!< Enable clock for QEP */ +#define RCU_PCLKCFG_ECAP0EN_Msk 0x00000200UL /*!< Enable clock for ECAP0 */ +#define RCU_PCLKCFG_ECAP1EN_Msk 0x00000400UL /*!< Enable clock for ECAP1 */ +#define RCU_PCLKCFG_ECAP2EN_Msk 0x00000800UL /*!< Enable clock for ECAP2 */ + +/*-- PRSTCFG: APB reset configuration register ---------------------------------------------------------------*/ +typedef struct { + uint32_t TMR0EN :1; /*!< Disable reset from TMR0 */ + uint32_t TMR1EN :1; /*!< Disable reset from TMR1 */ + uint32_t TMR2EN :1; /*!< Disable reset from TMR2 */ + uint32_t TMR3EN :1; /*!< Disable reset from TMR3 */ + uint32_t PWM0EN :1; /*!< Disable reset from PWM0 */ + uint32_t PWM1EN :1; /*!< Disable reset from PWM1 */ + uint32_t PWM2EN :1; /*!< Disable reset from PWM2 */ + uint32_t I2CEN :1; /*!< Disable reset from I2C */ + uint32_t QEPEN :1; /*!< Disable reset from QEP */ + uint32_t ECAP0EN :1; /*!< Disable reset from ECAP0 */ + uint32_t ECAP1EN :1; /*!< Disable reset from ECAP1 */ + uint32_t ECAP2EN :1; /*!< Disable reset from ECAP2 */ +} _RCU_PRSTCFG_bits; + +/* Bit field positions: */ +#define RCU_PRSTCFG_TMR0EN_Pos 0 /*!< Disable reset from TMR0 */ +#define RCU_PRSTCFG_TMR1EN_Pos 1 /*!< Disable reset from TMR1 */ +#define RCU_PRSTCFG_TMR2EN_Pos 2 /*!< Disable reset from TMR2 */ +#define RCU_PRSTCFG_TMR3EN_Pos 3 /*!< Disable reset from TMR3 */ +#define RCU_PRSTCFG_PWM0EN_Pos 4 /*!< Disable reset from PWM0 */ +#define RCU_PRSTCFG_PWM1EN_Pos 5 /*!< Disable reset from PWM1 */ +#define RCU_PRSTCFG_PWM2EN_Pos 6 /*!< Disable reset from PWM2 */ +#define RCU_PRSTCFG_I2CEN_Pos 7 /*!< Disable reset from I2C */ +#define RCU_PRSTCFG_QEPEN_Pos 8 /*!< Disable reset from QEP */ +#define RCU_PRSTCFG_ECAP0EN_Pos 9 /*!< Disable reset from ECAP0 */ +#define RCU_PRSTCFG_ECAP1EN_Pos 10 /*!< Disable reset from ECAP1 */ +#define RCU_PRSTCFG_ECAP2EN_Pos 11 /*!< Disable reset from ECAP2 */ + +/* Bit field masks: */ +#define RCU_PRSTCFG_TMR0EN_Msk 0x00000001UL /*!< Disable reset from TMR0 */ +#define RCU_PRSTCFG_TMR1EN_Msk 0x00000002UL /*!< Disable reset from TMR1 */ +#define RCU_PRSTCFG_TMR2EN_Msk 0x00000004UL /*!< Disable reset from TMR2 */ +#define RCU_PRSTCFG_TMR3EN_Msk 0x00000008UL /*!< Disable reset from TMR3 */ +#define RCU_PRSTCFG_PWM0EN_Msk 0x00000010UL /*!< Disable reset from PWM0 */ +#define RCU_PRSTCFG_PWM1EN_Msk 0x00000020UL /*!< Disable reset from PWM1 */ +#define RCU_PRSTCFG_PWM2EN_Msk 0x00000040UL /*!< Disable reset from PWM2 */ +#define RCU_PRSTCFG_I2CEN_Msk 0x00000080UL /*!< Disable reset from I2C */ +#define RCU_PRSTCFG_QEPEN_Msk 0x00000100UL /*!< Disable reset from QEP */ +#define RCU_PRSTCFG_ECAP0EN_Msk 0x00000200UL /*!< Disable reset from ECAP0 */ +#define RCU_PRSTCFG_ECAP1EN_Msk 0x00000400UL /*!< Disable reset from ECAP1 */ +#define RCU_PRSTCFG_ECAP2EN_Msk 0x00000800UL /*!< Disable reset from ECAP2 */ + +/*-- HCLKCFG: AHB clock configuration register ---------------------------------------------------------------*/ +typedef struct { + uint32_t GPIOAEN :1; /*!< Enable clock for GPIOA port */ + uint32_t GPIOBEN :1; /*!< Enable clock for GPIOB port */ + uint32_t CANEN :1; /*!< Enable clock for CAN */ +} _RCU_HCLKCFG_bits; + +/* Bit field positions: */ +#define RCU_HCLKCFG_GPIOAEN_Pos 0 /*!< Enable clock for GPIOA port */ +#define RCU_HCLKCFG_GPIOBEN_Pos 1 /*!< Enable clock for GPIOB port */ +#define RCU_HCLKCFG_CANEN_Pos 2 /*!< Enable clock for CAN */ + +/* Bit field masks: */ +#define RCU_HCLKCFG_GPIOAEN_Msk 0x00000001UL /*!< Enable clock for GPIOA port */ +#define RCU_HCLKCFG_GPIOBEN_Msk 0x00000002UL /*!< Enable clock for GPIOB port */ +#define RCU_HCLKCFG_CANEN_Msk 0x00000004UL /*!< Enable clock for CAN */ + +/*-- HRSTCFG: AHB reset configuration register ---------------------------------------------------------------*/ +typedef struct { + uint32_t GPIOAEN :1; /*!< Disable reset from GPIOA port */ + uint32_t GPIOBEN :1; /*!< Disable reset from GPIOB port */ + uint32_t CANEN :1; /*!< Disable reset from CAN */ +} _RCU_HRSTCFG_bits; + +/* Bit field positions: */ +#define RCU_HRSTCFG_GPIOAEN_Pos 0 /*!< Disable reset from GPIOA port */ +#define RCU_HRSTCFG_GPIOBEN_Pos 1 /*!< Disable reset from GPIOB port */ +#define RCU_HRSTCFG_CANEN_Pos 2 /*!< Disable reset from CAN */ + +/* Bit field masks: */ +#define RCU_HRSTCFG_GPIOAEN_Msk 0x00000001UL /*!< Disable reset from GPIOA port */ +#define RCU_HRSTCFG_GPIOBEN_Msk 0x00000002UL /*!< Disable reset from GPIOB port */ +#define RCU_HRSTCFG_CANEN_Msk 0x00000004UL /*!< Disable reset from CAN */ + +//Cluster UARTCFG: +typedef struct { + union { + /*!< UART clock and reset configuration register */ + __IO uint32_t UARTCFG; /*!< UARTCFG : type used for word access */ + __IO _RCU_UARTCFG_UARTCFG_bits UARTCFG_bit; /*!< UARTCFG_bit: structure used for bit access */ + }; +} _RCU_UARTCFG_TypeDef; +typedef struct { + union { /*!< Internal oscillator configuration register */ + __IO uint32_t OSICFG; /*!< OSICFG : type used for word access */ + __IO _RCU_OSICFG_bits OSICFG_bit; /*!< OSICFG_bit: structure used for bit access */ + }; + union { /*!< External oscillator configuration register */ + __IO uint32_t OSECFG; /*!< OSECFG : type used for word access */ + __IO _RCU_OSECFG_bits OSECFG_bit; /*!< OSECFG_bit: structure used for bit access */ + }; + union { /*!< PLL configuration register */ + __IO uint32_t PLLCFG; /*!< PLLCFG : type used for word access */ + __IO _RCU_PLLCFG_bits PLLCFG_bit; /*!< PLLCFG_bit: structure used for bit access */ + }; + union { /*!< PLL divider register */ + __IO uint32_t PLLDIV; /*!< PLLDIV : type used for word access */ + __IO _RCU_PLLDIV_bits PLLDIV_bit; /*!< PLLDIV_bit: structure used for bit access */ + }; + union { /*!< System clock configuration register */ + __IO uint32_t SYSCLKCFG; /*!< SYSCLKCFG : type used for word access */ + __IO _RCU_SYSCLKCFG_bits SYSCLKCFG_bit; /*!< SYSCLKCFG_bit: structure used for bit access */ + }; + union { /*!< System clock status register */ + __I uint32_t SYSCLKSTAT; /*!< SYSCLKSTAT : type used for word access */ + __I _RCU_SYSCLKSTAT_bits SYSCLKSTAT_bit; /*!< SYSCLKSTAT_bit: structure used for bit access */ + }; + union { /*!< Security sysytem clock period register */ + __IO uint32_t SECPRD; /*!< SECPRD : type used for word access */ + __IO _RCU_SECPRD_bits SECPRD_bit; /*!< SECPRD_bit: structure used for bit access */ + }; + union { /*!< System reset configuration register */ + __IO uint32_t SYSRSTCFG; /*!< SYSRSTCFG : type used for word access */ + __IO _RCU_SYSRSTCFG_bits SYSRSTCFG_bit; /*!< SYSRSTCFG_bit: structure used for bit access */ + }; + union { /*!< Reset status register */ + __IO uint32_t SYSRSTSTAT; /*!< SYSRSTSTAT : type used for word access */ + __IO _RCU_SYSRSTSTAT_bits SYSRSTSTAT_bit; /*!< SYSRSTSTAT_bit: structure used for bit access */ + }; + union { /*!< Interrupt enable register */ + __IO uint32_t INTEN; /*!< INTEN : type used for word access */ + __IO _RCU_INTEN_bits INTEN_bit; /*!< INTEN_bit: structure used for bit access */ + }; + union { /*!< Interrupt status register */ + __IO uint32_t INTSTAT; /*!< INTSTAT : type used for word access */ + __IO _RCU_INTSTAT_bits INTSTAT_bit; /*!< INTSTAT_bit: structure used for bit access */ + }; + union { /*!< Trace clock configuration register */ + __IO uint32_t TRACECFG; /*!< TRACECFG : type used for word access */ + __IO _RCU_TRACECFG_bits TRACECFG_bit; /*!< TRACECFG_bit: structure used for bit access */ + }; + union { /*!< Clockout configuration register */ + __IO uint32_t CLKOUTCFG; /*!< CLKOUTCFG : type used for word access */ + __IO _RCU_CLKOUTCFG_bits CLKOUTCFG_bit; /*!< CLKOUTCFG_bit: structure used for bit access */ + }; + union { /*!< WatchDog configuration register */ + __IO uint32_t WDTCFG; /*!< WDTCFG : type used for word access */ + __IO _RCU_WDTCFG_bits WDTCFG_bit; /*!< WDTCFG_bit: structure used for bit access */ + }; + __IO uint32_t Reserved0[10]; + _RCU_UARTCFG_TypeDef UARTCFG[2]; + __IO uint32_t Reserved1[6]; + union { /*!< SPI clock and reset configuration register */ + __IO uint32_t SPICFG; /*!< SPICFG : type used for word access */ + __IO _RCU_SPICFG_bits SPICFG_bit; /*!< SPICFG_bit: structure used for bit access */ + }; + __IO uint32_t Reserved2[7]; + union { /*!< ADC clock and reset configuration register */ + __IO uint32_t ADCCFG; /*!< ADCCFG : type used for word access */ + __IO _RCU_ADCCFG_bits ADCCFG_bit; /*!< ADCCFG_bit: structure used for bit access */ + }; + __IO uint32_t Reserved3[15]; + union { /*!< APB clock configuration register */ + __IO uint32_t PCLKCFG; /*!< PCLKCFG : type used for word access */ + __IO _RCU_PCLKCFG_bits PCLKCFG_bit; /*!< PCLKCFG_bit: structure used for bit access */ + }; + __IO uint32_t Reserved4[3]; + union { /*!< APB reset configuration register */ + __IO uint32_t PRSTCFG; /*!< PRSTCFG : type used for word access */ + __IO _RCU_PRSTCFG_bits PRSTCFG_bit; /*!< PRSTCFG_bit: structure used for bit access */ + }; + __IO uint32_t Reserved5[3]; + union { /*!< AHB clock configuration register */ + __IO uint32_t HCLKCFG; /*!< HCLKCFG : type used for word access */ + __IO _RCU_HCLKCFG_bits HCLKCFG_bit; /*!< HCLKCFG_bit: structure used for bit access */ + }; + union { /*!< AHB reset configuration register */ + __IO uint32_t HRSTCFG; /*!< HRSTCFG : type used for word access */ + __IO _RCU_HRSTCFG_bits HRSTCFG_bit; /*!< HRSTCFG_bit: structure used for bit access */ + }; +} RCU_TypeDef; + + +/******************************************************************************/ +/* PMU registers */ +/******************************************************************************/ + +/*-- CFG: PMU Configuration Register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t EN :1; /*!< Enable PMU */ +} _PMU_CFG_bits; + +/* Bit field positions: */ +#define PMU_CFG_EN_Pos 0 /*!< Enable PMU */ + +/* Bit field masks: */ +#define PMU_CFG_EN_Msk 0x00000001UL /*!< Enable PMU */ + +/*-- PUDEL: PMU Powerup Delay Value --------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :16; /*!< Delay value for powerup peripheral blocks (in OSICLK ticks) */ +} _PMU_PUDEL_bits; + +/* Bit field positions: */ +#define PMU_PUDEL_VAL_Pos 0 /*!< Delay value for powerup peripheral blocks (in OSICLK ticks) */ + +/* Bit field masks: */ +#define PMU_PUDEL_VAL_Msk 0x0000FFFFUL /*!< Delay value for powerup peripheral blocks (in OSICLK ticks) */ + +/*-- PDEN: PMU Enable Powerdown for peripheral ---------------------------------------------------------------*/ +typedef struct { + uint32_t PLLPD :1; /*!< Enable powerdown for PLL */ + uint32_t MFLASHPD :1; /*!< Enable powerdown for MFLASH */ + uint32_t OSEPD :1; /*!< Enable powerdown for external oscillator */ +} _PMU_PDEN_bits; + +/* Bit field positions: */ +#define PMU_PDEN_PLLPD_Pos 0 /*!< Enable powerdown for PLL */ +#define PMU_PDEN_MFLASHPD_Pos 1 /*!< Enable powerdown for MFLASH */ +#define PMU_PDEN_OSEPD_Pos 2 /*!< Enable powerdown for external oscillator */ + +/* Bit field masks: */ +#define PMU_PDEN_PLLPD_Msk 0x00000001UL /*!< Enable powerdown for PLL */ +#define PMU_PDEN_MFLASHPD_Msk 0x00000002UL /*!< Enable powerdown for MFLASH */ +#define PMU_PDEN_OSEPD_Msk 0x00000004UL /*!< Enable powerdown for external oscillator */ + +/*-- RXEVEN: PMU RX Event generation enable register ---------------------------------------------------------*/ +typedef struct { + uint32_t GPIOAEV :1; /*!< Enable RX event from GPIOA pins */ + uint32_t GPIOBEV :1; /*!< Enable RX event from GPIOB pins */ +} _PMU_RXEVEN_bits; + +/* Bit field positions: */ +#define PMU_RXEVEN_GPIOAEV_Pos 0 /*!< Enable RX event from GPIOA pins */ +#define PMU_RXEVEN_GPIOBEV_Pos 1 /*!< Enable RX event from GPIOB pins */ + +/* Bit field masks: */ +#define PMU_RXEVEN_GPIOAEV_Msk 0x00000001UL /*!< Enable RX event from GPIOA pins */ +#define PMU_RXEVEN_GPIOBEV_Msk 0x00000002UL /*!< Enable RX event from GPIOB pins */ + +typedef struct { + union { /*!< PMU Configuration Register */ + __IO uint32_t CFG; /*!< CFG : type used for word access */ + __IO _PMU_CFG_bits CFG_bit; /*!< CFG_bit: structure used for bit access */ + }; + union { /*!< PMU Powerup Delay Value */ + __IO uint32_t PUDEL; /*!< PUDEL : type used for word access */ + __IO _PMU_PUDEL_bits PUDEL_bit; /*!< PUDEL_bit: structure used for bit access */ + }; + union { /*!< PMU Enable Powerdown for peripheral */ + __IO uint32_t PDEN; /*!< PDEN : type used for word access */ + __IO _PMU_PDEN_bits PDEN_bit; /*!< PDEN_bit: structure used for bit access */ + }; + union { /*!< PMU RX Event generation enable register */ + __IO uint32_t RXEVEN; /*!< RXEVEN : type used for word access */ + __IO _PMU_RXEVEN_bits RXEVEN_bit; /*!< RXEVEN_bit: structure used for bit access */ + }; +} PMU_TypeDef; + + +/******************************************************************************/ +/* WDT registers */ +/******************************************************************************/ + +/*-- LOAD: Watchdog Load Register ----------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Begin value counter */ +} _WDT_LOAD_bits; + +/* Bit field positions: */ +#define WDT_LOAD_VAL_Pos 0 /*!< Begin value counter */ + +/* Bit field masks: */ +#define WDT_LOAD_VAL_Msk 0xFFFFFFFFUL /*!< Begin value counter */ + +/*-- VALUE: Watchdog Value Register --------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Current value counter */ +} _WDT_VALUE_bits; + +/* Bit field positions: */ +#define WDT_VALUE_VAL_Pos 0 /*!< Current value counter */ + +/* Bit field masks: */ +#define WDT_VALUE_VAL_Msk 0xFFFFFFFFUL /*!< Current value counter */ + +/*-- CTRL: Watchdog Control Register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t INTEN :1; /*!< Enable the interrupt event */ + uint32_t RESEN :1; /*!< Enable watchdog reset output */ +} _WDT_CTRL_bits; + +/* Bit field positions: */ +#define WDT_CTRL_INTEN_Pos 0 /*!< Enable the interrupt event */ +#define WDT_CTRL_RESEN_Pos 1 /*!< Enable watchdog reset output */ + +/* Bit field masks: */ +#define WDT_CTRL_INTEN_Msk 0x00000001UL /*!< Enable the interrupt event */ +#define WDT_CTRL_RESEN_Msk 0x00000002UL /*!< Enable watchdog reset output */ + +/*-- INTCLR: Watchdog Clear Interrupt Register ---------------------------------------------------------------*/ +typedef struct { + uint32_t WDTCLR :32; /*!< Reset interrupt WDT */ +} _WDT_INTCLR_bits; + +/* Bit field positions: */ +#define WDT_INTCLR_WDTCLR_Pos 0 /*!< Reset interrupt WDT */ + +/* Bit field masks: */ +#define WDT_INTCLR_WDTCLR_Msk 0xFFFFFFFFUL /*!< Reset interrupt WDT */ + +/*-- RIS: Watchdog Raw Interrupt Status Register -------------------------------------------------------------*/ +typedef struct { + uint32_t RAWWDTINT :1; /*!< Raw interrupt status from the counter */ +} _WDT_RIS_bits; + +/* Bit field positions: */ +#define WDT_RIS_RAWWDTINT_Pos 0 /*!< Raw interrupt status from the counter */ + +/* Bit field masks: */ +#define WDT_RIS_RAWWDTINT_Msk 0x00000001UL /*!< Raw interrupt status from the counter */ + +/*-- MIS: Watchdog Interrupt Status Register -----------------------------------------------------------------*/ +typedef struct { + uint32_t WDTINT :1; /*!< Enabled interrupt status from the counter */ +} _WDT_MIS_bits; + +/* Bit field positions: */ +#define WDT_MIS_WDTINT_Pos 0 /*!< Enabled interrupt status from the counter */ + +/* Bit field masks: */ +#define WDT_MIS_WDTINT_Msk 0x00000001UL /*!< Enabled interrupt status from the counter */ + +/*-- LOCK: Watchdog Lock Register ----------------------------------------------------------------------------*/ +typedef struct { + uint32_t REGWRDIS :1; /*!< Disable write to all registers Watchdog */ +} _WDT_LOCK_bits; + +/* Bit field positions: */ +#define WDT_LOCK_REGWRDIS_Pos 0 /*!< Disable write to all registers Watchdog */ + +/* Bit field masks: */ +#define WDT_LOCK_REGWRDIS_Msk 0x00000001UL /*!< Disable write to all registers Watchdog */ + +typedef struct { + union { /*!< Watchdog Load Register */ + __IO uint32_t LOAD; /*!< LOAD : type used for word access */ + __IO _WDT_LOAD_bits LOAD_bit; /*!< LOAD_bit: structure used for bit access */ + }; + union { /*!< Watchdog Value Register */ + __I uint32_t VALUE; /*!< VALUE : type used for word access */ + __I _WDT_VALUE_bits VALUE_bit; /*!< VALUE_bit: structure used for bit access */ + }; + union { /*!< Watchdog Control Register */ + __IO uint32_t CTRL; /*!< CTRL : type used for word access */ + __IO _WDT_CTRL_bits CTRL_bit; /*!< CTRL_bit: structure used for bit access */ + }; + union { /*!< Watchdog Clear Interrupt Register */ + __O uint32_t INTCLR; /*!< INTCLR : type used for word access */ + __O _WDT_INTCLR_bits INTCLR_bit; /*!< INTCLR_bit: structure used for bit access */ + }; + union { /*!< Watchdog Raw Interrupt Status Register */ + __I uint32_t RIS; /*!< RIS : type used for word access */ + __I _WDT_RIS_bits RIS_bit; /*!< RIS_bit: structure used for bit access */ + }; + union { /*!< Watchdog Interrupt Status Register */ + __I uint32_t MIS; /*!< MIS : type used for word access */ + __I _WDT_MIS_bits MIS_bit; /*!< MIS_bit: structure used for bit access */ + }; + __IO uint32_t Reserved0[762]; + union { /*!< Watchdog Lock Register */ + __O uint32_t LOCK; /*!< LOCK : type used for word access */ + __O _WDT_LOCK_bits LOCK_bit; /*!< LOCK_bit: structure used for bit access */ + }; +} WDT_TypeDef; + + +/******************************************************************************/ +/* TMR registers */ +/******************************************************************************/ + +/*-- CTRL: Control Timer register ----------------------------------------------------------------------------*/ +typedef struct { + uint32_t ON :1; /*!< Enable Timer */ + uint32_t EXTINEN :1; /*!< Enable external input as ENABLE */ + uint32_t EXTINCLK :1; /*!< Enable external input as CLK */ + uint32_t INTEN :1; /*!< Enable Timer interrupt */ +} _TMR_CTRL_bits; + +/* Bit field positions: */ +#define TMR_CTRL_ON_Pos 0 /*!< Enable Timer */ +#define TMR_CTRL_EXTINEN_Pos 1 /*!< Enable external input as ENABLE */ +#define TMR_CTRL_EXTINCLK_Pos 2 /*!< Enable external input as CLK */ +#define TMR_CTRL_INTEN_Pos 3 /*!< Enable Timer interrupt */ + +/* Bit field masks: */ +#define TMR_CTRL_ON_Msk 0x00000001UL /*!< Enable Timer */ +#define TMR_CTRL_EXTINEN_Msk 0x00000002UL /*!< Enable external input as ENABLE */ +#define TMR_CTRL_EXTINCLK_Msk 0x00000004UL /*!< Enable external input as CLK */ +#define TMR_CTRL_INTEN_Msk 0x00000008UL /*!< Enable Timer interrupt */ + +/*-- VALUE: Current value timer register ---------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Current value timer */ +} _TMR_VALUE_bits; + +/* Bit field positions: */ +#define TMR_VALUE_VAL_Pos 0 /*!< Current value timer */ + +/* Bit field masks: */ +#define TMR_VALUE_VAL_Msk 0xFFFFFFFFUL /*!< Current value timer */ + +/*-- LOAD: Reload value timer register -----------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Reload value. A write to this register sets the current value */ +} _TMR_LOAD_bits; + +/* Bit field positions: */ +#define TMR_LOAD_VAL_Pos 0 /*!< Reload value. A write to this register sets the current value */ + +/* Bit field masks: */ +#define TMR_LOAD_VAL_Msk 0xFFFFFFFFUL /*!< Reload value. A write to this register sets the current value */ + +/*-- INTSTATUS: Interrupt status register --------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Timer interrupt flag */ +} _TMR_INTSTATUS_bits; + +/* Bit field positions: */ +#define TMR_INTSTATUS_INT_Pos 0 /*!< Timer interrupt flag */ + +/* Bit field masks: */ +#define TMR_INTSTATUS_INT_Msk 0x00000001UL /*!< Timer interrupt flag */ + +/*-- DMAREQ: DMA request register ----------------------------------------------------------------------------*/ +typedef struct { + uint32_t EN :1; /*!< */ +} _TMR_DMAREQ_bits; + +/* Bit field positions: */ +#define TMR_DMAREQ_EN_Pos 0 /*!< */ + +/* Bit field masks: */ +#define TMR_DMAREQ_EN_Msk 0x00000001UL /*!< */ + +/*-- ADCSOC: ADC start of conversion register ----------------------------------------------------------------*/ +typedef struct { + uint32_t EN :1; /*!< */ +} _TMR_ADCSOC_bits; + +/* Bit field positions: */ +#define TMR_ADCSOC_EN_Pos 0 /*!< */ + +/* Bit field masks: */ +#define TMR_ADCSOC_EN_Msk 0x00000001UL /*!< */ + +typedef struct { + union { /*!< Control Timer register */ + __IO uint32_t CTRL; /*!< CTRL : type used for word access */ + __IO _TMR_CTRL_bits CTRL_bit; /*!< CTRL_bit: structure used for bit access */ + }; + union { /*!< Current value timer register */ + __IO uint32_t VALUE; /*!< VALUE : type used for word access */ + __IO _TMR_VALUE_bits VALUE_bit; /*!< VALUE_bit: structure used for bit access */ + }; + union { /*!< Reload value timer register */ + __IO uint32_t LOAD; /*!< LOAD : type used for word access */ + __IO _TMR_LOAD_bits LOAD_bit; /*!< LOAD_bit: structure used for bit access */ + }; + union { /*!< Interrupt status register */ + __IO uint32_t INTSTATUS; /*!< INTSTATUS : type used for word access */ + __IO _TMR_INTSTATUS_bits INTSTATUS_bit; /*!< INTSTATUS_bit: structure used for bit access */ + }; + union { /*!< DMA request register */ + __IO uint32_t DMAREQ; /*!< DMAREQ : type used for word access */ + __IO _TMR_DMAREQ_bits DMAREQ_bit; /*!< DMAREQ_bit: structure used for bit access */ + }; + union { /*!< ADC start of conversion register */ + __IO uint32_t ADCSOC; /*!< ADCSOC : type used for word access */ + __IO _TMR_ADCSOC_bits ADCSOC_bit; /*!< ADCSOC_bit: structure used for bit access */ + }; +} TMR_TypeDef; + + +/******************************************************************************/ +/* ADC registers */ +/******************************************************************************/ + +/*-- SEQEN: Enable sequencer register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t SEQEN0 :1; /*!< Enable sequencer 0 */ + uint32_t SEQEN1 :1; /*!< Enable sequencer 1 */ +} _ADC_SEQEN_bits; + +/* Bit field positions: */ +#define ADC_SEQEN_SEQEN0_Pos 0 /*!< Enable sequencer 0 */ +#define ADC_SEQEN_SEQEN1_Pos 1 /*!< Enable sequencer 1 */ + +/* Bit field masks: */ +#define ADC_SEQEN_SEQEN0_Msk 0x00000001UL /*!< Enable sequencer 0 */ +#define ADC_SEQEN_SEQEN1_Msk 0x00000002UL /*!< Enable sequencer 1 */ + +/*-- SEQSYNC: Sequencer sync register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t SYNC0 :1; /*!< Enable sequencer 0 software sync */ + uint32_t SYNC1 :1; /*!< Enable sequencer 1 software sync */ + uint32_t :29; /*!< RESERVED */ + uint32_t GSYNC :1; /*!< Sync all sequencers */ +} _ADC_SEQSYNC_bits; + +/* Bit field positions: */ +#define ADC_SEQSYNC_SYNC0_Pos 0 /*!< Enable sequencer 0 software sync */ +#define ADC_SEQSYNC_SYNC1_Pos 1 /*!< Enable sequencer 1 software sync */ +#define ADC_SEQSYNC_GSYNC_Pos 31 /*!< Sync all sequencers */ + +/* Bit field masks: */ +#define ADC_SEQSYNC_SYNC0_Msk 0x00000001UL /*!< Enable sequencer 0 software sync */ +#define ADC_SEQSYNC_SYNC1_Msk 0x00000002UL /*!< Enable sequencer 1 software sync */ +#define ADC_SEQSYNC_GSYNC_Msk 0x80000000UL /*!< Sync all sequencers */ + +/*-- FSTAT: FIFO overflow status register --------------------------------------------------------------------*/ +typedef struct { + uint32_t OV0 :1; /*!< Sequencer 0 FIFO overflow */ + uint32_t OV1 :1; /*!< Sequencer 1 FIFO overflow */ + uint32_t :6; /*!< RESERVED */ + uint32_t UN0 :1; /*!< Sequencer 0 FIFO underflow */ + uint32_t UN1 :1; /*!< Sequencer 1 FIFO underflow */ + uint32_t :6; /*!< RESERVED */ + uint32_t DOV0 :1; /*!< Sequencer 0 FIFO DMA request overflow */ + uint32_t DOV1 :1; /*!< Sequencer 1 FIFO DMA request overflow */ +} _ADC_FSTAT_bits; + +/* Bit field positions: */ +#define ADC_FSTAT_OV0_Pos 0 /*!< Sequencer 0 FIFO overflow */ +#define ADC_FSTAT_OV1_Pos 1 /*!< Sequencer 1 FIFO overflow */ +#define ADC_FSTAT_UN0_Pos 8 /*!< Sequencer 0 FIFO underflow */ +#define ADC_FSTAT_UN1_Pos 9 /*!< Sequencer 1 FIFO underflow */ +#define ADC_FSTAT_DOV0_Pos 16 /*!< Sequencer 0 FIFO DMA request overflow */ +#define ADC_FSTAT_DOV1_Pos 17 /*!< Sequencer 1 FIFO DMA request overflow */ + +/* Bit field masks: */ +#define ADC_FSTAT_OV0_Msk 0x00000001UL /*!< Sequencer 0 FIFO overflow */ +#define ADC_FSTAT_OV1_Msk 0x00000002UL /*!< Sequencer 1 FIFO overflow */ +#define ADC_FSTAT_UN0_Msk 0x00000100UL /*!< Sequencer 0 FIFO underflow */ +#define ADC_FSTAT_UN1_Msk 0x00000200UL /*!< Sequencer 1 FIFO underflow */ +#define ADC_FSTAT_DOV0_Msk 0x00010000UL /*!< Sequencer 0 FIFO DMA request overflow */ +#define ADC_FSTAT_DOV1_Msk 0x00020000UL /*!< Sequencer 1 FIFO DMA request overflow */ + +/*-- BSTAT: Busy status register -----------------------------------------------------------------------------*/ +typedef struct { + uint32_t SEQBUSY0 :1; /*!< Sequencer 0 busy */ + uint32_t SEQBUSY1 :1; /*!< Sequencer 1 busy */ + uint32_t :14; /*!< RESERVED */ + uint32_t ADCBUSY :1; /*!< ADC module conversion busy */ +} _ADC_BSTAT_bits; + +/* Bit field positions: */ +#define ADC_BSTAT_SEQBUSY0_Pos 0 /*!< Sequencer 0 busy */ +#define ADC_BSTAT_SEQBUSY1_Pos 1 /*!< Sequencer 1 busy */ +#define ADC_BSTAT_ADCBUSY_Pos 16 /*!< ADC module conversion busy */ + +/* Bit field masks: */ +#define ADC_BSTAT_SEQBUSY0_Msk 0x00000001UL /*!< Sequencer 0 busy */ +#define ADC_BSTAT_SEQBUSY1_Msk 0x00000002UL /*!< Sequencer 1 busy */ +#define ADC_BSTAT_ADCBUSY_Msk 0x00010000UL /*!< ADC module conversion busy */ + +/*-- DCTRIG: Digital comparator output trigger status register -----------------------------------------------*/ +typedef struct { + uint32_t TOS0 :1; /*!< DC 0 output trigger status */ + uint32_t TOS1 :1; /*!< DC 1 output trigger status */ + uint32_t TOS2 :1; /*!< DC 2 output trigger status */ + uint32_t TOS3 :1; /*!< DC 3 output trigger status */ + uint32_t :12; /*!< RESERVED */ + uint32_t DCEV0 :1; /*!< Digital compare event 0 */ + uint32_t DCEV1 :1; /*!< Digital compare event 1 */ + uint32_t DCEV2 :1; /*!< Digital compare event 2 */ + uint32_t DCEV3 :1; /*!< Digital compare event 3 */ +} _ADC_DCTRIG_bits; + +/* Bit field positions: */ +#define ADC_DCTRIG_TOS0_Pos 0 /*!< DC 0 output trigger status */ +#define ADC_DCTRIG_TOS1_Pos 1 /*!< DC 1 output trigger status */ +#define ADC_DCTRIG_TOS2_Pos 2 /*!< DC 2 output trigger status */ +#define ADC_DCTRIG_TOS3_Pos 3 /*!< DC 3 output trigger status */ +#define ADC_DCTRIG_DCEV0_Pos 16 /*!< Digital compare event 0 */ +#define ADC_DCTRIG_DCEV1_Pos 17 /*!< Digital compare event 1 */ +#define ADC_DCTRIG_DCEV2_Pos 18 /*!< Digital compare event 2 */ +#define ADC_DCTRIG_DCEV3_Pos 19 /*!< Digital compare event 3 */ + +/* Bit field masks: */ +#define ADC_DCTRIG_TOS0_Msk 0x00000001UL /*!< DC 0 output trigger status */ +#define ADC_DCTRIG_TOS1_Msk 0x00000002UL /*!< DC 1 output trigger status */ +#define ADC_DCTRIG_TOS2_Msk 0x00000004UL /*!< DC 2 output trigger status */ +#define ADC_DCTRIG_TOS3_Msk 0x00000008UL /*!< DC 3 output trigger status */ +#define ADC_DCTRIG_DCEV0_Msk 0x00010000UL /*!< Digital compare event 0 */ +#define ADC_DCTRIG_DCEV1_Msk 0x00020000UL /*!< Digital compare event 1 */ +#define ADC_DCTRIG_DCEV2_Msk 0x00040000UL /*!< Digital compare event 2 */ +#define ADC_DCTRIG_DCEV3_Msk 0x00080000UL /*!< Digital compare event 3 */ + +/*-- CICNT: Interrupt counter clear control ------------------------------------------------------------------*/ +typedef struct { + uint32_t ICNT0 :1; /*!< Clear interrupt counter on sequencer 0 start */ + uint32_t ICNT1 :1; /*!< Clear interrupt counter on sequencer 1 start */ +} _ADC_CICNT_bits; + +/* Bit field positions: */ +#define ADC_CICNT_ICNT0_Pos 0 /*!< Clear interrupt counter on sequencer 0 start */ +#define ADC_CICNT_ICNT1_Pos 1 /*!< Clear interrupt counter on sequencer 1 start */ + +/* Bit field masks: */ +#define ADC_CICNT_ICNT0_Msk 0x00000001UL /*!< Clear interrupt counter on sequencer 0 start */ +#define ADC_CICNT_ICNT1_Msk 0x00000002UL /*!< Clear interrupt counter on sequencer 1 start */ + +/*-- EMUX: Sequencer start event selection register ----------------------------------------------------------*/ +typedef struct { + uint32_t EM0 :4; /*!< Select start event for sequencer 0 */ + uint32_t EM1 :4; /*!< Select start event for sequencer 1 */ +} _ADC_EMUX_bits; + +/* Bit field positions: */ +#define ADC_EMUX_EM0_Pos 0 /*!< Select start event for sequencer 0 */ +#define ADC_EMUX_EM1_Pos 4 /*!< Select start event for sequencer 1 */ + +/* Bit field masks: */ +#define ADC_EMUX_EM0_Msk 0x0000000FUL /*!< Select start event for sequencer 0 */ +#define ADC_EMUX_EM1_Msk 0x000000F0UL /*!< Select start event for sequencer 1 */ + +/* Bit field enums: */ +typedef enum { + ADC_EMUX_EM0_SwReq = 0x0UL, /*!< software request by GSYNC bit */ + ADC_EMUX_EM0_GPIOA = 0x1UL, /*!< GPIOA interrupt */ + ADC_EMUX_EM0_GPIOB = 0x2UL, /*!< GPIOB interrupt */ + ADC_EMUX_EM0_TMR0 = 0x3UL, /*!< Timer 0 request */ + ADC_EMUX_EM0_TMR1 = 0x4UL, /*!< Timer 1 request */ + ADC_EMUX_EM0_TMR2 = 0x5UL, /*!< Timer 2 request */ + ADC_EMUX_EM0_TMR3 = 0x6UL, /*!< Timer 3 request */ + ADC_EMUX_EM0_PWM012A = 0x7UL, /*!< PWM0,1,2 A channel request */ + ADC_EMUX_EM0_PWM012B = 0x8UL, /*!< PWM0,1,2 B channel request */ + ADC_EMUX_EM0_Cycle = 0xFUL, /*!< Cycle mode */ +} ADC_EMUX_EM0_Enum; + +typedef enum { + ADC_EMUX_EM1_SwReq = 0x0UL, /*!< software request by GSYNC bit */ + ADC_EMUX_EM1_GPIOA = 0x1UL, /*!< GPIOA interrupt */ + ADC_EMUX_EM1_GPIOB = 0x2UL, /*!< GPIOB interrupt */ + ADC_EMUX_EM1_TMR0 = 0x3UL, /*!< Timer 0 request */ + ADC_EMUX_EM1_TMR1 = 0x4UL, /*!< Timer 1 request */ + ADC_EMUX_EM1_TMR2 = 0x5UL, /*!< Timer 2 request */ + ADC_EMUX_EM1_TMR3 = 0x6UL, /*!< Timer 3 request */ + ADC_EMUX_EM1_PWM012A = 0x7UL, /*!< PWM0,1,2 A channel request */ + ADC_EMUX_EM1_PWM012B = 0x8UL, /*!< PWM0,1,2 B channel request */ + ADC_EMUX_EM1_Cycle = 0xFUL, /*!< Cycle mode */ +} ADC_EMUX_EM1_Enum; + +/*-- RIS: Raw interrupt status register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t SEQRIS0 :1; /*!< Sequencer 0 raw interrupt status */ + uint32_t SEQRIS1 :1; /*!< Sequencer 1 raw interrupt status */ + uint32_t :6; /*!< RESERVED */ + uint32_t DCRIS0 :1; /*!< Raw interrupt status of Digital Comparator 0 */ + uint32_t DCRIS1 :1; /*!< Raw interrupt status of Digital Comparator 1 */ + uint32_t DCRIS2 :1; /*!< Raw interrupt status of Digital Comparator 2 */ + uint32_t DCRIS3 :1; /*!< Raw interrupt status of Digital Comparator 3 */ +} _ADC_RIS_bits; + +/* Bit field positions: */ +#define ADC_RIS_SEQRIS0_Pos 0 /*!< Sequencer 0 raw interrupt status */ +#define ADC_RIS_SEQRIS1_Pos 1 /*!< Sequencer 1 raw interrupt status */ +#define ADC_RIS_DCRIS0_Pos 8 /*!< Raw interrupt status of Digital Comparator 0 */ +#define ADC_RIS_DCRIS1_Pos 9 /*!< Raw interrupt status of Digital Comparator 1 */ +#define ADC_RIS_DCRIS2_Pos 10 /*!< Raw interrupt status of Digital Comparator 2 */ +#define ADC_RIS_DCRIS3_Pos 11 /*!< Raw interrupt status of Digital Comparator 3 */ + +/* Bit field masks: */ +#define ADC_RIS_SEQRIS0_Msk 0x00000001UL /*!< Sequencer 0 raw interrupt status */ +#define ADC_RIS_SEQRIS1_Msk 0x00000002UL /*!< Sequencer 1 raw interrupt status */ +#define ADC_RIS_DCRIS0_Msk 0x00000100UL /*!< Raw interrupt status of Digital Comparator 0 */ +#define ADC_RIS_DCRIS1_Msk 0x00000200UL /*!< Raw interrupt status of Digital Comparator 1 */ +#define ADC_RIS_DCRIS2_Msk 0x00000400UL /*!< Raw interrupt status of Digital Comparator 2 */ +#define ADC_RIS_DCRIS3_Msk 0x00000800UL /*!< Raw interrupt status of Digital Comparator 3 */ + +/*-- IM: Interrupt mask register -----------------------------------------------------------------------------*/ +typedef struct { + uint32_t SEQIM0 :1; /*!< Sequencer 0 interrupt mask */ + uint32_t SEQIM1 :1; /*!< Sequencer 1 interrupt mask */ + uint32_t :6; /*!< RESERVED */ + uint32_t DCIM0 :1; /*!< Interrupt mask of Digital Comparator 0 */ + uint32_t DCIM1 :1; /*!< Interrupt mask of Digital Comparator 1 */ + uint32_t DCIM2 :1; /*!< Interrupt mask of Digital Comparator 2 */ + uint32_t DCIM3 :1; /*!< Interrupt mask of Digital Comparator 3 */ +} _ADC_IM_bits; + +/* Bit field positions: */ +#define ADC_IM_SEQIM0_Pos 0 /*!< Sequencer 0 interrupt mask */ +#define ADC_IM_SEQIM1_Pos 1 /*!< Sequencer 1 interrupt mask */ +#define ADC_IM_DCIM0_Pos 8 /*!< Interrupt mask of Digital Comparator 0 */ +#define ADC_IM_DCIM1_Pos 9 /*!< Interrupt mask of Digital Comparator 1 */ +#define ADC_IM_DCIM2_Pos 10 /*!< Interrupt mask of Digital Comparator 2 */ +#define ADC_IM_DCIM3_Pos 11 /*!< Interrupt mask of Digital Comparator 3 */ + +/* Bit field masks: */ +#define ADC_IM_SEQIM0_Msk 0x00000001UL /*!< Sequencer 0 interrupt mask */ +#define ADC_IM_SEQIM1_Msk 0x00000002UL /*!< Sequencer 1 interrupt mask */ +#define ADC_IM_DCIM0_Msk 0x00000100UL /*!< Interrupt mask of Digital Comparator 0 */ +#define ADC_IM_DCIM1_Msk 0x00000200UL /*!< Interrupt mask of Digital Comparator 1 */ +#define ADC_IM_DCIM2_Msk 0x00000400UL /*!< Interrupt mask of Digital Comparator 2 */ +#define ADC_IM_DCIM3_Msk 0x00000800UL /*!< Interrupt mask of Digital Comparator 3 */ + +/*-- MIS: Masked interrupt status and clear register ---------------------------------------------------------*/ +typedef struct { + uint32_t SEQMIS0 :1; /*!< Sequencer 0 masked interrupt status */ + uint32_t SEQMIS1 :1; /*!< Sequencer 1 masked interrupt status */ + uint32_t :6; /*!< RESERVED */ + uint32_t DCMIS0 :1; /*!< DC 0 masked interrupt status */ + uint32_t DCMIS1 :1; /*!< DC 1 masked interrupt status */ + uint32_t DCMIS2 :1; /*!< DC 2 masked interrupt status */ + uint32_t DCMIS3 :1; /*!< DC 3 masked interrupt status */ +} _ADC_MIS_bits; + +/* Bit field positions: */ +#define ADC_MIS_SEQMIS0_Pos 0 /*!< Sequencer 0 masked interrupt status */ +#define ADC_MIS_SEQMIS1_Pos 1 /*!< Sequencer 1 masked interrupt status */ +#define ADC_MIS_DCMIS0_Pos 8 /*!< DC 0 masked interrupt status */ +#define ADC_MIS_DCMIS1_Pos 9 /*!< DC 1 masked interrupt status */ +#define ADC_MIS_DCMIS2_Pos 10 /*!< DC 2 masked interrupt status */ +#define ADC_MIS_DCMIS3_Pos 11 /*!< DC 3 masked interrupt status */ + +/* Bit field masks: */ +#define ADC_MIS_SEQMIS0_Msk 0x00000001UL /*!< Sequencer 0 masked interrupt status */ +#define ADC_MIS_SEQMIS1_Msk 0x00000002UL /*!< Sequencer 1 masked interrupt status */ +#define ADC_MIS_DCMIS0_Msk 0x00000100UL /*!< DC 0 masked interrupt status */ +#define ADC_MIS_DCMIS1_Msk 0x00000200UL /*!< DC 1 masked interrupt status */ +#define ADC_MIS_DCMIS2_Msk 0x00000400UL /*!< DC 2 masked interrupt status */ +#define ADC_MIS_DCMIS3_Msk 0x00000800UL /*!< DC 3 masked interrupt status */ + +/*-- IC: Interrupt clear register ----------------------------------------------------------------------------*/ +typedef struct { + uint32_t SEQIC0 :1; /*!< Sequencer 0 interrupt status clear */ + uint32_t SEQIC1 :1; /*!< Sequencer 1 interrupt status clear */ + uint32_t :6; /*!< RESERVED */ + uint32_t DCIC0 :1; /*!< DC 0 interrupt status clear */ + uint32_t DCIC1 :1; /*!< DC 1 interrupt status clear */ + uint32_t DCIC2 :1; /*!< DC 2 interrupt status clear */ + uint32_t DCIC3 :1; /*!< DC 3 interrupt status clear */ +} _ADC_IC_bits; + +/* Bit field positions: */ +#define ADC_IC_SEQIC0_Pos 0 /*!< Sequencer 0 interrupt status clear */ +#define ADC_IC_SEQIC1_Pos 1 /*!< Sequencer 1 interrupt status clear */ +#define ADC_IC_DCIC0_Pos 8 /*!< DC 0 interrupt status clear */ +#define ADC_IC_DCIC1_Pos 9 /*!< DC 1 interrupt status clear */ +#define ADC_IC_DCIC2_Pos 10 /*!< DC 2 interrupt status clear */ +#define ADC_IC_DCIC3_Pos 11 /*!< DC 3 interrupt status clear */ + +/* Bit field masks: */ +#define ADC_IC_SEQIC0_Msk 0x00000001UL /*!< Sequencer 0 interrupt status clear */ +#define ADC_IC_SEQIC1_Msk 0x00000002UL /*!< Sequencer 1 interrupt status clear */ +#define ADC_IC_DCIC0_Msk 0x00000100UL /*!< DC 0 interrupt status clear */ +#define ADC_IC_DCIC1_Msk 0x00000200UL /*!< DC 1 interrupt status clear */ +#define ADC_IC_DCIC2_Msk 0x00000400UL /*!< DC 2 interrupt status clear */ +#define ADC_IC_DCIC3_Msk 0x00000800UL /*!< DC 3 interrupt status clear */ + +/*-- SEQ: SRQSEL: Sequencer request ADC channels selection register -------------------------------------------*/ +typedef struct { + uint32_t RQ0 :2; /*!< Select ADC channel for request 0 */ + uint32_t :2; /*!< RESERVED */ + uint32_t RQ1 :2; /*!< Select ADC channel for request 1 */ + uint32_t :2; /*!< RESERVED */ + uint32_t RQ2 :2; /*!< Select ADC channel for request 2 */ + uint32_t :2; /*!< RESERVED */ + uint32_t RQ3 :2; /*!< Select ADC channel for request 3 */ +} _ADC_SEQ_SRQSEL_bits; + +/* Bit field positions: */ +#define ADC_SEQ_SRQSEL_RQ0_Pos 0 /*!< Select ADC channel for request 0 */ +#define ADC_SEQ_SRQSEL_RQ1_Pos 4 /*!< Select ADC channel for request 1 */ +#define ADC_SEQ_SRQSEL_RQ2_Pos 8 /*!< Select ADC channel for request 2 */ +#define ADC_SEQ_SRQSEL_RQ3_Pos 12 /*!< Select ADC channel for request 3 */ + +/* Bit field masks: */ +#define ADC_SEQ_SRQSEL_RQ0_Msk 0x00000003UL /*!< Select ADC channel for request 0 */ +#define ADC_SEQ_SRQSEL_RQ1_Msk 0x00000030UL /*!< Select ADC channel for request 1 */ +#define ADC_SEQ_SRQSEL_RQ2_Msk 0x00000300UL /*!< Select ADC channel for request 2 */ +#define ADC_SEQ_SRQSEL_RQ3_Msk 0x00003000UL /*!< Select ADC channel for request 3 */ + +/*-- SEQ: SRQCTL: Sequencer request control register ----------------------------------------------------------*/ +typedef struct { + uint32_t RQMAX :2; /*!< Request queue max depth */ + uint32_t :6; /*!< RESERVED */ + uint32_t QAVGEN :1; /*!< Queue avearage (scanning) enable */ + uint32_t QAVGVAL :3; /*!< Queue average value */ +} _ADC_SEQ_SRQCTL_bits; + +/* Bit field positions: */ +#define ADC_SEQ_SRQCTL_RQMAX_Pos 0 /*!< Request queue max depth */ +#define ADC_SEQ_SRQCTL_QAVGEN_Pos 8 /*!< Queue avearage (scanning) enable */ +#define ADC_SEQ_SRQCTL_QAVGVAL_Pos 9 /*!< Queue average value */ + +/* Bit field masks: */ +#define ADC_SEQ_SRQCTL_RQMAX_Msk 0x00000003UL /*!< Request queue max depth */ +#define ADC_SEQ_SRQCTL_QAVGEN_Msk 0x00000100UL /*!< Queue avearage (scanning) enable */ +#define ADC_SEQ_SRQCTL_QAVGVAL_Msk 0x00000E00UL /*!< Queue average value */ + +/* Bit field enums: */ +typedef enum { + ADC_SEQ_SRQCTL_QAVGVAL_Disable = 0x0UL, /*!< Average disabled */ + ADC_SEQ_SRQCTL_QAVGVAL_Average2 = 0x1UL, /*!< Average with 2 measures */ + ADC_SEQ_SRQCTL_QAVGVAL_Average4 = 0x2UL, /*!< Average with 4 measures */ + ADC_SEQ_SRQCTL_QAVGVAL_Average8 = 0x3UL, /*!< Average with 8 measures */ + ADC_SEQ_SRQCTL_QAVGVAL_Average16 = 0x4UL, /*!< Average with 16 measures */ + ADC_SEQ_SRQCTL_QAVGVAL_Average32 = 0x5UL, /*!< Average with 32 measures */ + ADC_SEQ_SRQCTL_QAVGVAL_Average64 = 0x6UL, /*!< Average with 64 measures */ +} ADC_SEQ_SRQCTL_QAVGVAL_Enum; + +/*-- SEQ: SRQSTAT: Sequencer request status register ----------------------------------------------------------*/ +typedef struct { + uint32_t RQPTR :2; /*!< Pointer to queue current request */ + uint32_t :6; /*!< RESERVED */ + uint32_t RQBUSY :1; /*!< Active request status */ +} _ADC_SEQ_SRQSTAT_bits; + +/* Bit field positions: */ +#define ADC_SEQ_SRQSTAT_RQPTR_Pos 0 /*!< Pointer to queue current request */ +#define ADC_SEQ_SRQSTAT_RQBUSY_Pos 8 /*!< Active request status */ + +/* Bit field masks: */ +#define ADC_SEQ_SRQSTAT_RQPTR_Msk 0x00000003UL /*!< Pointer to queue current request */ +#define ADC_SEQ_SRQSTAT_RQBUSY_Msk 0x00000100UL /*!< Active request status */ + +/*-- SEQ: SDMACTL: Sequencer DMA control register -------------------------------------------------------------*/ +typedef struct { + uint32_t DMAEN :1; /*!< Enable DMA use */ + uint32_t :7; /*!< RESERVED */ + uint32_t WMARK :3; /*!< FIFO load threshold for DMA request generation */ +} _ADC_SEQ_SDMACTL_bits; + +/* Bit field positions: */ +#define ADC_SEQ_SDMACTL_DMAEN_Pos 0 /*!< Enable DMA use */ +#define ADC_SEQ_SDMACTL_WMARK_Pos 8 /*!< FIFO load threshold for DMA request generation */ + +/* Bit field masks: */ +#define ADC_SEQ_SDMACTL_DMAEN_Msk 0x00000001UL /*!< Enable DMA use */ +#define ADC_SEQ_SDMACTL_WMARK_Msk 0x00000700UL /*!< FIFO load threshold for DMA request generation */ + +/* Bit field enums: */ +typedef enum { + ADC_SEQ_SDMACTL_WMARK_Level1 = 0x1UL, /*!< 1 measure for dma request */ + ADC_SEQ_SDMACTL_WMARK_Level2 = 0x2UL, /*!< 2 measures for dma request */ + ADC_SEQ_SDMACTL_WMARK_Level4 = 0x3UL, /*!< 4 measures for dma request */ + ADC_SEQ_SDMACTL_WMARK_Level8 = 0x4UL, /*!< 8 measures for dma request */ + ADC_SEQ_SDMACTL_WMARK_Level16 = 0x5UL, /*!< 16 measures for dma request */ + ADC_SEQ_SDMACTL_WMARK_Level32 = 0x6UL, /*!< 32 measures for dma request */ +} ADC_SEQ_SDMACTL_WMARK_Enum; + +/*-- SEQ: SCCTL: Sequencer ADC interrupt and restart counter control register ---------------------------------*/ +typedef struct { + uint32_t RCNT :8; /*!< Current number of ADC restarts by sequencer */ + uint32_t RAVGEN :1; /*!< Average of ADC restarts enable */ + uint32_t :7; /*!< RESERVED */ + uint32_t ICNT :8; /*!< Number of ADC requests for interrupt generation */ +} _ADC_SEQ_SCCTL_bits; + +/* Bit field positions: */ +#define ADC_SEQ_SCCTL_RCNT_Pos 0 /*!< Current number of ADC restarts by sequencer */ +#define ADC_SEQ_SCCTL_RAVGEN_Pos 8 /*!< Average of ADC restarts enable */ +#define ADC_SEQ_SCCTL_ICNT_Pos 16 /*!< Number of ADC requests for interrupt generation */ + +/* Bit field masks: */ +#define ADC_SEQ_SCCTL_RCNT_Msk 0x000000FFUL /*!< Current number of ADC restarts by sequencer */ +#define ADC_SEQ_SCCTL_RAVGEN_Msk 0x00000100UL /*!< Average of ADC restarts enable */ +#define ADC_SEQ_SCCTL_ICNT_Msk 0x00FF0000UL /*!< Number of ADC requests for interrupt generation */ + +/*-- SEQ: SCVAL: Sequencer ADC interrupt and restart counter current value register ---------------------------------*/ +typedef struct { + uint32_t RCNT :8; /*!< Current number of ADC restarts by sequencer */ + uint32_t :8; /*!< RESERVED */ + uint32_t ICNT :8; /*!< Current number of ADC requests for interrupt generation */ + uint32_t ICLR :1; /*!< Clear interrupt counter */ +} _ADC_SEQ_SCVAL_bits; + +/* Bit field positions: */ +#define ADC_SEQ_SCVAL_RCNT_Pos 0 /*!< Current number of ADC restarts by sequencer */ +#define ADC_SEQ_SCVAL_ICNT_Pos 16 /*!< Current number of ADC requests for interrupt generation */ +#define ADC_SEQ_SCVAL_ICLR_Pos 24 /*!< Clear interrupt counter */ + +/* Bit field masks: */ +#define ADC_SEQ_SCVAL_RCNT_Msk 0x000000FFUL /*!< Current number of ADC restarts by sequencer */ +#define ADC_SEQ_SCVAL_ICNT_Msk 0x00FF0000UL /*!< Current number of ADC requests for interrupt generation */ +#define ADC_SEQ_SCVAL_ICLR_Msk 0x01000000UL /*!< Clear interrupt counter */ + +/*-- SEQ: SDC: Sequencer digital comparator selection register ------------------------------------------------*/ +typedef struct { + uint32_t DC0 :1; /*!< Enable DC 0 */ + uint32_t DC1 :1; /*!< Enable DC 1 */ + uint32_t DC2 :1; /*!< Enable DC 2 */ + uint32_t DC3 :1; /*!< Enable DC 3 */ +} _ADC_SEQ_SDC_bits; + +/* Bit field positions: */ +#define ADC_SEQ_SDC_DC0_Pos 0 /*!< Enable DC 0 */ +#define ADC_SEQ_SDC_DC1_Pos 1 /*!< Enable DC 1 */ +#define ADC_SEQ_SDC_DC2_Pos 2 /*!< Enable DC 2 */ +#define ADC_SEQ_SDC_DC3_Pos 3 /*!< Enable DC 3 */ + +/* Bit field masks: */ +#define ADC_SEQ_SDC_DC0_Msk 0x00000001UL /*!< Enable DC 0 */ +#define ADC_SEQ_SDC_DC1_Msk 0x00000002UL /*!< Enable DC 1 */ +#define ADC_SEQ_SDC_DC2_Msk 0x00000004UL /*!< Enable DC 2 */ +#define ADC_SEQ_SDC_DC3_Msk 0x00000008UL /*!< Enable DC 3 */ + +/*-- SEQ: SRTMR: Sequencer ADC restart timer register ---------------------------------------------------------*/ +typedef struct { + uint32_t VAL :24; /*!< Sequencer ADC restart timer value */ + uint32_t :7; /*!< RESERVED */ + uint32_t NOWAIT :1; /*!< Timer update with no waiting the end of current seq task */ +} _ADC_SEQ_SRTMR_bits; + +/* Bit field positions: */ +#define ADC_SEQ_SRTMR_VAL_Pos 0 /*!< Sequencer ADC restart timer value */ +#define ADC_SEQ_SRTMR_NOWAIT_Pos 31 /*!< Timer update with no waiting the end of current seq task */ + +/* Bit field masks: */ +#define ADC_SEQ_SRTMR_VAL_Msk 0x00FFFFFFUL /*!< Sequencer ADC restart timer value */ +#define ADC_SEQ_SRTMR_NOWAIT_Msk 0x80000000UL /*!< Timer update with no waiting the end of current seq task */ + +/*-- SEQ: SFLOAD: Sequencer FIFO load status register ---------------------------------------------------------*/ +typedef struct { + uint32_t VAL :6; /*!< Sequencer FIFO current load value */ +} _ADC_SEQ_SFLOAD_bits; + +/* Bit field positions: */ +#define ADC_SEQ_SFLOAD_VAL_Pos 0 /*!< Sequencer FIFO current load value */ + +/* Bit field masks: */ +#define ADC_SEQ_SFLOAD_VAL_Msk 0x0000003FUL /*!< Sequencer FIFO current load value */ + +/*-- SEQ: SFIFO: Sequencer FIFO register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t DATA :12; /*!< AD conversion value */ +} _ADC_SEQ_SFIFO_bits; + +/* Bit field positions: */ +#define ADC_SEQ_SFIFO_DATA_Pos 0 /*!< AD conversion value */ + +/* Bit field masks: */ +#define ADC_SEQ_SFIFO_DATA_Msk 0x00000FFFUL /*!< AD conversion value */ + +/*-- DC: DCTL: Digital comparator control register ------------------------------------------------------------*/ +typedef struct { + uint32_t CIM :2; /*!< DC interrupt generation mode */ + uint32_t CIC :2; /*!< DC interrupt generation compare conditions */ + uint32_t CIE :1; /*!< Enable DC interrupt generation */ + uint32_t :3; /*!< RESERVED */ + uint32_t CTM :2; /*!< DC output trigger mode */ + uint32_t CTC :2; /*!< DC output trigger compare conditions */ + uint32_t CTE :1; /*!< Enable DC output trigger */ + uint32_t :3; /*!< RESERVED */ + uint32_t CHNL :2; /*!< ADC channel selection */ + uint32_t :6; /*!< RESERVED */ + uint32_t SRC :1; /*!< Select data source for comparation: ADC module (0) or sequencer(1) */ +} _ADC_DC_DCTL_bits; + +/* Bit field positions: */ +#define ADC_DC_DCTL_CIM_Pos 0 /*!< DC interrupt generation mode */ +#define ADC_DC_DCTL_CIC_Pos 2 /*!< DC interrupt generation compare conditions */ +#define ADC_DC_DCTL_CIE_Pos 4 /*!< Enable DC interrupt generation */ +#define ADC_DC_DCTL_CTM_Pos 8 /*!< DC output trigger mode */ +#define ADC_DC_DCTL_CTC_Pos 10 /*!< DC output trigger compare conditions */ +#define ADC_DC_DCTL_CTE_Pos 12 /*!< Enable DC output trigger */ +#define ADC_DC_DCTL_CHNL_Pos 16 /*!< ADC channel selection */ +#define ADC_DC_DCTL_SRC_Pos 24 /*!< Select data source for comparation: ADC module (0) or sequencer(1) */ + +/* Bit field masks: */ +#define ADC_DC_DCTL_CIM_Msk 0x00000003UL /*!< DC interrupt generation mode */ +#define ADC_DC_DCTL_CIC_Msk 0x0000000CUL /*!< DC interrupt generation compare conditions */ +#define ADC_DC_DCTL_CIE_Msk 0x00000010UL /*!< Enable DC interrupt generation */ +#define ADC_DC_DCTL_CTM_Msk 0x00000300UL /*!< DC output trigger mode */ +#define ADC_DC_DCTL_CTC_Msk 0x00000C00UL /*!< DC output trigger compare conditions */ +#define ADC_DC_DCTL_CTE_Msk 0x00001000UL /*!< Enable DC output trigger */ +#define ADC_DC_DCTL_CHNL_Msk 0x00030000UL /*!< ADC channel selection */ +#define ADC_DC_DCTL_SRC_Msk 0x01000000UL /*!< Select data source for comparation: ADC module (0) or sequencer(1) */ + +/* Bit field enums: */ +typedef enum { + ADC_DC_DCTL_CIM_Multiple = 0x0UL, /*!< multiple trigger mode */ + ADC_DC_DCTL_CIM_Single = 0x1UL, /*!< single trigger mode */ + ADC_DC_DCTL_CIM_MultipleHyst = 0x2UL, /*!< multiple trigger mode with hysteresis */ + ADC_DC_DCTL_CIM_SingleHyst = 0x3UL, /*!< single trigger mode with hysteresis */ +} ADC_DC_DCTL_CIM_Enum; + +typedef enum { + ADC_DC_DCTL_CIC_Low = 0x0UL, /*!< result lower or equal COMP0 */ + ADC_DC_DCTL_CIC_Window = 0x1UL, /*!< result between COMP0 and COMP1 or equal any of them */ + ADC_DC_DCTL_CIC_High = 0x2UL, /*!< result higher or equal COMP1 */ +} ADC_DC_DCTL_CIC_Enum; + +typedef enum { + ADC_DC_DCTL_CTM_Multiple = 0x0UL, /*!< multiple trigger mode */ + ADC_DC_DCTL_CTM_Single = 0x1UL, /*!< single trigger mode */ + ADC_DC_DCTL_CTM_MultipleHyst = 0x2UL, /*!< multiple trigger mode with hysteresis */ + ADC_DC_DCTL_CTM_SingleHyst = 0x3UL, /*!< single trigger mode with hysteresis */ +} ADC_DC_DCTL_CTM_Enum; + +typedef enum { + ADC_DC_DCTL_CTC_Low = 0x0UL, /*!< result lower or equal COMP0 */ + ADC_DC_DCTL_CTC_Window = 0x1UL, /*!< result between COMP0 and COMP1 or equal any of them */ + ADC_DC_DCTL_CTC_High = 0x2UL, /*!< result higher or equal COMP1 */ +} ADC_DC_DCTL_CTC_Enum; + +/*-- DC: DCMP: Digital comparator range register --------------------------------------------------------------*/ +typedef struct { + uint32_t CMPL :12; /*!< Low threshold compare value */ + uint32_t :4; /*!< RESERVED */ + uint32_t CMPH :12; /*!< High threshold compare value */ +} _ADC_DC_DCMP_bits; + +/* Bit field positions: */ +#define ADC_DC_DCMP_CMPL_Pos 0 /*!< Low threshold compare value */ +#define ADC_DC_DCMP_CMPH_Pos 16 /*!< High threshold compare value */ + +/* Bit field masks: */ +#define ADC_DC_DCMP_CMPL_Msk 0x00000FFFUL /*!< Low threshold compare value */ +#define ADC_DC_DCMP_CMPH_Msk 0x0FFF0000UL /*!< High threshold compare value */ + +/*-- DC: DDATA: Digital comparator last compared data register ------------------------------------------------*/ +typedef struct { + uint32_t VAL :12; /*!< Value of last compared AD conversion result */ +} _ADC_DC_DDATA_bits; + +/* Bit field positions: */ +#define ADC_DC_DDATA_VAL_Pos 0 /*!< Value of last compared AD conversion result */ + +/* Bit field masks: */ +#define ADC_DC_DDATA_VAL_Msk 0x00000FFFUL /*!< Value of last compared AD conversion result */ + +/*-- ACTL: ADC module control register -----------------------------------------------------------------------*/ +typedef struct { + uint32_t ADCEN :1; /*!< Enable ADC module */ + uint32_t ADCRDY :1; /*!< ADC ready for conversions */ +} _ADC_ACTL_bits; + +/* Bit field positions: */ +#define ADC_ACTL_ADCEN_Pos 0 /*!< Enable ADC module */ +#define ADC_ACTL_ADCRDY_Pos 1 /*!< ADC ready for conversions */ + +/* Bit field masks: */ +#define ADC_ACTL_ADCEN_Msk 0x00000001UL /*!< Enable ADC module */ +#define ADC_ACTL_ADCRDY_Msk 0x00000002UL /*!< ADC ready for conversions */ + +/*-- CHCTL: CHCTL: ADC channel control register ---------------------------------------------------------------*/ +typedef struct { + uint32_t OFFTRIM :9; /*!< ADC channel offset trimm value */ + uint32_t :7; /*!< RESERVED */ + uint32_t GAINTRIM :9; /*!< ADC channel gain trimm value */ + uint32_t :3; /*!< RESERVED */ + uint32_t PRIORITY :1; /*!< ADC channel priority level */ +} _ADC_CHCTL_CHCTL_bits; + +/* Bit field positions: */ +#define ADC_CHCTL_CHCTL_OFFTRIM_Pos 0 /*!< ADC channel offset trimm value */ +#define ADC_CHCTL_CHCTL_GAINTRIM_Pos 16 /*!< ADC channel gain trimm value */ +#define ADC_CHCTL_CHCTL_PRIORITY_Pos 28 /*!< ADC channel priority level */ + +/* Bit field masks: */ +#define ADC_CHCTL_CHCTL_OFFTRIM_Msk 0x000001FFUL /*!< ADC channel offset trimm value */ +#define ADC_CHCTL_CHCTL_GAINTRIM_Msk 0x01FF0000UL /*!< ADC channel gain trimm value */ +#define ADC_CHCTL_CHCTL_PRIORITY_Msk 0x10000000UL /*!< ADC channel priority level */ + +//Cluster SEQ: +typedef struct { + union { + /*!< Sequencer request ADC channels selection register */ + __IO uint32_t SRQSEL; /*!< SRQSEL : type used for word access */ + __IO _ADC_SEQ_SRQSEL_bits SRQSEL_bit; /*!< SRQSEL_bit: structure used for bit access */ + }; + __IO uint32_t Reserved0[3]; + union { + /*!< Sequencer request control register */ + __IO uint32_t SRQCTL; /*!< SRQCTL : type used for word access */ + __IO _ADC_SEQ_SRQCTL_bits SRQCTL_bit; /*!< SRQCTL_bit: structure used for bit access */ + }; + union { + /*!< Sequencer request status register */ + __I uint32_t SRQSTAT; /*!< SRQSTAT : type used for word access */ + __I _ADC_SEQ_SRQSTAT_bits SRQSTAT_bit; /*!< SRQSTAT_bit: structure used for bit access */ + }; + union { + /*!< Sequencer DMA control register */ + __IO uint32_t SDMACTL; /*!< SDMACTL : type used for word access */ + __IO _ADC_SEQ_SDMACTL_bits SDMACTL_bit; /*!< SDMACTL_bit: structure used for bit access */ + }; + union { + /*!< Sequencer ADC interrupt and restart counter control register */ + __IO uint32_t SCCTL; /*!< SCCTL : type used for word access */ + __IO _ADC_SEQ_SCCTL_bits SCCTL_bit; /*!< SCCTL_bit: structure used for bit access */ + }; + union { + /*!< Sequencer ADC interrupt and restart counter current value register */ + __O uint32_t SCVAL; /*!< SCVAL : type used for word access */ + __O _ADC_SEQ_SCVAL_bits SCVAL_bit; /*!< SCVAL_bit: structure used for bit access */ + }; + union { + /*!< Sequencer digital comparator selection register */ + __IO uint32_t SDC; /*!< SDC : type used for word access */ + __IO _ADC_SEQ_SDC_bits SDC_bit; /*!< SDC_bit: structure used for bit access */ + }; + union { + /*!< Sequencer ADC restart timer register */ + __IO uint32_t SRTMR; /*!< SRTMR : type used for word access */ + __IO _ADC_SEQ_SRTMR_bits SRTMR_bit; /*!< SRTMR_bit: structure used for bit access */ + }; + union { + /*!< Sequencer FIFO load status register */ + __I uint32_t SFLOAD; /*!< SFLOAD : type used for word access */ + __I _ADC_SEQ_SFLOAD_bits SFLOAD_bit; /*!< SFLOAD_bit: structure used for bit access */ + }; + union { + /*!< Sequencer FIFO register */ + __I uint32_t SFIFO; /*!< SFIFO : type used for word access */ + __I _ADC_SEQ_SFIFO_bits SFIFO_bit; /*!< SFIFO_bit: structure used for bit access */ + }; +} _ADC_SEQ_TypeDef; +//Cluster DC: +typedef struct { + union { + /*!< Digital comparator control register */ + __IO uint32_t DCTL; /*!< DCTL : type used for word access */ + __IO _ADC_DC_DCTL_bits DCTL_bit; /*!< DCTL_bit: structure used for bit access */ + }; + union { + /*!< Digital comparator range register */ + __IO uint32_t DCMP; /*!< DCMP : type used for word access */ + __IO _ADC_DC_DCMP_bits DCMP_bit; /*!< DCMP_bit: structure used for bit access */ + }; + union { + /*!< Digital comparator last compared data register */ + __I uint32_t DDATA; /*!< DDATA : type used for word access */ + __I _ADC_DC_DDATA_bits DDATA_bit; /*!< DDATA_bit: structure used for bit access */ + }; +} _ADC_DC_TypeDef; +//Cluster CHCTL: +typedef struct { + union { + /*!< ADC channel control register */ + __IO uint32_t CHCTL; /*!< CHCTL : type used for word access */ + __IO _ADC_CHCTL_CHCTL_bits CHCTL_bit; /*!< CHCTL_bit: structure used for bit access */ + }; +} _ADC_CHCTL_TypeDef; +typedef struct { + union { /*!< Enable sequencer register */ + __IO uint32_t SEQEN; /*!< SEQEN : type used for word access */ + __IO _ADC_SEQEN_bits SEQEN_bit; /*!< SEQEN_bit: structure used for bit access */ + }; + union { /*!< Sequencer sync register */ + __IO uint32_t SEQSYNC; /*!< SEQSYNC : type used for word access */ + __IO _ADC_SEQSYNC_bits SEQSYNC_bit; /*!< SEQSYNC_bit: structure used for bit access */ + }; + union { /*!< FIFO overflow status register */ + __IO uint32_t FSTAT; /*!< FSTAT : type used for word access */ + __IO _ADC_FSTAT_bits FSTAT_bit; /*!< FSTAT_bit: structure used for bit access */ + }; + union { /*!< Busy status register */ + __I uint32_t BSTAT; /*!< BSTAT : type used for word access */ + __I _ADC_BSTAT_bits BSTAT_bit; /*!< BSTAT_bit: structure used for bit access */ + }; + union { /*!< Digital comparator output trigger status register */ + __IO uint32_t DCTRIG; /*!< DCTRIG : type used for word access */ + __IO _ADC_DCTRIG_bits DCTRIG_bit; /*!< DCTRIG_bit: structure used for bit access */ + }; + union { /*!< Interrupt counter clear control */ + __IO uint32_t CICNT; /*!< CICNT : type used for word access */ + __IO _ADC_CICNT_bits CICNT_bit; /*!< CICNT_bit: structure used for bit access */ + }; + union { /*!< Sequencer start event selection register */ + __IO uint32_t EMUX; /*!< EMUX : type used for word access */ + __IO _ADC_EMUX_bits EMUX_bit; /*!< EMUX_bit: structure used for bit access */ + }; + union { /*!< Raw interrupt status register */ + __I uint32_t RIS; /*!< RIS : type used for word access */ + __I _ADC_RIS_bits RIS_bit; /*!< RIS_bit: structure used for bit access */ + }; + union { /*!< Interrupt mask register */ + __IO uint32_t IM; /*!< IM : type used for word access */ + __IO _ADC_IM_bits IM_bit; /*!< IM_bit: structure used for bit access */ + }; + union { /*!< Masked interrupt status and clear register */ + __I uint32_t MIS; /*!< MIS : type used for word access */ + __I _ADC_MIS_bits MIS_bit; /*!< MIS_bit: structure used for bit access */ + }; + union { /*!< Interrupt clear register */ + __O uint32_t IC; /*!< IC : type used for word access */ + __O _ADC_IC_bits IC_bit; /*!< IC_bit: structure used for bit access */ + }; + __IO uint32_t Reserved0[5]; + _ADC_SEQ_TypeDef SEQ[2]; + __IO uint32_t Reserved1[86]; + _ADC_DC_TypeDef DC[4]; + __IO uint32_t Reserved2[116]; + union { /*!< ADC module control register */ + __IO uint32_t ACTL; /*!< ACTL : type used for word access */ + __IO _ADC_ACTL_bits ACTL_bit; /*!< ACTL_bit: structure used for bit access */ + }; + __IO uint32_t Reserved3[63]; + _ADC_CHCTL_TypeDef CHCTL[4]; +} ADC_TypeDef; + + +/******************************************************************************/ +/* GPIO registers */ +/******************************************************************************/ + +/*-- DATA: Data Input register -------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :16; /*!< Data input */ +} _GPIO_DATA_bits; + +/* Bit field positions: */ +#define GPIO_DATA_VAL_Pos 0 /*!< Data input */ + +/* Bit field masks: */ +#define GPIO_DATA_VAL_Msk 0x0000FFFFUL /*!< Data input */ + +/*-- DATAOUT: Data output register ---------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :16; /*!< Data output */ +} _GPIO_DATAOUT_bits; + +/* Bit field positions: */ +#define GPIO_DATAOUT_VAL_Pos 0 /*!< Data output */ + +/* Bit field masks: */ +#define GPIO_DATAOUT_VAL_Msk 0x0000FFFFUL /*!< Data output */ + +/*-- DATAOUTSET: Data output set bits register ---------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Data output set bit 0 */ + uint32_t PIN1 :1; /*!< Data output set bit 1 */ + uint32_t PIN2 :1; /*!< Data output set bit 2 */ + uint32_t PIN3 :1; /*!< Data output set bit 3 */ + uint32_t PIN4 :1; /*!< Data output set bit 4 */ + uint32_t PIN5 :1; /*!< Data output set bit 5 */ + uint32_t PIN6 :1; /*!< Data output set bit 6 */ + uint32_t PIN7 :1; /*!< Data output set bit 7 */ + uint32_t PIN8 :1; /*!< Data output set bit 8 */ + uint32_t PIN9 :1; /*!< Data output set bit 9 */ + uint32_t PIN10 :1; /*!< Data output set bit 10 */ + uint32_t PIN11 :1; /*!< Data output set bit 11 */ + uint32_t PIN12 :1; /*!< Data output set bit 12 */ + uint32_t PIN13 :1; /*!< Data output set bit 13 */ + uint32_t PIN14 :1; /*!< Data output set bit 14 */ + uint32_t PIN15 :1; /*!< Data output set bit 15 */ +} _GPIO_DATAOUTSET_bits; + +/* Bit field positions: */ +#define GPIO_DATAOUTSET_PIN0_Pos 0 /*!< Data output set bit 0 */ +#define GPIO_DATAOUTSET_PIN1_Pos 1 /*!< Data output set bit 1 */ +#define GPIO_DATAOUTSET_PIN2_Pos 2 /*!< Data output set bit 2 */ +#define GPIO_DATAOUTSET_PIN3_Pos 3 /*!< Data output set bit 3 */ +#define GPIO_DATAOUTSET_PIN4_Pos 4 /*!< Data output set bit 4 */ +#define GPIO_DATAOUTSET_PIN5_Pos 5 /*!< Data output set bit 5 */ +#define GPIO_DATAOUTSET_PIN6_Pos 6 /*!< Data output set bit 6 */ +#define GPIO_DATAOUTSET_PIN7_Pos 7 /*!< Data output set bit 7 */ +#define GPIO_DATAOUTSET_PIN8_Pos 8 /*!< Data output set bit 8 */ +#define GPIO_DATAOUTSET_PIN9_Pos 9 /*!< Data output set bit 9 */ +#define GPIO_DATAOUTSET_PIN10_Pos 10 /*!< Data output set bit 10 */ +#define GPIO_DATAOUTSET_PIN11_Pos 11 /*!< Data output set bit 11 */ +#define GPIO_DATAOUTSET_PIN12_Pos 12 /*!< Data output set bit 12 */ +#define GPIO_DATAOUTSET_PIN13_Pos 13 /*!< Data output set bit 13 */ +#define GPIO_DATAOUTSET_PIN14_Pos 14 /*!< Data output set bit 14 */ +#define GPIO_DATAOUTSET_PIN15_Pos 15 /*!< Data output set bit 15 */ + +/* Bit field masks: */ +#define GPIO_DATAOUTSET_PIN0_Msk 0x00000001UL /*!< Data output set bit 0 */ +#define GPIO_DATAOUTSET_PIN1_Msk 0x00000002UL /*!< Data output set bit 1 */ +#define GPIO_DATAOUTSET_PIN2_Msk 0x00000004UL /*!< Data output set bit 2 */ +#define GPIO_DATAOUTSET_PIN3_Msk 0x00000008UL /*!< Data output set bit 3 */ +#define GPIO_DATAOUTSET_PIN4_Msk 0x00000010UL /*!< Data output set bit 4 */ +#define GPIO_DATAOUTSET_PIN5_Msk 0x00000020UL /*!< Data output set bit 5 */ +#define GPIO_DATAOUTSET_PIN6_Msk 0x00000040UL /*!< Data output set bit 6 */ +#define GPIO_DATAOUTSET_PIN7_Msk 0x00000080UL /*!< Data output set bit 7 */ +#define GPIO_DATAOUTSET_PIN8_Msk 0x00000100UL /*!< Data output set bit 8 */ +#define GPIO_DATAOUTSET_PIN9_Msk 0x00000200UL /*!< Data output set bit 9 */ +#define GPIO_DATAOUTSET_PIN10_Msk 0x00000400UL /*!< Data output set bit 10 */ +#define GPIO_DATAOUTSET_PIN11_Msk 0x00000800UL /*!< Data output set bit 11 */ +#define GPIO_DATAOUTSET_PIN12_Msk 0x00001000UL /*!< Data output set bit 12 */ +#define GPIO_DATAOUTSET_PIN13_Msk 0x00002000UL /*!< Data output set bit 13 */ +#define GPIO_DATAOUTSET_PIN14_Msk 0x00004000UL /*!< Data output set bit 14 */ +#define GPIO_DATAOUTSET_PIN15_Msk 0x00008000UL /*!< Data output set bit 15 */ + +/*-- DATAOUTCLR: Data output clear bits register -------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Data output clear bit 0 */ + uint32_t PIN1 :1; /*!< Data output clear bit 1 */ + uint32_t PIN2 :1; /*!< Data output clear bit 2 */ + uint32_t PIN3 :1; /*!< Data output clear bit 3 */ + uint32_t PIN4 :1; /*!< Data output clear bit 4 */ + uint32_t PIN5 :1; /*!< Data output clear bit 5 */ + uint32_t PIN6 :1; /*!< Data output clear bit 6 */ + uint32_t PIN7 :1; /*!< Data output clear bit 7 */ + uint32_t PIN8 :1; /*!< Data output clear bit 8 */ + uint32_t PIN9 :1; /*!< Data output clear bit 9 */ + uint32_t PIN10 :1; /*!< Data output clear bit 10 */ + uint32_t PIN11 :1; /*!< Data output clear bit 11 */ + uint32_t PIN12 :1; /*!< Data output clear bit 12 */ + uint32_t PIN13 :1; /*!< Data output clear bit 13 */ + uint32_t PIN14 :1; /*!< Data output clear bit 14 */ + uint32_t PIN15 :1; /*!< Data output clear bit 15 */ +} _GPIO_DATAOUTCLR_bits; + +/* Bit field positions: */ +#define GPIO_DATAOUTCLR_PIN0_Pos 0 /*!< Data output clear bit 0 */ +#define GPIO_DATAOUTCLR_PIN1_Pos 1 /*!< Data output clear bit 1 */ +#define GPIO_DATAOUTCLR_PIN2_Pos 2 /*!< Data output clear bit 2 */ +#define GPIO_DATAOUTCLR_PIN3_Pos 3 /*!< Data output clear bit 3 */ +#define GPIO_DATAOUTCLR_PIN4_Pos 4 /*!< Data output clear bit 4 */ +#define GPIO_DATAOUTCLR_PIN5_Pos 5 /*!< Data output clear bit 5 */ +#define GPIO_DATAOUTCLR_PIN6_Pos 6 /*!< Data output clear bit 6 */ +#define GPIO_DATAOUTCLR_PIN7_Pos 7 /*!< Data output clear bit 7 */ +#define GPIO_DATAOUTCLR_PIN8_Pos 8 /*!< Data output clear bit 8 */ +#define GPIO_DATAOUTCLR_PIN9_Pos 9 /*!< Data output clear bit 9 */ +#define GPIO_DATAOUTCLR_PIN10_Pos 10 /*!< Data output clear bit 10 */ +#define GPIO_DATAOUTCLR_PIN11_Pos 11 /*!< Data output clear bit 11 */ +#define GPIO_DATAOUTCLR_PIN12_Pos 12 /*!< Data output clear bit 12 */ +#define GPIO_DATAOUTCLR_PIN13_Pos 13 /*!< Data output clear bit 13 */ +#define GPIO_DATAOUTCLR_PIN14_Pos 14 /*!< Data output clear bit 14 */ +#define GPIO_DATAOUTCLR_PIN15_Pos 15 /*!< Data output clear bit 15 */ + +/* Bit field masks: */ +#define GPIO_DATAOUTCLR_PIN0_Msk 0x00000001UL /*!< Data output clear bit 0 */ +#define GPIO_DATAOUTCLR_PIN1_Msk 0x00000002UL /*!< Data output clear bit 1 */ +#define GPIO_DATAOUTCLR_PIN2_Msk 0x00000004UL /*!< Data output clear bit 2 */ +#define GPIO_DATAOUTCLR_PIN3_Msk 0x00000008UL /*!< Data output clear bit 3 */ +#define GPIO_DATAOUTCLR_PIN4_Msk 0x00000010UL /*!< Data output clear bit 4 */ +#define GPIO_DATAOUTCLR_PIN5_Msk 0x00000020UL /*!< Data output clear bit 5 */ +#define GPIO_DATAOUTCLR_PIN6_Msk 0x00000040UL /*!< Data output clear bit 6 */ +#define GPIO_DATAOUTCLR_PIN7_Msk 0x00000080UL /*!< Data output clear bit 7 */ +#define GPIO_DATAOUTCLR_PIN8_Msk 0x00000100UL /*!< Data output clear bit 8 */ +#define GPIO_DATAOUTCLR_PIN9_Msk 0x00000200UL /*!< Data output clear bit 9 */ +#define GPIO_DATAOUTCLR_PIN10_Msk 0x00000400UL /*!< Data output clear bit 10 */ +#define GPIO_DATAOUTCLR_PIN11_Msk 0x00000800UL /*!< Data output clear bit 11 */ +#define GPIO_DATAOUTCLR_PIN12_Msk 0x00001000UL /*!< Data output clear bit 12 */ +#define GPIO_DATAOUTCLR_PIN13_Msk 0x00002000UL /*!< Data output clear bit 13 */ +#define GPIO_DATAOUTCLR_PIN14_Msk 0x00004000UL /*!< Data output clear bit 14 */ +#define GPIO_DATAOUTCLR_PIN15_Msk 0x00008000UL /*!< Data output clear bit 15 */ + +/*-- DATAOUTTGL: Data output toogle bits register ------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Data output toogle bit 0 */ + uint32_t PIN1 :1; /*!< Data output toogle bit 1 */ + uint32_t PIN2 :1; /*!< Data output toogle bit 2 */ + uint32_t PIN3 :1; /*!< Data output toogle bit 3 */ + uint32_t PIN4 :1; /*!< Data output toogle bit 4 */ + uint32_t PIN5 :1; /*!< Data output toogle bit 5 */ + uint32_t PIN6 :1; /*!< Data output toogle bit 6 */ + uint32_t PIN7 :1; /*!< Data output toogle bit 7 */ + uint32_t PIN8 :1; /*!< Data output toogle bit 8 */ + uint32_t PIN9 :1; /*!< Data output toogle bit 9 */ + uint32_t PIN10 :1; /*!< Data output toogle bit 10 */ + uint32_t PIN11 :1; /*!< Data output toogle bit 11 */ + uint32_t PIN12 :1; /*!< Data output toogle bit 12 */ + uint32_t PIN13 :1; /*!< Data output toogle bit 13 */ + uint32_t PIN14 :1; /*!< Data output toogle bit 14 */ + uint32_t PIN15 :1; /*!< Data output toogle bit 15 */ +} _GPIO_DATAOUTTGL_bits; + +/* Bit field positions: */ +#define GPIO_DATAOUTTGL_PIN0_Pos 0 /*!< Data output toogle bit 0 */ +#define GPIO_DATAOUTTGL_PIN1_Pos 1 /*!< Data output toogle bit 1 */ +#define GPIO_DATAOUTTGL_PIN2_Pos 2 /*!< Data output toogle bit 2 */ +#define GPIO_DATAOUTTGL_PIN3_Pos 3 /*!< Data output toogle bit 3 */ +#define GPIO_DATAOUTTGL_PIN4_Pos 4 /*!< Data output toogle bit 4 */ +#define GPIO_DATAOUTTGL_PIN5_Pos 5 /*!< Data output toogle bit 5 */ +#define GPIO_DATAOUTTGL_PIN6_Pos 6 /*!< Data output toogle bit 6 */ +#define GPIO_DATAOUTTGL_PIN7_Pos 7 /*!< Data output toogle bit 7 */ +#define GPIO_DATAOUTTGL_PIN8_Pos 8 /*!< Data output toogle bit 8 */ +#define GPIO_DATAOUTTGL_PIN9_Pos 9 /*!< Data output toogle bit 9 */ +#define GPIO_DATAOUTTGL_PIN10_Pos 10 /*!< Data output toogle bit 10 */ +#define GPIO_DATAOUTTGL_PIN11_Pos 11 /*!< Data output toogle bit 11 */ +#define GPIO_DATAOUTTGL_PIN12_Pos 12 /*!< Data output toogle bit 12 */ +#define GPIO_DATAOUTTGL_PIN13_Pos 13 /*!< Data output toogle bit 13 */ +#define GPIO_DATAOUTTGL_PIN14_Pos 14 /*!< Data output toogle bit 14 */ +#define GPIO_DATAOUTTGL_PIN15_Pos 15 /*!< Data output toogle bit 15 */ + +/* Bit field masks: */ +#define GPIO_DATAOUTTGL_PIN0_Msk 0x00000001UL /*!< Data output toogle bit 0 */ +#define GPIO_DATAOUTTGL_PIN1_Msk 0x00000002UL /*!< Data output toogle bit 1 */ +#define GPIO_DATAOUTTGL_PIN2_Msk 0x00000004UL /*!< Data output toogle bit 2 */ +#define GPIO_DATAOUTTGL_PIN3_Msk 0x00000008UL /*!< Data output toogle bit 3 */ +#define GPIO_DATAOUTTGL_PIN4_Msk 0x00000010UL /*!< Data output toogle bit 4 */ +#define GPIO_DATAOUTTGL_PIN5_Msk 0x00000020UL /*!< Data output toogle bit 5 */ +#define GPIO_DATAOUTTGL_PIN6_Msk 0x00000040UL /*!< Data output toogle bit 6 */ +#define GPIO_DATAOUTTGL_PIN7_Msk 0x00000080UL /*!< Data output toogle bit 7 */ +#define GPIO_DATAOUTTGL_PIN8_Msk 0x00000100UL /*!< Data output toogle bit 8 */ +#define GPIO_DATAOUTTGL_PIN9_Msk 0x00000200UL /*!< Data output toogle bit 9 */ +#define GPIO_DATAOUTTGL_PIN10_Msk 0x00000400UL /*!< Data output toogle bit 10 */ +#define GPIO_DATAOUTTGL_PIN11_Msk 0x00000800UL /*!< Data output toogle bit 11 */ +#define GPIO_DATAOUTTGL_PIN12_Msk 0x00001000UL /*!< Data output toogle bit 12 */ +#define GPIO_DATAOUTTGL_PIN13_Msk 0x00002000UL /*!< Data output toogle bit 13 */ +#define GPIO_DATAOUTTGL_PIN14_Msk 0x00004000UL /*!< Data output toogle bit 14 */ +#define GPIO_DATAOUTTGL_PIN15_Msk 0x00008000UL /*!< Data output toogle bit 15 */ + +/*-- DENSET: Digital function (PAD) enable register ----------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Digital function (PAD) enable on pin 0 */ + uint32_t PIN1 :1; /*!< Digital function (PAD) enable on pin 1 */ + uint32_t PIN2 :1; /*!< Digital function (PAD) enable on pin 2 */ + uint32_t PIN3 :1; /*!< Digital function (PAD) enable on pin 3 */ + uint32_t PIN4 :1; /*!< Digital function (PAD) enable on pin 4 */ + uint32_t PIN5 :1; /*!< Digital function (PAD) enable on pin 5 */ + uint32_t PIN6 :1; /*!< Digital function (PAD) enable on pin 6 */ + uint32_t PIN7 :1; /*!< Digital function (PAD) enable on pin 7 */ + uint32_t PIN8 :1; /*!< Digital function (PAD) enable on pin 8 */ + uint32_t PIN9 :1; /*!< Digital function (PAD) enable on pin 9 */ + uint32_t PIN10 :1; /*!< Digital function (PAD) enable on pin 10 */ + uint32_t PIN11 :1; /*!< Digital function (PAD) enable on pin 11 */ + uint32_t PIN12 :1; /*!< Digital function (PAD) enable on pin 12 */ + uint32_t PIN13 :1; /*!< Digital function (PAD) enable on pin 13 */ + uint32_t PIN14 :1; /*!< Digital function (PAD) enable on pin 14 */ + uint32_t PIN15 :1; /*!< Digital function (PAD) enable on pin 15 */ +} _GPIO_DENSET_bits; + +/* Bit field positions: */ +#define GPIO_DENSET_PIN0_Pos 0 /*!< Digital function (PAD) enable on pin 0 */ +#define GPIO_DENSET_PIN1_Pos 1 /*!< Digital function (PAD) enable on pin 1 */ +#define GPIO_DENSET_PIN2_Pos 2 /*!< Digital function (PAD) enable on pin 2 */ +#define GPIO_DENSET_PIN3_Pos 3 /*!< Digital function (PAD) enable on pin 3 */ +#define GPIO_DENSET_PIN4_Pos 4 /*!< Digital function (PAD) enable on pin 4 */ +#define GPIO_DENSET_PIN5_Pos 5 /*!< Digital function (PAD) enable on pin 5 */ +#define GPIO_DENSET_PIN6_Pos 6 /*!< Digital function (PAD) enable on pin 6 */ +#define GPIO_DENSET_PIN7_Pos 7 /*!< Digital function (PAD) enable on pin 7 */ +#define GPIO_DENSET_PIN8_Pos 8 /*!< Digital function (PAD) enable on pin 8 */ +#define GPIO_DENSET_PIN9_Pos 9 /*!< Digital function (PAD) enable on pin 9 */ +#define GPIO_DENSET_PIN10_Pos 10 /*!< Digital function (PAD) enable on pin 10 */ +#define GPIO_DENSET_PIN11_Pos 11 /*!< Digital function (PAD) enable on pin 11 */ +#define GPIO_DENSET_PIN12_Pos 12 /*!< Digital function (PAD) enable on pin 12 */ +#define GPIO_DENSET_PIN13_Pos 13 /*!< Digital function (PAD) enable on pin 13 */ +#define GPIO_DENSET_PIN14_Pos 14 /*!< Digital function (PAD) enable on pin 14 */ +#define GPIO_DENSET_PIN15_Pos 15 /*!< Digital function (PAD) enable on pin 15 */ + +/* Bit field masks: */ +#define GPIO_DENSET_PIN0_Msk 0x00000001UL /*!< Digital function (PAD) enable on pin 0 */ +#define GPIO_DENSET_PIN1_Msk 0x00000002UL /*!< Digital function (PAD) enable on pin 1 */ +#define GPIO_DENSET_PIN2_Msk 0x00000004UL /*!< Digital function (PAD) enable on pin 2 */ +#define GPIO_DENSET_PIN3_Msk 0x00000008UL /*!< Digital function (PAD) enable on pin 3 */ +#define GPIO_DENSET_PIN4_Msk 0x00000010UL /*!< Digital function (PAD) enable on pin 4 */ +#define GPIO_DENSET_PIN5_Msk 0x00000020UL /*!< Digital function (PAD) enable on pin 5 */ +#define GPIO_DENSET_PIN6_Msk 0x00000040UL /*!< Digital function (PAD) enable on pin 6 */ +#define GPIO_DENSET_PIN7_Msk 0x00000080UL /*!< Digital function (PAD) enable on pin 7 */ +#define GPIO_DENSET_PIN8_Msk 0x00000100UL /*!< Digital function (PAD) enable on pin 8 */ +#define GPIO_DENSET_PIN9_Msk 0x00000200UL /*!< Digital function (PAD) enable on pin 9 */ +#define GPIO_DENSET_PIN10_Msk 0x00000400UL /*!< Digital function (PAD) enable on pin 10 */ +#define GPIO_DENSET_PIN11_Msk 0x00000800UL /*!< Digital function (PAD) enable on pin 11 */ +#define GPIO_DENSET_PIN12_Msk 0x00001000UL /*!< Digital function (PAD) enable on pin 12 */ +#define GPIO_DENSET_PIN13_Msk 0x00002000UL /*!< Digital function (PAD) enable on pin 13 */ +#define GPIO_DENSET_PIN14_Msk 0x00004000UL /*!< Digital function (PAD) enable on pin 14 */ +#define GPIO_DENSET_PIN15_Msk 0x00008000UL /*!< Digital function (PAD) enable on pin 15 */ + +/*-- DENCLR: Digital function (PAD) disable register ---------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Digital function (PAD) disable on pin 0 */ + uint32_t PIN1 :1; /*!< Digital function (PAD) disable on pin 1 */ + uint32_t PIN2 :1; /*!< Digital function (PAD) disable on pin 2 */ + uint32_t PIN3 :1; /*!< Digital function (PAD) disable on pin 3 */ + uint32_t PIN4 :1; /*!< Digital function (PAD) disable on pin 4 */ + uint32_t PIN5 :1; /*!< Digital function (PAD) disable on pin 5 */ + uint32_t PIN6 :1; /*!< Digital function (PAD) disable on pin 6 */ + uint32_t PIN7 :1; /*!< Digital function (PAD) disable on pin 7 */ + uint32_t PIN8 :1; /*!< Digital function (PAD) disable on pin 8 */ + uint32_t PIN9 :1; /*!< Digital function (PAD) disable on pin 9 */ + uint32_t PIN10 :1; /*!< Digital function (PAD) disable on pin 10 */ + uint32_t PIN11 :1; /*!< Digital function (PAD) disable on pin 11 */ + uint32_t PIN12 :1; /*!< Digital function (PAD) disable on pin 12 */ + uint32_t PIN13 :1; /*!< Digital function (PAD) disable on pin 13 */ + uint32_t PIN14 :1; /*!< Digital function (PAD) disable on pin 14 */ + uint32_t PIN15 :1; /*!< Digital function (PAD) disable on pin 15 */ +} _GPIO_DENCLR_bits; + +/* Bit field positions: */ +#define GPIO_DENCLR_PIN0_Pos 0 /*!< Digital function (PAD) disable on pin 0 */ +#define GPIO_DENCLR_PIN1_Pos 1 /*!< Digital function (PAD) disable on pin 1 */ +#define GPIO_DENCLR_PIN2_Pos 2 /*!< Digital function (PAD) disable on pin 2 */ +#define GPIO_DENCLR_PIN3_Pos 3 /*!< Digital function (PAD) disable on pin 3 */ +#define GPIO_DENCLR_PIN4_Pos 4 /*!< Digital function (PAD) disable on pin 4 */ +#define GPIO_DENCLR_PIN5_Pos 5 /*!< Digital function (PAD) disable on pin 5 */ +#define GPIO_DENCLR_PIN6_Pos 6 /*!< Digital function (PAD) disable on pin 6 */ +#define GPIO_DENCLR_PIN7_Pos 7 /*!< Digital function (PAD) disable on pin 7 */ +#define GPIO_DENCLR_PIN8_Pos 8 /*!< Digital function (PAD) disable on pin 8 */ +#define GPIO_DENCLR_PIN9_Pos 9 /*!< Digital function (PAD) disable on pin 9 */ +#define GPIO_DENCLR_PIN10_Pos 10 /*!< Digital function (PAD) disable on pin 10 */ +#define GPIO_DENCLR_PIN11_Pos 11 /*!< Digital function (PAD) disable on pin 11 */ +#define GPIO_DENCLR_PIN12_Pos 12 /*!< Digital function (PAD) disable on pin 12 */ +#define GPIO_DENCLR_PIN13_Pos 13 /*!< Digital function (PAD) disable on pin 13 */ +#define GPIO_DENCLR_PIN14_Pos 14 /*!< Digital function (PAD) disable on pin 14 */ +#define GPIO_DENCLR_PIN15_Pos 15 /*!< Digital function (PAD) disable on pin 15 */ + +/* Bit field masks: */ +#define GPIO_DENCLR_PIN0_Msk 0x00000001UL /*!< Digital function (PAD) disable on pin 0 */ +#define GPIO_DENCLR_PIN1_Msk 0x00000002UL /*!< Digital function (PAD) disable on pin 1 */ +#define GPIO_DENCLR_PIN2_Msk 0x00000004UL /*!< Digital function (PAD) disable on pin 2 */ +#define GPIO_DENCLR_PIN3_Msk 0x00000008UL /*!< Digital function (PAD) disable on pin 3 */ +#define GPIO_DENCLR_PIN4_Msk 0x00000010UL /*!< Digital function (PAD) disable on pin 4 */ +#define GPIO_DENCLR_PIN5_Msk 0x00000020UL /*!< Digital function (PAD) disable on pin 5 */ +#define GPIO_DENCLR_PIN6_Msk 0x00000040UL /*!< Digital function (PAD) disable on pin 6 */ +#define GPIO_DENCLR_PIN7_Msk 0x00000080UL /*!< Digital function (PAD) disable on pin 7 */ +#define GPIO_DENCLR_PIN8_Msk 0x00000100UL /*!< Digital function (PAD) disable on pin 8 */ +#define GPIO_DENCLR_PIN9_Msk 0x00000200UL /*!< Digital function (PAD) disable on pin 9 */ +#define GPIO_DENCLR_PIN10_Msk 0x00000400UL /*!< Digital function (PAD) disable on pin 10 */ +#define GPIO_DENCLR_PIN11_Msk 0x00000800UL /*!< Digital function (PAD) disable on pin 11 */ +#define GPIO_DENCLR_PIN12_Msk 0x00001000UL /*!< Digital function (PAD) disable on pin 12 */ +#define GPIO_DENCLR_PIN13_Msk 0x00002000UL /*!< Digital function (PAD) disable on pin 13 */ +#define GPIO_DENCLR_PIN14_Msk 0x00004000UL /*!< Digital function (PAD) disable on pin 14 */ +#define GPIO_DENCLR_PIN15_Msk 0x00008000UL /*!< Digital function (PAD) disable on pin 15 */ + +/*-- INMODE: Select input mode register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :2; /*!< Select input mode for pin 0 */ + uint32_t PIN1 :2; /*!< Select input mode for pin 1 */ + uint32_t PIN2 :2; /*!< Select input mode for pin 2 */ + uint32_t PIN3 :2; /*!< Select input mode for pin 3 */ + uint32_t PIN4 :2; /*!< Select input mode for pin 4 */ + uint32_t PIN5 :2; /*!< Select input mode for pin 5 */ + uint32_t PIN6 :2; /*!< Select input mode for pin 6 */ + uint32_t PIN7 :2; /*!< Select input mode for pin 7 */ + uint32_t PIN8 :2; /*!< Select input mode for pin 8 */ + uint32_t PIN9 :2; /*!< Select input mode for pin 9 */ + uint32_t PIN10 :2; /*!< Select input mode for pin 10 */ + uint32_t PIN11 :2; /*!< Select input mode for pin 11 */ + uint32_t PIN12 :2; /*!< Select input mode for pin 12 */ + uint32_t PIN13 :2; /*!< Select input mode for pin 13 */ + uint32_t PIN14 :2; /*!< Select input mode for pin 14 */ + uint32_t PIN15 :2; /*!< Select input mode for pin 15 */ +} _GPIO_INMODE_bits; + +/* Bit field positions: */ +#define GPIO_INMODE_PIN0_Pos 0 /*!< Select input mode for pin 0 */ +#define GPIO_INMODE_PIN1_Pos 2 /*!< Select input mode for pin 1 */ +#define GPIO_INMODE_PIN2_Pos 4 /*!< Select input mode for pin 2 */ +#define GPIO_INMODE_PIN3_Pos 6 /*!< Select input mode for pin 3 */ +#define GPIO_INMODE_PIN4_Pos 8 /*!< Select input mode for pin 4 */ +#define GPIO_INMODE_PIN5_Pos 10 /*!< Select input mode for pin 5 */ +#define GPIO_INMODE_PIN6_Pos 12 /*!< Select input mode for pin 6 */ +#define GPIO_INMODE_PIN7_Pos 14 /*!< Select input mode for pin 7 */ +#define GPIO_INMODE_PIN8_Pos 16 /*!< Select input mode for pin 8 */ +#define GPIO_INMODE_PIN9_Pos 18 /*!< Select input mode for pin 9 */ +#define GPIO_INMODE_PIN10_Pos 20 /*!< Select input mode for pin 10 */ +#define GPIO_INMODE_PIN11_Pos 22 /*!< Select input mode for pin 11 */ +#define GPIO_INMODE_PIN12_Pos 24 /*!< Select input mode for pin 12 */ +#define GPIO_INMODE_PIN13_Pos 26 /*!< Select input mode for pin 13 */ +#define GPIO_INMODE_PIN14_Pos 28 /*!< Select input mode for pin 14 */ +#define GPIO_INMODE_PIN15_Pos 30 /*!< Select input mode for pin 15 */ + +/* Bit field masks: */ +#define GPIO_INMODE_PIN0_Msk 0x00000003UL /*!< Select input mode for pin 0 */ +#define GPIO_INMODE_PIN1_Msk 0x0000000CUL /*!< Select input mode for pin 1 */ +#define GPIO_INMODE_PIN2_Msk 0x00000030UL /*!< Select input mode for pin 2 */ +#define GPIO_INMODE_PIN3_Msk 0x000000C0UL /*!< Select input mode for pin 3 */ +#define GPIO_INMODE_PIN4_Msk 0x00000300UL /*!< Select input mode for pin 4 */ +#define GPIO_INMODE_PIN5_Msk 0x00000C00UL /*!< Select input mode for pin 5 */ +#define GPIO_INMODE_PIN6_Msk 0x00003000UL /*!< Select input mode for pin 6 */ +#define GPIO_INMODE_PIN7_Msk 0x0000C000UL /*!< Select input mode for pin 7 */ +#define GPIO_INMODE_PIN8_Msk 0x00030000UL /*!< Select input mode for pin 8 */ +#define GPIO_INMODE_PIN9_Msk 0x000C0000UL /*!< Select input mode for pin 9 */ +#define GPIO_INMODE_PIN10_Msk 0x00300000UL /*!< Select input mode for pin 10 */ +#define GPIO_INMODE_PIN11_Msk 0x00C00000UL /*!< Select input mode for pin 11 */ +#define GPIO_INMODE_PIN12_Msk 0x03000000UL /*!< Select input mode for pin 12 */ +#define GPIO_INMODE_PIN13_Msk 0x0C000000UL /*!< Select input mode for pin 13 */ +#define GPIO_INMODE_PIN14_Msk 0x30000000UL /*!< Select input mode for pin 14 */ +#define GPIO_INMODE_PIN15_Msk 0xC0000000UL /*!< Select input mode for pin 15 */ + +/* Bit field enums: */ +typedef enum { + GPIO_INMODE_PIN0_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN0_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN0_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN0_Enum; + +typedef enum { + GPIO_INMODE_PIN1_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN1_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN1_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN1_Enum; + +typedef enum { + GPIO_INMODE_PIN2_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN2_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN2_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN2_Enum; + +typedef enum { + GPIO_INMODE_PIN3_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN3_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN3_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN3_Enum; + +typedef enum { + GPIO_INMODE_PIN4_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN4_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN4_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN4_Enum; + +typedef enum { + GPIO_INMODE_PIN5_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN5_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN5_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN5_Enum; + +typedef enum { + GPIO_INMODE_PIN6_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN6_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN6_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN6_Enum; + +typedef enum { + GPIO_INMODE_PIN7_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN7_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN7_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN7_Enum; + +typedef enum { + GPIO_INMODE_PIN8_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN8_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN8_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN8_Enum; + +typedef enum { + GPIO_INMODE_PIN9_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN9_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN9_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN9_Enum; + +typedef enum { + GPIO_INMODE_PIN10_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN10_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN10_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN10_Enum; + +typedef enum { + GPIO_INMODE_PIN11_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN11_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN11_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN11_Enum; + +typedef enum { + GPIO_INMODE_PIN12_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN12_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN12_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN12_Enum; + +typedef enum { + GPIO_INMODE_PIN13_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN13_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN13_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN13_Enum; + +typedef enum { + GPIO_INMODE_PIN14_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN14_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN14_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN14_Enum; + +typedef enum { + GPIO_INMODE_PIN15_Schmitt = 0x0UL, /*!< Scmitt buffer */ + GPIO_INMODE_PIN15_CMOS = 0x1UL, /*!< CMOS buffer */ + GPIO_INMODE_PIN15_Disable = 0x3UL, /*!< Input buffer disabled */ +} GPIO_INMODE_PIN15_Enum; + +/*-- PULLMODE: Select pull mode register ---------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :2; /*!< Select pull mode for pin 0 */ + uint32_t PIN1 :2; /*!< Select pull mode for pin 1 */ + uint32_t PIN2 :2; /*!< Select pull mode for pin 2 */ + uint32_t PIN3 :2; /*!< Select pull mode for pin 3 */ + uint32_t PIN4 :2; /*!< Select pull mode for pin 4 */ + uint32_t PIN5 :2; /*!< Select pull mode for pin 5 */ + uint32_t PIN6 :2; /*!< Select pull mode for pin 6 */ + uint32_t PIN7 :2; /*!< Select pull mode for pin 7 */ + uint32_t PIN8 :2; /*!< Select pull mode for pin 8 */ + uint32_t PIN9 :2; /*!< Select pull mode for pin 9 */ + uint32_t PIN10 :2; /*!< Select pull mode for pin 10 */ + uint32_t PIN11 :2; /*!< Select pull mode for pin 11 */ + uint32_t PIN12 :2; /*!< Select pull mode for pin 12 */ + uint32_t PIN13 :2; /*!< Select pull mode for pin 13 */ + uint32_t PIN14 :2; /*!< Select pull mode for pin 14 */ + uint32_t PIN15 :2; /*!< Select pull mode for pin 15 */ +} _GPIO_PULLMODE_bits; + +/* Bit field positions: */ +#define GPIO_PULLMODE_PIN0_Pos 0 /*!< Select pull mode for pin 0 */ +#define GPIO_PULLMODE_PIN1_Pos 2 /*!< Select pull mode for pin 1 */ +#define GPIO_PULLMODE_PIN2_Pos 4 /*!< Select pull mode for pin 2 */ +#define GPIO_PULLMODE_PIN3_Pos 6 /*!< Select pull mode for pin 3 */ +#define GPIO_PULLMODE_PIN4_Pos 8 /*!< Select pull mode for pin 4 */ +#define GPIO_PULLMODE_PIN5_Pos 10 /*!< Select pull mode for pin 5 */ +#define GPIO_PULLMODE_PIN6_Pos 12 /*!< Select pull mode for pin 6 */ +#define GPIO_PULLMODE_PIN7_Pos 14 /*!< Select pull mode for pin 7 */ +#define GPIO_PULLMODE_PIN8_Pos 16 /*!< Select pull mode for pin 8 */ +#define GPIO_PULLMODE_PIN9_Pos 18 /*!< Select pull mode for pin 9 */ +#define GPIO_PULLMODE_PIN10_Pos 20 /*!< Select pull mode for pin 10 */ +#define GPIO_PULLMODE_PIN11_Pos 22 /*!< Select pull mode for pin 11 */ +#define GPIO_PULLMODE_PIN12_Pos 24 /*!< Select pull mode for pin 12 */ +#define GPIO_PULLMODE_PIN13_Pos 26 /*!< Select pull mode for pin 13 */ +#define GPIO_PULLMODE_PIN14_Pos 28 /*!< Select pull mode for pin 14 */ +#define GPIO_PULLMODE_PIN15_Pos 30 /*!< Select pull mode for pin 15 */ + +/* Bit field masks: */ +#define GPIO_PULLMODE_PIN0_Msk 0x00000003UL /*!< Select pull mode for pin 0 */ +#define GPIO_PULLMODE_PIN1_Msk 0x0000000CUL /*!< Select pull mode for pin 1 */ +#define GPIO_PULLMODE_PIN2_Msk 0x00000030UL /*!< Select pull mode for pin 2 */ +#define GPIO_PULLMODE_PIN3_Msk 0x000000C0UL /*!< Select pull mode for pin 3 */ +#define GPIO_PULLMODE_PIN4_Msk 0x00000300UL /*!< Select pull mode for pin 4 */ +#define GPIO_PULLMODE_PIN5_Msk 0x00000C00UL /*!< Select pull mode for pin 5 */ +#define GPIO_PULLMODE_PIN6_Msk 0x00003000UL /*!< Select pull mode for pin 6 */ +#define GPIO_PULLMODE_PIN7_Msk 0x0000C000UL /*!< Select pull mode for pin 7 */ +#define GPIO_PULLMODE_PIN8_Msk 0x00030000UL /*!< Select pull mode for pin 8 */ +#define GPIO_PULLMODE_PIN9_Msk 0x000C0000UL /*!< Select pull mode for pin 9 */ +#define GPIO_PULLMODE_PIN10_Msk 0x00300000UL /*!< Select pull mode for pin 10 */ +#define GPIO_PULLMODE_PIN11_Msk 0x00C00000UL /*!< Select pull mode for pin 11 */ +#define GPIO_PULLMODE_PIN12_Msk 0x03000000UL /*!< Select pull mode for pin 12 */ +#define GPIO_PULLMODE_PIN13_Msk 0x0C000000UL /*!< Select pull mode for pin 13 */ +#define GPIO_PULLMODE_PIN14_Msk 0x30000000UL /*!< Select pull mode for pin 14 */ +#define GPIO_PULLMODE_PIN15_Msk 0xC0000000UL /*!< Select pull mode for pin 15 */ + +/* Bit field enums: */ +typedef enum { + GPIO_PULLMODE_PIN0_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN0_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN0_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN0_Enum; + +typedef enum { + GPIO_PULLMODE_PIN1_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN1_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN1_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN1_Enum; + +typedef enum { + GPIO_PULLMODE_PIN2_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN2_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN2_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN2_Enum; + +typedef enum { + GPIO_PULLMODE_PIN3_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN3_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN3_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN3_Enum; + +typedef enum { + GPIO_PULLMODE_PIN4_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN4_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN4_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN4_Enum; + +typedef enum { + GPIO_PULLMODE_PIN5_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN5_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN5_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN5_Enum; + +typedef enum { + GPIO_PULLMODE_PIN6_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN6_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN6_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN6_Enum; + +typedef enum { + GPIO_PULLMODE_PIN7_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN7_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN7_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN7_Enum; + +typedef enum { + GPIO_PULLMODE_PIN8_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN8_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN8_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN8_Enum; + +typedef enum { + GPIO_PULLMODE_PIN9_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN9_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN9_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN9_Enum; + +typedef enum { + GPIO_PULLMODE_PIN10_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN10_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN10_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN10_Enum; + +typedef enum { + GPIO_PULLMODE_PIN11_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN11_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN11_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN11_Enum; + +typedef enum { + GPIO_PULLMODE_PIN12_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN12_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN12_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN12_Enum; + +typedef enum { + GPIO_PULLMODE_PIN13_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN13_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN13_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN13_Enum; + +typedef enum { + GPIO_PULLMODE_PIN14_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN14_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN14_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN14_Enum; + +typedef enum { + GPIO_PULLMODE_PIN15_Disable = 0x0UL, /*!< Pull disabled */ + GPIO_PULLMODE_PIN15_PU = 0x1UL, /*!< Pull-up */ + GPIO_PULLMODE_PIN15_PD = 0x2UL, /*!< Pull-down */ +} GPIO_PULLMODE_PIN15_Enum; + +/*-- OUTMODE: Select output mode register --------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :2; /*!< Select output mode for pin 0 */ + uint32_t PIN1 :2; /*!< Select output mode for pin 1 */ + uint32_t PIN2 :2; /*!< Select output mode for pin 2 */ + uint32_t PIN3 :2; /*!< Select output mode for pin 3 */ + uint32_t PIN4 :2; /*!< Select output mode for pin 4 */ + uint32_t PIN5 :2; /*!< Select output mode for pin 5 */ + uint32_t PIN6 :2; /*!< Select output mode for pin 6 */ + uint32_t PIN7 :2; /*!< Select output mode for pin 7 */ + uint32_t PIN8 :2; /*!< Select output mode for pin 8 */ + uint32_t PIN9 :2; /*!< Select output mode for pin 9 */ + uint32_t PIN10 :2; /*!< Select output mode for pin 10 */ + uint32_t PIN11 :2; /*!< Select output mode for pin 11 */ + uint32_t PIN12 :2; /*!< Select output mode for pin 12 */ + uint32_t PIN13 :2; /*!< Select output mode for pin 13 */ + uint32_t PIN14 :2; /*!< Select output mode for pin 14 */ + uint32_t PIN15 :2; /*!< Select output mode for pin 15 */ +} _GPIO_OUTMODE_bits; + +/* Bit field positions: */ +#define GPIO_OUTMODE_PIN0_Pos 0 /*!< Select output mode for pin 0 */ +#define GPIO_OUTMODE_PIN1_Pos 2 /*!< Select output mode for pin 1 */ +#define GPIO_OUTMODE_PIN2_Pos 4 /*!< Select output mode for pin 2 */ +#define GPIO_OUTMODE_PIN3_Pos 6 /*!< Select output mode for pin 3 */ +#define GPIO_OUTMODE_PIN4_Pos 8 /*!< Select output mode for pin 4 */ +#define GPIO_OUTMODE_PIN5_Pos 10 /*!< Select output mode for pin 5 */ +#define GPIO_OUTMODE_PIN6_Pos 12 /*!< Select output mode for pin 6 */ +#define GPIO_OUTMODE_PIN7_Pos 14 /*!< Select output mode for pin 7 */ +#define GPIO_OUTMODE_PIN8_Pos 16 /*!< Select output mode for pin 8 */ +#define GPIO_OUTMODE_PIN9_Pos 18 /*!< Select output mode for pin 9 */ +#define GPIO_OUTMODE_PIN10_Pos 20 /*!< Select output mode for pin 10 */ +#define GPIO_OUTMODE_PIN11_Pos 22 /*!< Select output mode for pin 11 */ +#define GPIO_OUTMODE_PIN12_Pos 24 /*!< Select output mode for pin 12 */ +#define GPIO_OUTMODE_PIN13_Pos 26 /*!< Select output mode for pin 13 */ +#define GPIO_OUTMODE_PIN14_Pos 28 /*!< Select output mode for pin 14 */ +#define GPIO_OUTMODE_PIN15_Pos 30 /*!< Select output mode for pin 15 */ + +/* Bit field masks: */ +#define GPIO_OUTMODE_PIN0_Msk 0x00000003UL /*!< Select output mode for pin 0 */ +#define GPIO_OUTMODE_PIN1_Msk 0x0000000CUL /*!< Select output mode for pin 1 */ +#define GPIO_OUTMODE_PIN2_Msk 0x00000030UL /*!< Select output mode for pin 2 */ +#define GPIO_OUTMODE_PIN3_Msk 0x000000C0UL /*!< Select output mode for pin 3 */ +#define GPIO_OUTMODE_PIN4_Msk 0x00000300UL /*!< Select output mode for pin 4 */ +#define GPIO_OUTMODE_PIN5_Msk 0x00000C00UL /*!< Select output mode for pin 5 */ +#define GPIO_OUTMODE_PIN6_Msk 0x00003000UL /*!< Select output mode for pin 6 */ +#define GPIO_OUTMODE_PIN7_Msk 0x0000C000UL /*!< Select output mode for pin 7 */ +#define GPIO_OUTMODE_PIN8_Msk 0x00030000UL /*!< Select output mode for pin 8 */ +#define GPIO_OUTMODE_PIN9_Msk 0x000C0000UL /*!< Select output mode for pin 9 */ +#define GPIO_OUTMODE_PIN10_Msk 0x00300000UL /*!< Select output mode for pin 10 */ +#define GPIO_OUTMODE_PIN11_Msk 0x00C00000UL /*!< Select output mode for pin 11 */ +#define GPIO_OUTMODE_PIN12_Msk 0x03000000UL /*!< Select output mode for pin 12 */ +#define GPIO_OUTMODE_PIN13_Msk 0x0C000000UL /*!< Select output mode for pin 13 */ +#define GPIO_OUTMODE_PIN14_Msk 0x30000000UL /*!< Select output mode for pin 14 */ +#define GPIO_OUTMODE_PIN15_Msk 0xC0000000UL /*!< Select output mode for pin 15 */ + +/* Bit field enums: */ +typedef enum { + GPIO_OUTMODE_PIN0_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN0_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN0_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN0_Enum; + +typedef enum { + GPIO_OUTMODE_PIN1_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN1_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN1_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN1_Enum; + +typedef enum { + GPIO_OUTMODE_PIN2_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN2_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN2_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN2_Enum; + +typedef enum { + GPIO_OUTMODE_PIN3_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN3_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN3_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN3_Enum; + +typedef enum { + GPIO_OUTMODE_PIN4_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN4_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN4_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN4_Enum; + +typedef enum { + GPIO_OUTMODE_PIN5_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN5_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN5_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN5_Enum; + +typedef enum { + GPIO_OUTMODE_PIN6_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN6_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN6_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN6_Enum; + +typedef enum { + GPIO_OUTMODE_PIN7_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN7_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN7_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN7_Enum; + +typedef enum { + GPIO_OUTMODE_PIN8_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN8_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN8_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN8_Enum; + +typedef enum { + GPIO_OUTMODE_PIN9_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN9_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN9_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN9_Enum; + +typedef enum { + GPIO_OUTMODE_PIN10_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN10_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN10_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN10_Enum; + +typedef enum { + GPIO_OUTMODE_PIN11_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN11_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN11_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN11_Enum; + +typedef enum { + GPIO_OUTMODE_PIN12_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN12_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN12_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN12_Enum; + +typedef enum { + GPIO_OUTMODE_PIN13_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN13_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN13_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN13_Enum; + +typedef enum { + GPIO_OUTMODE_PIN14_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN14_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN14_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN14_Enum; + +typedef enum { + GPIO_OUTMODE_PIN15_PP = 0x0UL, /*!< Push-pull output */ + GPIO_OUTMODE_PIN15_OD = 0x1UL, /*!< Open drain output */ + GPIO_OUTMODE_PIN15_OS = 0x2UL, /*!< Open source output */ +} GPIO_OUTMODE_PIN15_Enum; + +/*-- DRIVEMODE: Select drive mode register -------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :2; /*!< Select drive mode for pin 0 */ + uint32_t PIN1 :2; /*!< Select drive mode for pin 1 */ + uint32_t PIN2 :2; /*!< Select drive mode for pin 2 */ + uint32_t PIN3 :2; /*!< Select drive mode for pin 3 */ + uint32_t PIN4 :2; /*!< Select drive mode for pin 4 */ + uint32_t PIN5 :2; /*!< Select drive mode for pin 5 */ + uint32_t PIN6 :2; /*!< Select drive mode for pin 6 */ + uint32_t PIN7 :2; /*!< Select drive mode for pin 7 */ + uint32_t PIN8 :2; /*!< Select drive mode for pin 8 */ + uint32_t PIN9 :2; /*!< Select drive mode for pin 9 */ + uint32_t PIN10 :2; /*!< Select drive mode for pin 10 */ + uint32_t PIN11 :2; /*!< Select drive mode for pin 11 */ + uint32_t PIN12 :2; /*!< Select drive mode for pin 12 */ + uint32_t PIN13 :2; /*!< Select drive mode for pin 13 */ + uint32_t PIN14 :2; /*!< Select drive mode for pin 14 */ + uint32_t PIN15 :2; /*!< Select drive mode for pin 15 */ +} _GPIO_DRIVEMODE_bits; + +/* Bit field positions: */ +#define GPIO_DRIVEMODE_PIN0_Pos 0 /*!< Select drive mode for pin 0 */ +#define GPIO_DRIVEMODE_PIN1_Pos 2 /*!< Select drive mode for pin 1 */ +#define GPIO_DRIVEMODE_PIN2_Pos 4 /*!< Select drive mode for pin 2 */ +#define GPIO_DRIVEMODE_PIN3_Pos 6 /*!< Select drive mode for pin 3 */ +#define GPIO_DRIVEMODE_PIN4_Pos 8 /*!< Select drive mode for pin 4 */ +#define GPIO_DRIVEMODE_PIN5_Pos 10 /*!< Select drive mode for pin 5 */ +#define GPIO_DRIVEMODE_PIN6_Pos 12 /*!< Select drive mode for pin 6 */ +#define GPIO_DRIVEMODE_PIN7_Pos 14 /*!< Select drive mode for pin 7 */ +#define GPIO_DRIVEMODE_PIN8_Pos 16 /*!< Select drive mode for pin 8 */ +#define GPIO_DRIVEMODE_PIN9_Pos 18 /*!< Select drive mode for pin 9 */ +#define GPIO_DRIVEMODE_PIN10_Pos 20 /*!< Select drive mode for pin 10 */ +#define GPIO_DRIVEMODE_PIN11_Pos 22 /*!< Select drive mode for pin 11 */ +#define GPIO_DRIVEMODE_PIN12_Pos 24 /*!< Select drive mode for pin 12 */ +#define GPIO_DRIVEMODE_PIN13_Pos 26 /*!< Select drive mode for pin 13 */ +#define GPIO_DRIVEMODE_PIN14_Pos 28 /*!< Select drive mode for pin 14 */ +#define GPIO_DRIVEMODE_PIN15_Pos 30 /*!< Select drive mode for pin 15 */ + +/* Bit field masks: */ +#define GPIO_DRIVEMODE_PIN0_Msk 0x00000003UL /*!< Select drive mode for pin 0 */ +#define GPIO_DRIVEMODE_PIN1_Msk 0x0000000CUL /*!< Select drive mode for pin 1 */ +#define GPIO_DRIVEMODE_PIN2_Msk 0x00000030UL /*!< Select drive mode for pin 2 */ +#define GPIO_DRIVEMODE_PIN3_Msk 0x000000C0UL /*!< Select drive mode for pin 3 */ +#define GPIO_DRIVEMODE_PIN4_Msk 0x00000300UL /*!< Select drive mode for pin 4 */ +#define GPIO_DRIVEMODE_PIN5_Msk 0x00000C00UL /*!< Select drive mode for pin 5 */ +#define GPIO_DRIVEMODE_PIN6_Msk 0x00003000UL /*!< Select drive mode for pin 6 */ +#define GPIO_DRIVEMODE_PIN7_Msk 0x0000C000UL /*!< Select drive mode for pin 7 */ +#define GPIO_DRIVEMODE_PIN8_Msk 0x00030000UL /*!< Select drive mode for pin 8 */ +#define GPIO_DRIVEMODE_PIN9_Msk 0x000C0000UL /*!< Select drive mode for pin 9 */ +#define GPIO_DRIVEMODE_PIN10_Msk 0x00300000UL /*!< Select drive mode for pin 10 */ +#define GPIO_DRIVEMODE_PIN11_Msk 0x00C00000UL /*!< Select drive mode for pin 11 */ +#define GPIO_DRIVEMODE_PIN12_Msk 0x03000000UL /*!< Select drive mode for pin 12 */ +#define GPIO_DRIVEMODE_PIN13_Msk 0x0C000000UL /*!< Select drive mode for pin 13 */ +#define GPIO_DRIVEMODE_PIN14_Msk 0x30000000UL /*!< Select drive mode for pin 14 */ +#define GPIO_DRIVEMODE_PIN15_Msk 0xC0000000UL /*!< Select drive mode for pin 15 */ + +/* Bit field enums: */ +typedef enum { + GPIO_DRIVEMODE_PIN0_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN0_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN0_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN0_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN0_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN1_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN1_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN1_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN1_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN1_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN2_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN2_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN2_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN2_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN2_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN3_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN3_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN3_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN3_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN3_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN4_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN4_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN4_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN4_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN4_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN5_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN5_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN5_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN5_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN5_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN6_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN6_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN6_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN6_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN6_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN7_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN7_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN7_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN7_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN7_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN8_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN8_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN8_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN8_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN8_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN9_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN9_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN9_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN9_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN9_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN10_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN10_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN10_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN10_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN10_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN11_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN11_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN11_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN11_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN11_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN12_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN12_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN12_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN12_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN12_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN13_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN13_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN13_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN13_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN13_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN14_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN14_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN14_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN14_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN14_Enum; + +typedef enum { + GPIO_DRIVEMODE_PIN15_HF = 0x0UL, /*!< High strength and Fast rate */ + GPIO_DRIVEMODE_PIN15_HS = 0x1UL, /*!< High strength and Slow rate */ + GPIO_DRIVEMODE_PIN15_LF = 0x2UL, /*!< Low strength and Fast rate */ + GPIO_DRIVEMODE_PIN15_LS = 0x3UL, /*!< Low strength and Slow rate */ +} GPIO_DRIVEMODE_PIN15_Enum; + +/*-- OUTENSET: Output enable register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Output enable for pin 0 */ + uint32_t PIN1 :1; /*!< Output enable for pin 1 */ + uint32_t PIN2 :1; /*!< Output enable for pin 2 */ + uint32_t PIN3 :1; /*!< Output enable for pin 3 */ + uint32_t PIN4 :1; /*!< Output enable for pin 4 */ + uint32_t PIN5 :1; /*!< Output enable for pin 5 */ + uint32_t PIN6 :1; /*!< Output enable for pin 6 */ + uint32_t PIN7 :1; /*!< Output enable for pin 7 */ + uint32_t PIN8 :1; /*!< Output enable for pin 8 */ + uint32_t PIN9 :1; /*!< Output enable for pin 9 */ + uint32_t PIN10 :1; /*!< Output enable for pin 10 */ + uint32_t PIN11 :1; /*!< Output enable for pin 11 */ + uint32_t PIN12 :1; /*!< Output enable for pin 12 */ + uint32_t PIN13 :1; /*!< Output enable for pin 13 */ + uint32_t PIN14 :1; /*!< Output enable for pin 14 */ + uint32_t PIN15 :1; /*!< Output enable for pin 15 */ +} _GPIO_OUTENSET_bits; + +/* Bit field positions: */ +#define GPIO_OUTENSET_PIN0_Pos 0 /*!< Output enable for pin 0 */ +#define GPIO_OUTENSET_PIN1_Pos 1 /*!< Output enable for pin 1 */ +#define GPIO_OUTENSET_PIN2_Pos 2 /*!< Output enable for pin 2 */ +#define GPIO_OUTENSET_PIN3_Pos 3 /*!< Output enable for pin 3 */ +#define GPIO_OUTENSET_PIN4_Pos 4 /*!< Output enable for pin 4 */ +#define GPIO_OUTENSET_PIN5_Pos 5 /*!< Output enable for pin 5 */ +#define GPIO_OUTENSET_PIN6_Pos 6 /*!< Output enable for pin 6 */ +#define GPIO_OUTENSET_PIN7_Pos 7 /*!< Output enable for pin 7 */ +#define GPIO_OUTENSET_PIN8_Pos 8 /*!< Output enable for pin 8 */ +#define GPIO_OUTENSET_PIN9_Pos 9 /*!< Output enable for pin 9 */ +#define GPIO_OUTENSET_PIN10_Pos 10 /*!< Output enable for pin 10 */ +#define GPIO_OUTENSET_PIN11_Pos 11 /*!< Output enable for pin 11 */ +#define GPIO_OUTENSET_PIN12_Pos 12 /*!< Output enable for pin 12 */ +#define GPIO_OUTENSET_PIN13_Pos 13 /*!< Output enable for pin 13 */ +#define GPIO_OUTENSET_PIN14_Pos 14 /*!< Output enable for pin 14 */ +#define GPIO_OUTENSET_PIN15_Pos 15 /*!< Output enable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_OUTENSET_PIN0_Msk 0x00000001UL /*!< Output enable for pin 0 */ +#define GPIO_OUTENSET_PIN1_Msk 0x00000002UL /*!< Output enable for pin 1 */ +#define GPIO_OUTENSET_PIN2_Msk 0x00000004UL /*!< Output enable for pin 2 */ +#define GPIO_OUTENSET_PIN3_Msk 0x00000008UL /*!< Output enable for pin 3 */ +#define GPIO_OUTENSET_PIN4_Msk 0x00000010UL /*!< Output enable for pin 4 */ +#define GPIO_OUTENSET_PIN5_Msk 0x00000020UL /*!< Output enable for pin 5 */ +#define GPIO_OUTENSET_PIN6_Msk 0x00000040UL /*!< Output enable for pin 6 */ +#define GPIO_OUTENSET_PIN7_Msk 0x00000080UL /*!< Output enable for pin 7 */ +#define GPIO_OUTENSET_PIN8_Msk 0x00000100UL /*!< Output enable for pin 8 */ +#define GPIO_OUTENSET_PIN9_Msk 0x00000200UL /*!< Output enable for pin 9 */ +#define GPIO_OUTENSET_PIN10_Msk 0x00000400UL /*!< Output enable for pin 10 */ +#define GPIO_OUTENSET_PIN11_Msk 0x00000800UL /*!< Output enable for pin 11 */ +#define GPIO_OUTENSET_PIN12_Msk 0x00001000UL /*!< Output enable for pin 12 */ +#define GPIO_OUTENSET_PIN13_Msk 0x00002000UL /*!< Output enable for pin 13 */ +#define GPIO_OUTENSET_PIN14_Msk 0x00004000UL /*!< Output enable for pin 14 */ +#define GPIO_OUTENSET_PIN15_Msk 0x00008000UL /*!< Output enable for pin 15 */ + +/*-- OUTENCLR: Output disable register -----------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Output disable for pin 0 */ + uint32_t PIN1 :1; /*!< Output disable for pin 1 */ + uint32_t PIN2 :1; /*!< Output disable for pin 2 */ + uint32_t PIN3 :1; /*!< Output disable for pin 3 */ + uint32_t PIN4 :1; /*!< Output disable for pin 4 */ + uint32_t PIN5 :1; /*!< Output disable for pin 5 */ + uint32_t PIN6 :1; /*!< Output disable for pin 6 */ + uint32_t PIN7 :1; /*!< Output disable for pin 7 */ + uint32_t PIN8 :1; /*!< Output disable for pin 8 */ + uint32_t PIN9 :1; /*!< Output disable for pin 9 */ + uint32_t PIN10 :1; /*!< Output disable for pin 10 */ + uint32_t PIN11 :1; /*!< Output disable for pin 11 */ + uint32_t PIN12 :1; /*!< Output disable for pin 12 */ + uint32_t PIN13 :1; /*!< Output disable for pin 13 */ + uint32_t PIN14 :1; /*!< Output disable for pin 14 */ + uint32_t PIN15 :1; /*!< Output disable for pin 15 */ +} _GPIO_OUTENCLR_bits; + +/* Bit field positions: */ +#define GPIO_OUTENCLR_PIN0_Pos 0 /*!< Output disable for pin 0 */ +#define GPIO_OUTENCLR_PIN1_Pos 1 /*!< Output disable for pin 1 */ +#define GPIO_OUTENCLR_PIN2_Pos 2 /*!< Output disable for pin 2 */ +#define GPIO_OUTENCLR_PIN3_Pos 3 /*!< Output disable for pin 3 */ +#define GPIO_OUTENCLR_PIN4_Pos 4 /*!< Output disable for pin 4 */ +#define GPIO_OUTENCLR_PIN5_Pos 5 /*!< Output disable for pin 5 */ +#define GPIO_OUTENCLR_PIN6_Pos 6 /*!< Output disable for pin 6 */ +#define GPIO_OUTENCLR_PIN7_Pos 7 /*!< Output disable for pin 7 */ +#define GPIO_OUTENCLR_PIN8_Pos 8 /*!< Output disable for pin 8 */ +#define GPIO_OUTENCLR_PIN9_Pos 9 /*!< Output disable for pin 9 */ +#define GPIO_OUTENCLR_PIN10_Pos 10 /*!< Output disable for pin 10 */ +#define GPIO_OUTENCLR_PIN11_Pos 11 /*!< Output disable for pin 11 */ +#define GPIO_OUTENCLR_PIN12_Pos 12 /*!< Output disable for pin 12 */ +#define GPIO_OUTENCLR_PIN13_Pos 13 /*!< Output disable for pin 13 */ +#define GPIO_OUTENCLR_PIN14_Pos 14 /*!< Output disable for pin 14 */ +#define GPIO_OUTENCLR_PIN15_Pos 15 /*!< Output disable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_OUTENCLR_PIN0_Msk 0x00000001UL /*!< Output disable for pin 0 */ +#define GPIO_OUTENCLR_PIN1_Msk 0x00000002UL /*!< Output disable for pin 1 */ +#define GPIO_OUTENCLR_PIN2_Msk 0x00000004UL /*!< Output disable for pin 2 */ +#define GPIO_OUTENCLR_PIN3_Msk 0x00000008UL /*!< Output disable for pin 3 */ +#define GPIO_OUTENCLR_PIN4_Msk 0x00000010UL /*!< Output disable for pin 4 */ +#define GPIO_OUTENCLR_PIN5_Msk 0x00000020UL /*!< Output disable for pin 5 */ +#define GPIO_OUTENCLR_PIN6_Msk 0x00000040UL /*!< Output disable for pin 6 */ +#define GPIO_OUTENCLR_PIN7_Msk 0x00000080UL /*!< Output disable for pin 7 */ +#define GPIO_OUTENCLR_PIN8_Msk 0x00000100UL /*!< Output disable for pin 8 */ +#define GPIO_OUTENCLR_PIN9_Msk 0x00000200UL /*!< Output disable for pin 9 */ +#define GPIO_OUTENCLR_PIN10_Msk 0x00000400UL /*!< Output disable for pin 10 */ +#define GPIO_OUTENCLR_PIN11_Msk 0x00000800UL /*!< Output disable for pin 11 */ +#define GPIO_OUTENCLR_PIN12_Msk 0x00001000UL /*!< Output disable for pin 12 */ +#define GPIO_OUTENCLR_PIN13_Msk 0x00002000UL /*!< Output disable for pin 13 */ +#define GPIO_OUTENCLR_PIN14_Msk 0x00004000UL /*!< Output disable for pin 14 */ +#define GPIO_OUTENCLR_PIN15_Msk 0x00008000UL /*!< Output disable for pin 15 */ + +/*-- ALTFUNCSET: Alternative function enable register --------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Alternative function enable for pin 0 */ + uint32_t PIN1 :1; /*!< Alternative function enable for pin 1 */ + uint32_t PIN2 :1; /*!< Alternative function enable for pin 2 */ + uint32_t PIN3 :1; /*!< Alternative function enable for pin 3 */ + uint32_t PIN4 :1; /*!< Alternative function enable for pin 4 */ + uint32_t PIN5 :1; /*!< Alternative function enable for pin 5 */ + uint32_t PIN6 :1; /*!< Alternative function enable for pin 6 */ + uint32_t PIN7 :1; /*!< Alternative function enable for pin 7 */ + uint32_t PIN8 :1; /*!< Alternative function enable for pin 8 */ + uint32_t PIN9 :1; /*!< Alternative function enable for pin 9 */ + uint32_t PIN10 :1; /*!< Alternative function enable for pin 10 */ + uint32_t PIN11 :1; /*!< Alternative function enable for pin 11 */ + uint32_t PIN12 :1; /*!< Alternative function enable for pin 12 */ + uint32_t PIN13 :1; /*!< Alternative function enable for pin 13 */ + uint32_t PIN14 :1; /*!< Alternative function enable for pin 14 */ + uint32_t PIN15 :1; /*!< Alternative function enable for pin 15 */ +} _GPIO_ALTFUNCSET_bits; + +/* Bit field positions: */ +#define GPIO_ALTFUNCSET_PIN0_Pos 0 /*!< Alternative function enable for pin 0 */ +#define GPIO_ALTFUNCSET_PIN1_Pos 1 /*!< Alternative function enable for pin 1 */ +#define GPIO_ALTFUNCSET_PIN2_Pos 2 /*!< Alternative function enable for pin 2 */ +#define GPIO_ALTFUNCSET_PIN3_Pos 3 /*!< Alternative function enable for pin 3 */ +#define GPIO_ALTFUNCSET_PIN4_Pos 4 /*!< Alternative function enable for pin 4 */ +#define GPIO_ALTFUNCSET_PIN5_Pos 5 /*!< Alternative function enable for pin 5 */ +#define GPIO_ALTFUNCSET_PIN6_Pos 6 /*!< Alternative function enable for pin 6 */ +#define GPIO_ALTFUNCSET_PIN7_Pos 7 /*!< Alternative function enable for pin 7 */ +#define GPIO_ALTFUNCSET_PIN8_Pos 8 /*!< Alternative function enable for pin 8 */ +#define GPIO_ALTFUNCSET_PIN9_Pos 9 /*!< Alternative function enable for pin 9 */ +#define GPIO_ALTFUNCSET_PIN10_Pos 10 /*!< Alternative function enable for pin 10 */ +#define GPIO_ALTFUNCSET_PIN11_Pos 11 /*!< Alternative function enable for pin 11 */ +#define GPIO_ALTFUNCSET_PIN12_Pos 12 /*!< Alternative function enable for pin 12 */ +#define GPIO_ALTFUNCSET_PIN13_Pos 13 /*!< Alternative function enable for pin 13 */ +#define GPIO_ALTFUNCSET_PIN14_Pos 14 /*!< Alternative function enable for pin 14 */ +#define GPIO_ALTFUNCSET_PIN15_Pos 15 /*!< Alternative function enable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_ALTFUNCSET_PIN0_Msk 0x00000001UL /*!< Alternative function enable for pin 0 */ +#define GPIO_ALTFUNCSET_PIN1_Msk 0x00000002UL /*!< Alternative function enable for pin 1 */ +#define GPIO_ALTFUNCSET_PIN2_Msk 0x00000004UL /*!< Alternative function enable for pin 2 */ +#define GPIO_ALTFUNCSET_PIN3_Msk 0x00000008UL /*!< Alternative function enable for pin 3 */ +#define GPIO_ALTFUNCSET_PIN4_Msk 0x00000010UL /*!< Alternative function enable for pin 4 */ +#define GPIO_ALTFUNCSET_PIN5_Msk 0x00000020UL /*!< Alternative function enable for pin 5 */ +#define GPIO_ALTFUNCSET_PIN6_Msk 0x00000040UL /*!< Alternative function enable for pin 6 */ +#define GPIO_ALTFUNCSET_PIN7_Msk 0x00000080UL /*!< Alternative function enable for pin 7 */ +#define GPIO_ALTFUNCSET_PIN8_Msk 0x00000100UL /*!< Alternative function enable for pin 8 */ +#define GPIO_ALTFUNCSET_PIN9_Msk 0x00000200UL /*!< Alternative function enable for pin 9 */ +#define GPIO_ALTFUNCSET_PIN10_Msk 0x00000400UL /*!< Alternative function enable for pin 10 */ +#define GPIO_ALTFUNCSET_PIN11_Msk 0x00000800UL /*!< Alternative function enable for pin 11 */ +#define GPIO_ALTFUNCSET_PIN12_Msk 0x00001000UL /*!< Alternative function enable for pin 12 */ +#define GPIO_ALTFUNCSET_PIN13_Msk 0x00002000UL /*!< Alternative function enable for pin 13 */ +#define GPIO_ALTFUNCSET_PIN14_Msk 0x00004000UL /*!< Alternative function enable for pin 14 */ +#define GPIO_ALTFUNCSET_PIN15_Msk 0x00008000UL /*!< Alternative function enable for pin 15 */ + +/*-- ALTFUNCCLR: Alternative function disable register -------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Alternative function disable for pin 0 */ + uint32_t PIN1 :1; /*!< Alternative function disable for pin 1 */ + uint32_t PIN2 :1; /*!< Alternative function disable for pin 2 */ + uint32_t PIN3 :1; /*!< Alternative function disable for pin 3 */ + uint32_t PIN4 :1; /*!< Alternative function disable for pin 4 */ + uint32_t PIN5 :1; /*!< Alternative function disable for pin 5 */ + uint32_t PIN6 :1; /*!< Alternative function disable for pin 6 */ + uint32_t PIN7 :1; /*!< Alternative function disable for pin 7 */ + uint32_t PIN8 :1; /*!< Alternative function disable for pin 8 */ + uint32_t PIN9 :1; /*!< Alternative function disable for pin 9 */ + uint32_t PIN10 :1; /*!< Alternative function disable for pin 10 */ + uint32_t PIN11 :1; /*!< Alternative function disable for pin 11 */ + uint32_t PIN12 :1; /*!< Alternative function disable for pin 12 */ + uint32_t PIN13 :1; /*!< Alternative function disable for pin 13 */ + uint32_t PIN14 :1; /*!< Alternative function disable for pin 14 */ + uint32_t PIN15 :1; /*!< Alternative function disable for pin 15 */ +} _GPIO_ALTFUNCCLR_bits; + +/* Bit field positions: */ +#define GPIO_ALTFUNCCLR_PIN0_Pos 0 /*!< Alternative function disable for pin 0 */ +#define GPIO_ALTFUNCCLR_PIN1_Pos 1 /*!< Alternative function disable for pin 1 */ +#define GPIO_ALTFUNCCLR_PIN2_Pos 2 /*!< Alternative function disable for pin 2 */ +#define GPIO_ALTFUNCCLR_PIN3_Pos 3 /*!< Alternative function disable for pin 3 */ +#define GPIO_ALTFUNCCLR_PIN4_Pos 4 /*!< Alternative function disable for pin 4 */ +#define GPIO_ALTFUNCCLR_PIN5_Pos 5 /*!< Alternative function disable for pin 5 */ +#define GPIO_ALTFUNCCLR_PIN6_Pos 6 /*!< Alternative function disable for pin 6 */ +#define GPIO_ALTFUNCCLR_PIN7_Pos 7 /*!< Alternative function disable for pin 7 */ +#define GPIO_ALTFUNCCLR_PIN8_Pos 8 /*!< Alternative function disable for pin 8 */ +#define GPIO_ALTFUNCCLR_PIN9_Pos 9 /*!< Alternative function disable for pin 9 */ +#define GPIO_ALTFUNCCLR_PIN10_Pos 10 /*!< Alternative function disable for pin 10 */ +#define GPIO_ALTFUNCCLR_PIN11_Pos 11 /*!< Alternative function disable for pin 11 */ +#define GPIO_ALTFUNCCLR_PIN12_Pos 12 /*!< Alternative function disable for pin 12 */ +#define GPIO_ALTFUNCCLR_PIN13_Pos 13 /*!< Alternative function disable for pin 13 */ +#define GPIO_ALTFUNCCLR_PIN14_Pos 14 /*!< Alternative function disable for pin 14 */ +#define GPIO_ALTFUNCCLR_PIN15_Pos 15 /*!< Alternative function disable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_ALTFUNCCLR_PIN0_Msk 0x00000001UL /*!< Alternative function disable for pin 0 */ +#define GPIO_ALTFUNCCLR_PIN1_Msk 0x00000002UL /*!< Alternative function disable for pin 1 */ +#define GPIO_ALTFUNCCLR_PIN2_Msk 0x00000004UL /*!< Alternative function disable for pin 2 */ +#define GPIO_ALTFUNCCLR_PIN3_Msk 0x00000008UL /*!< Alternative function disable for pin 3 */ +#define GPIO_ALTFUNCCLR_PIN4_Msk 0x00000010UL /*!< Alternative function disable for pin 4 */ +#define GPIO_ALTFUNCCLR_PIN5_Msk 0x00000020UL /*!< Alternative function disable for pin 5 */ +#define GPIO_ALTFUNCCLR_PIN6_Msk 0x00000040UL /*!< Alternative function disable for pin 6 */ +#define GPIO_ALTFUNCCLR_PIN7_Msk 0x00000080UL /*!< Alternative function disable for pin 7 */ +#define GPIO_ALTFUNCCLR_PIN8_Msk 0x00000100UL /*!< Alternative function disable for pin 8 */ +#define GPIO_ALTFUNCCLR_PIN9_Msk 0x00000200UL /*!< Alternative function disable for pin 9 */ +#define GPIO_ALTFUNCCLR_PIN10_Msk 0x00000400UL /*!< Alternative function disable for pin 10 */ +#define GPIO_ALTFUNCCLR_PIN11_Msk 0x00000800UL /*!< Alternative function disable for pin 11 */ +#define GPIO_ALTFUNCCLR_PIN12_Msk 0x00001000UL /*!< Alternative function disable for pin 12 */ +#define GPIO_ALTFUNCCLR_PIN13_Msk 0x00002000UL /*!< Alternative function disable for pin 13 */ +#define GPIO_ALTFUNCCLR_PIN14_Msk 0x00004000UL /*!< Alternative function disable for pin 14 */ +#define GPIO_ALTFUNCCLR_PIN15_Msk 0x00008000UL /*!< Alternative function disable for pin 15 */ + +/*-- SYNCSET: Additional double flip-flop syncronization enable register -------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 0 */ + uint32_t PIN1 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 1 */ + uint32_t PIN2 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 2 */ + uint32_t PIN3 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 3 */ + uint32_t PIN4 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 4 */ + uint32_t PIN5 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 5 */ + uint32_t PIN6 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 6 */ + uint32_t PIN7 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 7 */ + uint32_t PIN8 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 8 */ + uint32_t PIN9 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 9 */ + uint32_t PIN10 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 10 */ + uint32_t PIN11 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 11 */ + uint32_t PIN12 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 12 */ + uint32_t PIN13 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 13 */ + uint32_t PIN14 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 14 */ + uint32_t PIN15 :1; /*!< Additional double flip-flop syncronization buffer enable for pin 15 */ +} _GPIO_SYNCSET_bits; + +/* Bit field positions: */ +#define GPIO_SYNCSET_PIN0_Pos 0 /*!< Additional double flip-flop syncronization buffer enable for pin 0 */ +#define GPIO_SYNCSET_PIN1_Pos 1 /*!< Additional double flip-flop syncronization buffer enable for pin 1 */ +#define GPIO_SYNCSET_PIN2_Pos 2 /*!< Additional double flip-flop syncronization buffer enable for pin 2 */ +#define GPIO_SYNCSET_PIN3_Pos 3 /*!< Additional double flip-flop syncronization buffer enable for pin 3 */ +#define GPIO_SYNCSET_PIN4_Pos 4 /*!< Additional double flip-flop syncronization buffer enable for pin 4 */ +#define GPIO_SYNCSET_PIN5_Pos 5 /*!< Additional double flip-flop syncronization buffer enable for pin 5 */ +#define GPIO_SYNCSET_PIN6_Pos 6 /*!< Additional double flip-flop syncronization buffer enable for pin 6 */ +#define GPIO_SYNCSET_PIN7_Pos 7 /*!< Additional double flip-flop syncronization buffer enable for pin 7 */ +#define GPIO_SYNCSET_PIN8_Pos 8 /*!< Additional double flip-flop syncronization buffer enable for pin 8 */ +#define GPIO_SYNCSET_PIN9_Pos 9 /*!< Additional double flip-flop syncronization buffer enable for pin 9 */ +#define GPIO_SYNCSET_PIN10_Pos 10 /*!< Additional double flip-flop syncronization buffer enable for pin 10 */ +#define GPIO_SYNCSET_PIN11_Pos 11 /*!< Additional double flip-flop syncronization buffer enable for pin 11 */ +#define GPIO_SYNCSET_PIN12_Pos 12 /*!< Additional double flip-flop syncronization buffer enable for pin 12 */ +#define GPIO_SYNCSET_PIN13_Pos 13 /*!< Additional double flip-flop syncronization buffer enable for pin 13 */ +#define GPIO_SYNCSET_PIN14_Pos 14 /*!< Additional double flip-flop syncronization buffer enable for pin 14 */ +#define GPIO_SYNCSET_PIN15_Pos 15 /*!< Additional double flip-flop syncronization buffer enable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_SYNCSET_PIN0_Msk 0x00000001UL /*!< Additional double flip-flop syncronization buffer enable for pin 0 */ +#define GPIO_SYNCSET_PIN1_Msk 0x00000002UL /*!< Additional double flip-flop syncronization buffer enable for pin 1 */ +#define GPIO_SYNCSET_PIN2_Msk 0x00000004UL /*!< Additional double flip-flop syncronization buffer enable for pin 2 */ +#define GPIO_SYNCSET_PIN3_Msk 0x00000008UL /*!< Additional double flip-flop syncronization buffer enable for pin 3 */ +#define GPIO_SYNCSET_PIN4_Msk 0x00000010UL /*!< Additional double flip-flop syncronization buffer enable for pin 4 */ +#define GPIO_SYNCSET_PIN5_Msk 0x00000020UL /*!< Additional double flip-flop syncronization buffer enable for pin 5 */ +#define GPIO_SYNCSET_PIN6_Msk 0x00000040UL /*!< Additional double flip-flop syncronization buffer enable for pin 6 */ +#define GPIO_SYNCSET_PIN7_Msk 0x00000080UL /*!< Additional double flip-flop syncronization buffer enable for pin 7 */ +#define GPIO_SYNCSET_PIN8_Msk 0x00000100UL /*!< Additional double flip-flop syncronization buffer enable for pin 8 */ +#define GPIO_SYNCSET_PIN9_Msk 0x00000200UL /*!< Additional double flip-flop syncronization buffer enable for pin 9 */ +#define GPIO_SYNCSET_PIN10_Msk 0x00000400UL /*!< Additional double flip-flop syncronization buffer enable for pin 10 */ +#define GPIO_SYNCSET_PIN11_Msk 0x00000800UL /*!< Additional double flip-flop syncronization buffer enable for pin 11 */ +#define GPIO_SYNCSET_PIN12_Msk 0x00001000UL /*!< Additional double flip-flop syncronization buffer enable for pin 12 */ +#define GPIO_SYNCSET_PIN13_Msk 0x00002000UL /*!< Additional double flip-flop syncronization buffer enable for pin 13 */ +#define GPIO_SYNCSET_PIN14_Msk 0x00004000UL /*!< Additional double flip-flop syncronization buffer enable for pin 14 */ +#define GPIO_SYNCSET_PIN15_Msk 0x00008000UL /*!< Additional double flip-flop syncronization buffer enable for pin 15 */ + +/*-- SYNCCLR: Additional double flip-flop syncronization disable register ------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Additional double flip-flop syncronization disable for pin 0 */ + uint32_t PIN1 :1; /*!< Additional double flip-flop syncronization disable for pin 1 */ + uint32_t PIN2 :1; /*!< Additional double flip-flop syncronization disable for pin 2 */ + uint32_t PIN3 :1; /*!< Additional double flip-flop syncronization disable for pin 3 */ + uint32_t PIN4 :1; /*!< Additional double flip-flop syncronization disable for pin 4 */ + uint32_t PIN5 :1; /*!< Additional double flip-flop syncronization disable for pin 5 */ + uint32_t PIN6 :1; /*!< Additional double flip-flop syncronization disable for pin 6 */ + uint32_t PIN7 :1; /*!< Additional double flip-flop syncronization disable for pin 7 */ + uint32_t PIN8 :1; /*!< Additional double flip-flop syncronization disable for pin 8 */ + uint32_t PIN9 :1; /*!< Additional double flip-flop syncronization disable for pin 9 */ + uint32_t PIN10 :1; /*!< Additional double flip-flop syncronization disable for pin 10 */ + uint32_t PIN11 :1; /*!< Additional double flip-flop syncronization disable for pin 11 */ + uint32_t PIN12 :1; /*!< Additional double flip-flop syncronization disable for pin 12 */ + uint32_t PIN13 :1; /*!< Additional double flip-flop syncronization disable for pin 13 */ + uint32_t PIN14 :1; /*!< Additional double flip-flop syncronization disable for pin 14 */ + uint32_t PIN15 :1; /*!< Additional double flip-flop syncronization disable for pin 15 */ +} _GPIO_SYNCCLR_bits; + +/* Bit field positions: */ +#define GPIO_SYNCCLR_PIN0_Pos 0 /*!< Additional double flip-flop syncronization disable for pin 0 */ +#define GPIO_SYNCCLR_PIN1_Pos 1 /*!< Additional double flip-flop syncronization disable for pin 1 */ +#define GPIO_SYNCCLR_PIN2_Pos 2 /*!< Additional double flip-flop syncronization disable for pin 2 */ +#define GPIO_SYNCCLR_PIN3_Pos 3 /*!< Additional double flip-flop syncronization disable for pin 3 */ +#define GPIO_SYNCCLR_PIN4_Pos 4 /*!< Additional double flip-flop syncronization disable for pin 4 */ +#define GPIO_SYNCCLR_PIN5_Pos 5 /*!< Additional double flip-flop syncronization disable for pin 5 */ +#define GPIO_SYNCCLR_PIN6_Pos 6 /*!< Additional double flip-flop syncronization disable for pin 6 */ +#define GPIO_SYNCCLR_PIN7_Pos 7 /*!< Additional double flip-flop syncronization disable for pin 7 */ +#define GPIO_SYNCCLR_PIN8_Pos 8 /*!< Additional double flip-flop syncronization disable for pin 8 */ +#define GPIO_SYNCCLR_PIN9_Pos 9 /*!< Additional double flip-flop syncronization disable for pin 9 */ +#define GPIO_SYNCCLR_PIN10_Pos 10 /*!< Additional double flip-flop syncronization disable for pin 10 */ +#define GPIO_SYNCCLR_PIN11_Pos 11 /*!< Additional double flip-flop syncronization disable for pin 11 */ +#define GPIO_SYNCCLR_PIN12_Pos 12 /*!< Additional double flip-flop syncronization disable for pin 12 */ +#define GPIO_SYNCCLR_PIN13_Pos 13 /*!< Additional double flip-flop syncronization disable for pin 13 */ +#define GPIO_SYNCCLR_PIN14_Pos 14 /*!< Additional double flip-flop syncronization disable for pin 14 */ +#define GPIO_SYNCCLR_PIN15_Pos 15 /*!< Additional double flip-flop syncronization disable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_SYNCCLR_PIN0_Msk 0x00000001UL /*!< Additional double flip-flop syncronization disable for pin 0 */ +#define GPIO_SYNCCLR_PIN1_Msk 0x00000002UL /*!< Additional double flip-flop syncronization disable for pin 1 */ +#define GPIO_SYNCCLR_PIN2_Msk 0x00000004UL /*!< Additional double flip-flop syncronization disable for pin 2 */ +#define GPIO_SYNCCLR_PIN3_Msk 0x00000008UL /*!< Additional double flip-flop syncronization disable for pin 3 */ +#define GPIO_SYNCCLR_PIN4_Msk 0x00000010UL /*!< Additional double flip-flop syncronization disable for pin 4 */ +#define GPIO_SYNCCLR_PIN5_Msk 0x00000020UL /*!< Additional double flip-flop syncronization disable for pin 5 */ +#define GPIO_SYNCCLR_PIN6_Msk 0x00000040UL /*!< Additional double flip-flop syncronization disable for pin 6 */ +#define GPIO_SYNCCLR_PIN7_Msk 0x00000080UL /*!< Additional double flip-flop syncronization disable for pin 7 */ +#define GPIO_SYNCCLR_PIN8_Msk 0x00000100UL /*!< Additional double flip-flop syncronization disable for pin 8 */ +#define GPIO_SYNCCLR_PIN9_Msk 0x00000200UL /*!< Additional double flip-flop syncronization disable for pin 9 */ +#define GPIO_SYNCCLR_PIN10_Msk 0x00000400UL /*!< Additional double flip-flop syncronization disable for pin 10 */ +#define GPIO_SYNCCLR_PIN11_Msk 0x00000800UL /*!< Additional double flip-flop syncronization disable for pin 11 */ +#define GPIO_SYNCCLR_PIN12_Msk 0x00001000UL /*!< Additional double flip-flop syncronization disable for pin 12 */ +#define GPIO_SYNCCLR_PIN13_Msk 0x00002000UL /*!< Additional double flip-flop syncronization disable for pin 13 */ +#define GPIO_SYNCCLR_PIN14_Msk 0x00004000UL /*!< Additional double flip-flop syncronization disable for pin 14 */ +#define GPIO_SYNCCLR_PIN15_Msk 0x00008000UL /*!< Additional double flip-flop syncronization disable for pin 15 */ + +/*-- QUALSET: Qualifier enable register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Qualifier enable for pin 0 */ + uint32_t PIN1 :1; /*!< Qualifier enable for pin 1 */ + uint32_t PIN2 :1; /*!< Qualifier enable for pin 2 */ + uint32_t PIN3 :1; /*!< Qualifier enable for pin 3 */ + uint32_t PIN4 :1; /*!< Qualifier enable for pin 4 */ + uint32_t PIN5 :1; /*!< Qualifier enable for pin 5 */ + uint32_t PIN6 :1; /*!< Qualifier enable for pin 6 */ + uint32_t PIN7 :1; /*!< Qualifier enable for pin 7 */ + uint32_t PIN8 :1; /*!< Qualifier enable for pin 8 */ + uint32_t PIN9 :1; /*!< Qualifier enable for pin 9 */ + uint32_t PIN10 :1; /*!< Qualifier enable for pin 10 */ + uint32_t PIN11 :1; /*!< Qualifier enable for pin 11 */ + uint32_t PIN12 :1; /*!< Qualifier enable for pin 12 */ + uint32_t PIN13 :1; /*!< Qualifier enable for pin 13 */ + uint32_t PIN14 :1; /*!< Qualifier enable for pin 14 */ + uint32_t PIN15 :1; /*!< Qualifier enable for pin 15 */ +} _GPIO_QUALSET_bits; + +/* Bit field positions: */ +#define GPIO_QUALSET_PIN0_Pos 0 /*!< Qualifier enable for pin 0 */ +#define GPIO_QUALSET_PIN1_Pos 1 /*!< Qualifier enable for pin 1 */ +#define GPIO_QUALSET_PIN2_Pos 2 /*!< Qualifier enable for pin 2 */ +#define GPIO_QUALSET_PIN3_Pos 3 /*!< Qualifier enable for pin 3 */ +#define GPIO_QUALSET_PIN4_Pos 4 /*!< Qualifier enable for pin 4 */ +#define GPIO_QUALSET_PIN5_Pos 5 /*!< Qualifier enable for pin 5 */ +#define GPIO_QUALSET_PIN6_Pos 6 /*!< Qualifier enable for pin 6 */ +#define GPIO_QUALSET_PIN7_Pos 7 /*!< Qualifier enable for pin 7 */ +#define GPIO_QUALSET_PIN8_Pos 8 /*!< Qualifier enable for pin 8 */ +#define GPIO_QUALSET_PIN9_Pos 9 /*!< Qualifier enable for pin 9 */ +#define GPIO_QUALSET_PIN10_Pos 10 /*!< Qualifier enable for pin 10 */ +#define GPIO_QUALSET_PIN11_Pos 11 /*!< Qualifier enable for pin 11 */ +#define GPIO_QUALSET_PIN12_Pos 12 /*!< Qualifier enable for pin 12 */ +#define GPIO_QUALSET_PIN13_Pos 13 /*!< Qualifier enable for pin 13 */ +#define GPIO_QUALSET_PIN14_Pos 14 /*!< Qualifier enable for pin 14 */ +#define GPIO_QUALSET_PIN15_Pos 15 /*!< Qualifier enable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_QUALSET_PIN0_Msk 0x00000001UL /*!< Qualifier enable for pin 0 */ +#define GPIO_QUALSET_PIN1_Msk 0x00000002UL /*!< Qualifier enable for pin 1 */ +#define GPIO_QUALSET_PIN2_Msk 0x00000004UL /*!< Qualifier enable for pin 2 */ +#define GPIO_QUALSET_PIN3_Msk 0x00000008UL /*!< Qualifier enable for pin 3 */ +#define GPIO_QUALSET_PIN4_Msk 0x00000010UL /*!< Qualifier enable for pin 4 */ +#define GPIO_QUALSET_PIN5_Msk 0x00000020UL /*!< Qualifier enable for pin 5 */ +#define GPIO_QUALSET_PIN6_Msk 0x00000040UL /*!< Qualifier enable for pin 6 */ +#define GPIO_QUALSET_PIN7_Msk 0x00000080UL /*!< Qualifier enable for pin 7 */ +#define GPIO_QUALSET_PIN8_Msk 0x00000100UL /*!< Qualifier enable for pin 8 */ +#define GPIO_QUALSET_PIN9_Msk 0x00000200UL /*!< Qualifier enable for pin 9 */ +#define GPIO_QUALSET_PIN10_Msk 0x00000400UL /*!< Qualifier enable for pin 10 */ +#define GPIO_QUALSET_PIN11_Msk 0x00000800UL /*!< Qualifier enable for pin 11 */ +#define GPIO_QUALSET_PIN12_Msk 0x00001000UL /*!< Qualifier enable for pin 12 */ +#define GPIO_QUALSET_PIN13_Msk 0x00002000UL /*!< Qualifier enable for pin 13 */ +#define GPIO_QUALSET_PIN14_Msk 0x00004000UL /*!< Qualifier enable for pin 14 */ +#define GPIO_QUALSET_PIN15_Msk 0x00008000UL /*!< Qualifier enable for pin 15 */ + +/*-- QUALCLR: Qualifier disable register ---------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Qualifier disable for pin 0 */ + uint32_t PIN1 :1; /*!< Qualifier disable for pin 1 */ + uint32_t PIN2 :1; /*!< Qualifier disable for pin 2 */ + uint32_t PIN3 :1; /*!< Qualifier disable for pin 3 */ + uint32_t PIN4 :1; /*!< Qualifier disable for pin 4 */ + uint32_t PIN5 :1; /*!< Qualifier disable for pin 5 */ + uint32_t PIN6 :1; /*!< Qualifier disable for pin 6 */ + uint32_t PIN7 :1; /*!< Qualifier disable for pin 7 */ + uint32_t PIN8 :1; /*!< Qualifier disable for pin 8 */ + uint32_t PIN9 :1; /*!< Qualifier disable for pin 9 */ + uint32_t PIN10 :1; /*!< Qualifier disable for pin 10 */ + uint32_t PIN11 :1; /*!< Qualifier disable for pin 11 */ + uint32_t PIN12 :1; /*!< Qualifier disable for pin 12 */ + uint32_t PIN13 :1; /*!< Qualifier disable for pin 13 */ + uint32_t PIN14 :1; /*!< Qualifier disable for pin 14 */ + uint32_t PIN15 :1; /*!< Qualifier disable for pin 15 */ +} _GPIO_QUALCLR_bits; + +/* Bit field positions: */ +#define GPIO_QUALCLR_PIN0_Pos 0 /*!< Qualifier disable for pin 0 */ +#define GPIO_QUALCLR_PIN1_Pos 1 /*!< Qualifier disable for pin 1 */ +#define GPIO_QUALCLR_PIN2_Pos 2 /*!< Qualifier disable for pin 2 */ +#define GPIO_QUALCLR_PIN3_Pos 3 /*!< Qualifier disable for pin 3 */ +#define GPIO_QUALCLR_PIN4_Pos 4 /*!< Qualifier disable for pin 4 */ +#define GPIO_QUALCLR_PIN5_Pos 5 /*!< Qualifier disable for pin 5 */ +#define GPIO_QUALCLR_PIN6_Pos 6 /*!< Qualifier disable for pin 6 */ +#define GPIO_QUALCLR_PIN7_Pos 7 /*!< Qualifier disable for pin 7 */ +#define GPIO_QUALCLR_PIN8_Pos 8 /*!< Qualifier disable for pin 8 */ +#define GPIO_QUALCLR_PIN9_Pos 9 /*!< Qualifier disable for pin 9 */ +#define GPIO_QUALCLR_PIN10_Pos 10 /*!< Qualifier disable for pin 10 */ +#define GPIO_QUALCLR_PIN11_Pos 11 /*!< Qualifier disable for pin 11 */ +#define GPIO_QUALCLR_PIN12_Pos 12 /*!< Qualifier disable for pin 12 */ +#define GPIO_QUALCLR_PIN13_Pos 13 /*!< Qualifier disable for pin 13 */ +#define GPIO_QUALCLR_PIN14_Pos 14 /*!< Qualifier disable for pin 14 */ +#define GPIO_QUALCLR_PIN15_Pos 15 /*!< Qualifier disable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_QUALCLR_PIN0_Msk 0x00000001UL /*!< Qualifier disable for pin 0 */ +#define GPIO_QUALCLR_PIN1_Msk 0x00000002UL /*!< Qualifier disable for pin 1 */ +#define GPIO_QUALCLR_PIN2_Msk 0x00000004UL /*!< Qualifier disable for pin 2 */ +#define GPIO_QUALCLR_PIN3_Msk 0x00000008UL /*!< Qualifier disable for pin 3 */ +#define GPIO_QUALCLR_PIN4_Msk 0x00000010UL /*!< Qualifier disable for pin 4 */ +#define GPIO_QUALCLR_PIN5_Msk 0x00000020UL /*!< Qualifier disable for pin 5 */ +#define GPIO_QUALCLR_PIN6_Msk 0x00000040UL /*!< Qualifier disable for pin 6 */ +#define GPIO_QUALCLR_PIN7_Msk 0x00000080UL /*!< Qualifier disable for pin 7 */ +#define GPIO_QUALCLR_PIN8_Msk 0x00000100UL /*!< Qualifier disable for pin 8 */ +#define GPIO_QUALCLR_PIN9_Msk 0x00000200UL /*!< Qualifier disable for pin 9 */ +#define GPIO_QUALCLR_PIN10_Msk 0x00000400UL /*!< Qualifier disable for pin 10 */ +#define GPIO_QUALCLR_PIN11_Msk 0x00000800UL /*!< Qualifier disable for pin 11 */ +#define GPIO_QUALCLR_PIN12_Msk 0x00001000UL /*!< Qualifier disable for pin 12 */ +#define GPIO_QUALCLR_PIN13_Msk 0x00002000UL /*!< Qualifier disable for pin 13 */ +#define GPIO_QUALCLR_PIN14_Msk 0x00004000UL /*!< Qualifier disable for pin 14 */ +#define GPIO_QUALCLR_PIN15_Msk 0x00008000UL /*!< Qualifier disable for pin 15 */ + +/*-- QUALMODESET: Qualifier mode set register ----------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Qualifier mode set for pin 0 */ + uint32_t PIN1 :1; /*!< Qualifier mode set for pin 1 */ + uint32_t PIN2 :1; /*!< Qualifier mode set for pin 2 */ + uint32_t PIN3 :1; /*!< Qualifier mode set for pin 3 */ + uint32_t PIN4 :1; /*!< Qualifier mode set for pin 4 */ + uint32_t PIN5 :1; /*!< Qualifier mode set for pin 5 */ + uint32_t PIN6 :1; /*!< Qualifier mode set for pin 6 */ + uint32_t PIN7 :1; /*!< Qualifier mode set for pin 7 */ + uint32_t PIN8 :1; /*!< Qualifier mode set for pin 8 */ + uint32_t PIN9 :1; /*!< Qualifier mode set for pin 9 */ + uint32_t PIN10 :1; /*!< Qualifier mode set for pin 10 */ + uint32_t PIN11 :1; /*!< Qualifier mode set for pin 11 */ + uint32_t PIN12 :1; /*!< Qualifier mode set for pin 12 */ + uint32_t PIN13 :1; /*!< Qualifier mode set for pin 13 */ + uint32_t PIN14 :1; /*!< Qualifier mode set for pin 14 */ + uint32_t PIN15 :1; /*!< Qualifier mode set for pin 15 */ +} _GPIO_QUALMODESET_bits; + +/* Bit field positions: */ +#define GPIO_QUALMODESET_PIN0_Pos 0 /*!< Qualifier mode set for pin 0 */ +#define GPIO_QUALMODESET_PIN1_Pos 1 /*!< Qualifier mode set for pin 1 */ +#define GPIO_QUALMODESET_PIN2_Pos 2 /*!< Qualifier mode set for pin 2 */ +#define GPIO_QUALMODESET_PIN3_Pos 3 /*!< Qualifier mode set for pin 3 */ +#define GPIO_QUALMODESET_PIN4_Pos 4 /*!< Qualifier mode set for pin 4 */ +#define GPIO_QUALMODESET_PIN5_Pos 5 /*!< Qualifier mode set for pin 5 */ +#define GPIO_QUALMODESET_PIN6_Pos 6 /*!< Qualifier mode set for pin 6 */ +#define GPIO_QUALMODESET_PIN7_Pos 7 /*!< Qualifier mode set for pin 7 */ +#define GPIO_QUALMODESET_PIN8_Pos 8 /*!< Qualifier mode set for pin 8 */ +#define GPIO_QUALMODESET_PIN9_Pos 9 /*!< Qualifier mode set for pin 9 */ +#define GPIO_QUALMODESET_PIN10_Pos 10 /*!< Qualifier mode set for pin 10 */ +#define GPIO_QUALMODESET_PIN11_Pos 11 /*!< Qualifier mode set for pin 11 */ +#define GPIO_QUALMODESET_PIN12_Pos 12 /*!< Qualifier mode set for pin 12 */ +#define GPIO_QUALMODESET_PIN13_Pos 13 /*!< Qualifier mode set for pin 13 */ +#define GPIO_QUALMODESET_PIN14_Pos 14 /*!< Qualifier mode set for pin 14 */ +#define GPIO_QUALMODESET_PIN15_Pos 15 /*!< Qualifier mode set for pin 15 */ + +/* Bit field masks: */ +#define GPIO_QUALMODESET_PIN0_Msk 0x00000001UL /*!< Qualifier mode set for pin 0 */ +#define GPIO_QUALMODESET_PIN1_Msk 0x00000002UL /*!< Qualifier mode set for pin 1 */ +#define GPIO_QUALMODESET_PIN2_Msk 0x00000004UL /*!< Qualifier mode set for pin 2 */ +#define GPIO_QUALMODESET_PIN3_Msk 0x00000008UL /*!< Qualifier mode set for pin 3 */ +#define GPIO_QUALMODESET_PIN4_Msk 0x00000010UL /*!< Qualifier mode set for pin 4 */ +#define GPIO_QUALMODESET_PIN5_Msk 0x00000020UL /*!< Qualifier mode set for pin 5 */ +#define GPIO_QUALMODESET_PIN6_Msk 0x00000040UL /*!< Qualifier mode set for pin 6 */ +#define GPIO_QUALMODESET_PIN7_Msk 0x00000080UL /*!< Qualifier mode set for pin 7 */ +#define GPIO_QUALMODESET_PIN8_Msk 0x00000100UL /*!< Qualifier mode set for pin 8 */ +#define GPIO_QUALMODESET_PIN9_Msk 0x00000200UL /*!< Qualifier mode set for pin 9 */ +#define GPIO_QUALMODESET_PIN10_Msk 0x00000400UL /*!< Qualifier mode set for pin 10 */ +#define GPIO_QUALMODESET_PIN11_Msk 0x00000800UL /*!< Qualifier mode set for pin 11 */ +#define GPIO_QUALMODESET_PIN12_Msk 0x00001000UL /*!< Qualifier mode set for pin 12 */ +#define GPIO_QUALMODESET_PIN13_Msk 0x00002000UL /*!< Qualifier mode set for pin 13 */ +#define GPIO_QUALMODESET_PIN14_Msk 0x00004000UL /*!< Qualifier mode set for pin 14 */ +#define GPIO_QUALMODESET_PIN15_Msk 0x00008000UL /*!< Qualifier mode set for pin 15 */ + +/*-- QUALMODECLR: Qualifier mode clear register --------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Qualifier mode clear for pin 0 */ + uint32_t PIN1 :1; /*!< Qualifier mode clear for pin 1 */ + uint32_t PIN2 :1; /*!< Qualifier mode clear for pin 2 */ + uint32_t PIN3 :1; /*!< Qualifier mode clear for pin 3 */ + uint32_t PIN4 :1; /*!< Qualifier mode clear for pin 4 */ + uint32_t PIN5 :1; /*!< Qualifier mode clear for pin 5 */ + uint32_t PIN6 :1; /*!< Qualifier mode clear for pin 6 */ + uint32_t PIN7 :1; /*!< Qualifier mode clear for pin 7 */ + uint32_t PIN8 :1; /*!< Qualifier mode clear for pin 8 */ + uint32_t PIN9 :1; /*!< Qualifier mode clear for pin 9 */ + uint32_t PIN10 :1; /*!< Qualifier mode clear for pin 10 */ + uint32_t PIN11 :1; /*!< Qualifier mode clear for pin 11 */ + uint32_t PIN12 :1; /*!< Qualifier mode clear for pin 12 */ + uint32_t PIN13 :1; /*!< Qualifier mode clear for pin 13 */ + uint32_t PIN14 :1; /*!< Qualifier mode clear for pin 14 */ + uint32_t PIN15 :1; /*!< Qualifier mode clear for pin 15 */ +} _GPIO_QUALMODECLR_bits; + +/* Bit field positions: */ +#define GPIO_QUALMODECLR_PIN0_Pos 0 /*!< Qualifier mode clear for pin 0 */ +#define GPIO_QUALMODECLR_PIN1_Pos 1 /*!< Qualifier mode clear for pin 1 */ +#define GPIO_QUALMODECLR_PIN2_Pos 2 /*!< Qualifier mode clear for pin 2 */ +#define GPIO_QUALMODECLR_PIN3_Pos 3 /*!< Qualifier mode clear for pin 3 */ +#define GPIO_QUALMODECLR_PIN4_Pos 4 /*!< Qualifier mode clear for pin 4 */ +#define GPIO_QUALMODECLR_PIN5_Pos 5 /*!< Qualifier mode clear for pin 5 */ +#define GPIO_QUALMODECLR_PIN6_Pos 6 /*!< Qualifier mode clear for pin 6 */ +#define GPIO_QUALMODECLR_PIN7_Pos 7 /*!< Qualifier mode clear for pin 7 */ +#define GPIO_QUALMODECLR_PIN8_Pos 8 /*!< Qualifier mode clear for pin 8 */ +#define GPIO_QUALMODECLR_PIN9_Pos 9 /*!< Qualifier mode clear for pin 9 */ +#define GPIO_QUALMODECLR_PIN10_Pos 10 /*!< Qualifier mode clear for pin 10 */ +#define GPIO_QUALMODECLR_PIN11_Pos 11 /*!< Qualifier mode clear for pin 11 */ +#define GPIO_QUALMODECLR_PIN12_Pos 12 /*!< Qualifier mode clear for pin 12 */ +#define GPIO_QUALMODECLR_PIN13_Pos 13 /*!< Qualifier mode clear for pin 13 */ +#define GPIO_QUALMODECLR_PIN14_Pos 14 /*!< Qualifier mode clear for pin 14 */ +#define GPIO_QUALMODECLR_PIN15_Pos 15 /*!< Qualifier mode clear for pin 15 */ + +/* Bit field masks: */ +#define GPIO_QUALMODECLR_PIN0_Msk 0x00000001UL /*!< Qualifier mode clear for pin 0 */ +#define GPIO_QUALMODECLR_PIN1_Msk 0x00000002UL /*!< Qualifier mode clear for pin 1 */ +#define GPIO_QUALMODECLR_PIN2_Msk 0x00000004UL /*!< Qualifier mode clear for pin 2 */ +#define GPIO_QUALMODECLR_PIN3_Msk 0x00000008UL /*!< Qualifier mode clear for pin 3 */ +#define GPIO_QUALMODECLR_PIN4_Msk 0x00000010UL /*!< Qualifier mode clear for pin 4 */ +#define GPIO_QUALMODECLR_PIN5_Msk 0x00000020UL /*!< Qualifier mode clear for pin 5 */ +#define GPIO_QUALMODECLR_PIN6_Msk 0x00000040UL /*!< Qualifier mode clear for pin 6 */ +#define GPIO_QUALMODECLR_PIN7_Msk 0x00000080UL /*!< Qualifier mode clear for pin 7 */ +#define GPIO_QUALMODECLR_PIN8_Msk 0x00000100UL /*!< Qualifier mode clear for pin 8 */ +#define GPIO_QUALMODECLR_PIN9_Msk 0x00000200UL /*!< Qualifier mode clear for pin 9 */ +#define GPIO_QUALMODECLR_PIN10_Msk 0x00000400UL /*!< Qualifier mode clear for pin 10 */ +#define GPIO_QUALMODECLR_PIN11_Msk 0x00000800UL /*!< Qualifier mode clear for pin 11 */ +#define GPIO_QUALMODECLR_PIN12_Msk 0x00001000UL /*!< Qualifier mode clear for pin 12 */ +#define GPIO_QUALMODECLR_PIN13_Msk 0x00002000UL /*!< Qualifier mode clear for pin 13 */ +#define GPIO_QUALMODECLR_PIN14_Msk 0x00004000UL /*!< Qualifier mode clear for pin 14 */ +#define GPIO_QUALMODECLR_PIN15_Msk 0x00008000UL /*!< Qualifier mode clear for pin 15 */ + +/*-- QUALSAMPLE: Qualifier sample period register ------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :8; /*!< Qualifier sample period */ +} _GPIO_QUALSAMPLE_bits; + +/* Bit field positions: */ +#define GPIO_QUALSAMPLE_VAL_Pos 0 /*!< Qualifier sample period */ + +/* Bit field masks: */ +#define GPIO_QUALSAMPLE_VAL_Msk 0x000000FFUL /*!< Qualifier sample period */ + +/*-- INTENSET: Interrupt enable register ---------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Interrupt enable for pin 0 */ + uint32_t PIN1 :1; /*!< Interrupt enable for pin 1 */ + uint32_t PIN2 :1; /*!< Interrupt enable for pin 2 */ + uint32_t PIN3 :1; /*!< Interrupt enable for pin 3 */ + uint32_t PIN4 :1; /*!< Interrupt enable for pin 4 */ + uint32_t PIN5 :1; /*!< Interrupt enable for pin 5 */ + uint32_t PIN6 :1; /*!< Interrupt enable for pin 6 */ + uint32_t PIN7 :1; /*!< Interrupt enable for pin 7 */ + uint32_t PIN8 :1; /*!< Interrupt enable for pin 8 */ + uint32_t PIN9 :1; /*!< Interrupt enable for pin 9 */ + uint32_t PIN10 :1; /*!< Interrupt enable for pin 10 */ + uint32_t PIN11 :1; /*!< Interrupt enable for pin 11 */ + uint32_t PIN12 :1; /*!< Interrupt enable for pin 12 */ + uint32_t PIN13 :1; /*!< Interrupt enable for pin 13 */ + uint32_t PIN14 :1; /*!< Interrupt enable for pin 14 */ + uint32_t PIN15 :1; /*!< Interrupt enable for pin 15 */ +} _GPIO_INTENSET_bits; + +/* Bit field positions: */ +#define GPIO_INTENSET_PIN0_Pos 0 /*!< Interrupt enable for pin 0 */ +#define GPIO_INTENSET_PIN1_Pos 1 /*!< Interrupt enable for pin 1 */ +#define GPIO_INTENSET_PIN2_Pos 2 /*!< Interrupt enable for pin 2 */ +#define GPIO_INTENSET_PIN3_Pos 3 /*!< Interrupt enable for pin 3 */ +#define GPIO_INTENSET_PIN4_Pos 4 /*!< Interrupt enable for pin 4 */ +#define GPIO_INTENSET_PIN5_Pos 5 /*!< Interrupt enable for pin 5 */ +#define GPIO_INTENSET_PIN6_Pos 6 /*!< Interrupt enable for pin 6 */ +#define GPIO_INTENSET_PIN7_Pos 7 /*!< Interrupt enable for pin 7 */ +#define GPIO_INTENSET_PIN8_Pos 8 /*!< Interrupt enable for pin 8 */ +#define GPIO_INTENSET_PIN9_Pos 9 /*!< Interrupt enable for pin 9 */ +#define GPIO_INTENSET_PIN10_Pos 10 /*!< Interrupt enable for pin 10 */ +#define GPIO_INTENSET_PIN11_Pos 11 /*!< Interrupt enable for pin 11 */ +#define GPIO_INTENSET_PIN12_Pos 12 /*!< Interrupt enable for pin 12 */ +#define GPIO_INTENSET_PIN13_Pos 13 /*!< Interrupt enable for pin 13 */ +#define GPIO_INTENSET_PIN14_Pos 14 /*!< Interrupt enable for pin 14 */ +#define GPIO_INTENSET_PIN15_Pos 15 /*!< Interrupt enable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_INTENSET_PIN0_Msk 0x00000001UL /*!< Interrupt enable for pin 0 */ +#define GPIO_INTENSET_PIN1_Msk 0x00000002UL /*!< Interrupt enable for pin 1 */ +#define GPIO_INTENSET_PIN2_Msk 0x00000004UL /*!< Interrupt enable for pin 2 */ +#define GPIO_INTENSET_PIN3_Msk 0x00000008UL /*!< Interrupt enable for pin 3 */ +#define GPIO_INTENSET_PIN4_Msk 0x00000010UL /*!< Interrupt enable for pin 4 */ +#define GPIO_INTENSET_PIN5_Msk 0x00000020UL /*!< Interrupt enable for pin 5 */ +#define GPIO_INTENSET_PIN6_Msk 0x00000040UL /*!< Interrupt enable for pin 6 */ +#define GPIO_INTENSET_PIN7_Msk 0x00000080UL /*!< Interrupt enable for pin 7 */ +#define GPIO_INTENSET_PIN8_Msk 0x00000100UL /*!< Interrupt enable for pin 8 */ +#define GPIO_INTENSET_PIN9_Msk 0x00000200UL /*!< Interrupt enable for pin 9 */ +#define GPIO_INTENSET_PIN10_Msk 0x00000400UL /*!< Interrupt enable for pin 10 */ +#define GPIO_INTENSET_PIN11_Msk 0x00000800UL /*!< Interrupt enable for pin 11 */ +#define GPIO_INTENSET_PIN12_Msk 0x00001000UL /*!< Interrupt enable for pin 12 */ +#define GPIO_INTENSET_PIN13_Msk 0x00002000UL /*!< Interrupt enable for pin 13 */ +#define GPIO_INTENSET_PIN14_Msk 0x00004000UL /*!< Interrupt enable for pin 14 */ +#define GPIO_INTENSET_PIN15_Msk 0x00008000UL /*!< Interrupt enable for pin 15 */ + +/*-- INTENCLR: Interrupt disable register --------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Interrupt disable for pin 0 */ + uint32_t PIN1 :1; /*!< Interrupt disable for pin 1 */ + uint32_t PIN2 :1; /*!< Interrupt disable for pin 2 */ + uint32_t PIN3 :1; /*!< Interrupt disable for pin 3 */ + uint32_t PIN4 :1; /*!< Interrupt disable for pin 4 */ + uint32_t PIN5 :1; /*!< Interrupt disable for pin 5 */ + uint32_t PIN6 :1; /*!< Interrupt disable for pin 6 */ + uint32_t PIN7 :1; /*!< Interrupt disable for pin 7 */ + uint32_t PIN8 :1; /*!< Interrupt disable for pin 8 */ + uint32_t PIN9 :1; /*!< Interrupt disable for pin 9 */ + uint32_t PIN10 :1; /*!< Interrupt disable for pin 10 */ + uint32_t PIN11 :1; /*!< Interrupt disable for pin 11 */ + uint32_t PIN12 :1; /*!< Interrupt disable for pin 12 */ + uint32_t PIN13 :1; /*!< Interrupt disable for pin 13 */ + uint32_t PIN14 :1; /*!< Interrupt disable for pin 14 */ + uint32_t PIN15 :1; /*!< Interrupt disable for pin 15 */ +} _GPIO_INTENCLR_bits; + +/* Bit field positions: */ +#define GPIO_INTENCLR_PIN0_Pos 0 /*!< Interrupt disable for pin 0 */ +#define GPIO_INTENCLR_PIN1_Pos 1 /*!< Interrupt disable for pin 1 */ +#define GPIO_INTENCLR_PIN2_Pos 2 /*!< Interrupt disable for pin 2 */ +#define GPIO_INTENCLR_PIN3_Pos 3 /*!< Interrupt disable for pin 3 */ +#define GPIO_INTENCLR_PIN4_Pos 4 /*!< Interrupt disable for pin 4 */ +#define GPIO_INTENCLR_PIN5_Pos 5 /*!< Interrupt disable for pin 5 */ +#define GPIO_INTENCLR_PIN6_Pos 6 /*!< Interrupt disable for pin 6 */ +#define GPIO_INTENCLR_PIN7_Pos 7 /*!< Interrupt disable for pin 7 */ +#define GPIO_INTENCLR_PIN8_Pos 8 /*!< Interrupt disable for pin 8 */ +#define GPIO_INTENCLR_PIN9_Pos 9 /*!< Interrupt disable for pin 9 */ +#define GPIO_INTENCLR_PIN10_Pos 10 /*!< Interrupt disable for pin 10 */ +#define GPIO_INTENCLR_PIN11_Pos 11 /*!< Interrupt disable for pin 11 */ +#define GPIO_INTENCLR_PIN12_Pos 12 /*!< Interrupt disable for pin 12 */ +#define GPIO_INTENCLR_PIN13_Pos 13 /*!< Interrupt disable for pin 13 */ +#define GPIO_INTENCLR_PIN14_Pos 14 /*!< Interrupt disable for pin 14 */ +#define GPIO_INTENCLR_PIN15_Pos 15 /*!< Interrupt disable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_INTENCLR_PIN0_Msk 0x00000001UL /*!< Interrupt disable for pin 0 */ +#define GPIO_INTENCLR_PIN1_Msk 0x00000002UL /*!< Interrupt disable for pin 1 */ +#define GPIO_INTENCLR_PIN2_Msk 0x00000004UL /*!< Interrupt disable for pin 2 */ +#define GPIO_INTENCLR_PIN3_Msk 0x00000008UL /*!< Interrupt disable for pin 3 */ +#define GPIO_INTENCLR_PIN4_Msk 0x00000010UL /*!< Interrupt disable for pin 4 */ +#define GPIO_INTENCLR_PIN5_Msk 0x00000020UL /*!< Interrupt disable for pin 5 */ +#define GPIO_INTENCLR_PIN6_Msk 0x00000040UL /*!< Interrupt disable for pin 6 */ +#define GPIO_INTENCLR_PIN7_Msk 0x00000080UL /*!< Interrupt disable for pin 7 */ +#define GPIO_INTENCLR_PIN8_Msk 0x00000100UL /*!< Interrupt disable for pin 8 */ +#define GPIO_INTENCLR_PIN9_Msk 0x00000200UL /*!< Interrupt disable for pin 9 */ +#define GPIO_INTENCLR_PIN10_Msk 0x00000400UL /*!< Interrupt disable for pin 10 */ +#define GPIO_INTENCLR_PIN11_Msk 0x00000800UL /*!< Interrupt disable for pin 11 */ +#define GPIO_INTENCLR_PIN12_Msk 0x00001000UL /*!< Interrupt disable for pin 12 */ +#define GPIO_INTENCLR_PIN13_Msk 0x00002000UL /*!< Interrupt disable for pin 13 */ +#define GPIO_INTENCLR_PIN14_Msk 0x00004000UL /*!< Interrupt disable for pin 14 */ +#define GPIO_INTENCLR_PIN15_Msk 0x00008000UL /*!< Interrupt disable for pin 15 */ + +/*-- INTTYPESET: Interrupt type set register -----------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Interrupt type set for pin 0 */ + uint32_t PIN1 :1; /*!< Interrupt type set for pin 1 */ + uint32_t PIN2 :1; /*!< Interrupt type set for pin 2 */ + uint32_t PIN3 :1; /*!< Interrupt type set for pin 3 */ + uint32_t PIN4 :1; /*!< Interrupt type set for pin 4 */ + uint32_t PIN5 :1; /*!< Interrupt type set for pin 5 */ + uint32_t PIN6 :1; /*!< Interrupt type set for pin 6 */ + uint32_t PIN7 :1; /*!< Interrupt type set for pin 7 */ + uint32_t PIN8 :1; /*!< Interrupt type set for pin 8 */ + uint32_t PIN9 :1; /*!< Interrupt type set for pin 9 */ + uint32_t PIN10 :1; /*!< Interrupt type set for pin 10 */ + uint32_t PIN11 :1; /*!< Interrupt type set for pin 11 */ + uint32_t PIN12 :1; /*!< Interrupt type set for pin 12 */ + uint32_t PIN13 :1; /*!< Interrupt type set for pin 13 */ + uint32_t PIN14 :1; /*!< Interrupt type set for pin 14 */ + uint32_t PIN15 :1; /*!< Interrupt type set for pin 15 */ +} _GPIO_INTTYPESET_bits; + +/* Bit field positions: */ +#define GPIO_INTTYPESET_PIN0_Pos 0 /*!< Interrupt type set for pin 0 */ +#define GPIO_INTTYPESET_PIN1_Pos 1 /*!< Interrupt type set for pin 1 */ +#define GPIO_INTTYPESET_PIN2_Pos 2 /*!< Interrupt type set for pin 2 */ +#define GPIO_INTTYPESET_PIN3_Pos 3 /*!< Interrupt type set for pin 3 */ +#define GPIO_INTTYPESET_PIN4_Pos 4 /*!< Interrupt type set for pin 4 */ +#define GPIO_INTTYPESET_PIN5_Pos 5 /*!< Interrupt type set for pin 5 */ +#define GPIO_INTTYPESET_PIN6_Pos 6 /*!< Interrupt type set for pin 6 */ +#define GPIO_INTTYPESET_PIN7_Pos 7 /*!< Interrupt type set for pin 7 */ +#define GPIO_INTTYPESET_PIN8_Pos 8 /*!< Interrupt type set for pin 8 */ +#define GPIO_INTTYPESET_PIN9_Pos 9 /*!< Interrupt type set for pin 9 */ +#define GPIO_INTTYPESET_PIN10_Pos 10 /*!< Interrupt type set for pin 10 */ +#define GPIO_INTTYPESET_PIN11_Pos 11 /*!< Interrupt type set for pin 11 */ +#define GPIO_INTTYPESET_PIN12_Pos 12 /*!< Interrupt type set for pin 12 */ +#define GPIO_INTTYPESET_PIN13_Pos 13 /*!< Interrupt type set for pin 13 */ +#define GPIO_INTTYPESET_PIN14_Pos 14 /*!< Interrupt type set for pin 14 */ +#define GPIO_INTTYPESET_PIN15_Pos 15 /*!< Interrupt type set for pin 15 */ + +/* Bit field masks: */ +#define GPIO_INTTYPESET_PIN0_Msk 0x00000001UL /*!< Interrupt type set for pin 0 */ +#define GPIO_INTTYPESET_PIN1_Msk 0x00000002UL /*!< Interrupt type set for pin 1 */ +#define GPIO_INTTYPESET_PIN2_Msk 0x00000004UL /*!< Interrupt type set for pin 2 */ +#define GPIO_INTTYPESET_PIN3_Msk 0x00000008UL /*!< Interrupt type set for pin 3 */ +#define GPIO_INTTYPESET_PIN4_Msk 0x00000010UL /*!< Interrupt type set for pin 4 */ +#define GPIO_INTTYPESET_PIN5_Msk 0x00000020UL /*!< Interrupt type set for pin 5 */ +#define GPIO_INTTYPESET_PIN6_Msk 0x00000040UL /*!< Interrupt type set for pin 6 */ +#define GPIO_INTTYPESET_PIN7_Msk 0x00000080UL /*!< Interrupt type set for pin 7 */ +#define GPIO_INTTYPESET_PIN8_Msk 0x00000100UL /*!< Interrupt type set for pin 8 */ +#define GPIO_INTTYPESET_PIN9_Msk 0x00000200UL /*!< Interrupt type set for pin 9 */ +#define GPIO_INTTYPESET_PIN10_Msk 0x00000400UL /*!< Interrupt type set for pin 10 */ +#define GPIO_INTTYPESET_PIN11_Msk 0x00000800UL /*!< Interrupt type set for pin 11 */ +#define GPIO_INTTYPESET_PIN12_Msk 0x00001000UL /*!< Interrupt type set for pin 12 */ +#define GPIO_INTTYPESET_PIN13_Msk 0x00002000UL /*!< Interrupt type set for pin 13 */ +#define GPIO_INTTYPESET_PIN14_Msk 0x00004000UL /*!< Interrupt type set for pin 14 */ +#define GPIO_INTTYPESET_PIN15_Msk 0x00008000UL /*!< Interrupt type set for pin 15 */ + +/*-- INTTYPECLR: Interrupt type clear register ---------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Interrupt type clear for pin 0 */ + uint32_t PIN1 :1; /*!< Interrupt type clear for pin 1 */ + uint32_t PIN2 :1; /*!< Interrupt type clear for pin 2 */ + uint32_t PIN3 :1; /*!< Interrupt type clear for pin 3 */ + uint32_t PIN4 :1; /*!< Interrupt type clear for pin 4 */ + uint32_t PIN5 :1; /*!< Interrupt type clear for pin 5 */ + uint32_t PIN6 :1; /*!< Interrupt type clear for pin 6 */ + uint32_t PIN7 :1; /*!< Interrupt type clear for pin 7 */ + uint32_t PIN8 :1; /*!< Interrupt type clear for pin 8 */ + uint32_t PIN9 :1; /*!< Interrupt type clear for pin 9 */ + uint32_t PIN10 :1; /*!< Interrupt type clear for pin 10 */ + uint32_t PIN11 :1; /*!< Interrupt type clear for pin 11 */ + uint32_t PIN12 :1; /*!< Interrupt type clear for pin 12 */ + uint32_t PIN13 :1; /*!< Interrupt type clear for pin 13 */ + uint32_t PIN14 :1; /*!< Interrupt type clear for pin 14 */ + uint32_t PIN15 :1; /*!< Interrupt type clear for pin 15 */ +} _GPIO_INTTYPECLR_bits; + +/* Bit field positions: */ +#define GPIO_INTTYPECLR_PIN0_Pos 0 /*!< Interrupt type clear for pin 0 */ +#define GPIO_INTTYPECLR_PIN1_Pos 1 /*!< Interrupt type clear for pin 1 */ +#define GPIO_INTTYPECLR_PIN2_Pos 2 /*!< Interrupt type clear for pin 2 */ +#define GPIO_INTTYPECLR_PIN3_Pos 3 /*!< Interrupt type clear for pin 3 */ +#define GPIO_INTTYPECLR_PIN4_Pos 4 /*!< Interrupt type clear for pin 4 */ +#define GPIO_INTTYPECLR_PIN5_Pos 5 /*!< Interrupt type clear for pin 5 */ +#define GPIO_INTTYPECLR_PIN6_Pos 6 /*!< Interrupt type clear for pin 6 */ +#define GPIO_INTTYPECLR_PIN7_Pos 7 /*!< Interrupt type clear for pin 7 */ +#define GPIO_INTTYPECLR_PIN8_Pos 8 /*!< Interrupt type clear for pin 8 */ +#define GPIO_INTTYPECLR_PIN9_Pos 9 /*!< Interrupt type clear for pin 9 */ +#define GPIO_INTTYPECLR_PIN10_Pos 10 /*!< Interrupt type clear for pin 10 */ +#define GPIO_INTTYPECLR_PIN11_Pos 11 /*!< Interrupt type clear for pin 11 */ +#define GPIO_INTTYPECLR_PIN12_Pos 12 /*!< Interrupt type clear for pin 12 */ +#define GPIO_INTTYPECLR_PIN13_Pos 13 /*!< Interrupt type clear for pin 13 */ +#define GPIO_INTTYPECLR_PIN14_Pos 14 /*!< Interrupt type clear for pin 14 */ +#define GPIO_INTTYPECLR_PIN15_Pos 15 /*!< Interrupt type clear for pin 15 */ + +/* Bit field masks: */ +#define GPIO_INTTYPECLR_PIN0_Msk 0x00000001UL /*!< Interrupt type clear for pin 0 */ +#define GPIO_INTTYPECLR_PIN1_Msk 0x00000002UL /*!< Interrupt type clear for pin 1 */ +#define GPIO_INTTYPECLR_PIN2_Msk 0x00000004UL /*!< Interrupt type clear for pin 2 */ +#define GPIO_INTTYPECLR_PIN3_Msk 0x00000008UL /*!< Interrupt type clear for pin 3 */ +#define GPIO_INTTYPECLR_PIN4_Msk 0x00000010UL /*!< Interrupt type clear for pin 4 */ +#define GPIO_INTTYPECLR_PIN5_Msk 0x00000020UL /*!< Interrupt type clear for pin 5 */ +#define GPIO_INTTYPECLR_PIN6_Msk 0x00000040UL /*!< Interrupt type clear for pin 6 */ +#define GPIO_INTTYPECLR_PIN7_Msk 0x00000080UL /*!< Interrupt type clear for pin 7 */ +#define GPIO_INTTYPECLR_PIN8_Msk 0x00000100UL /*!< Interrupt type clear for pin 8 */ +#define GPIO_INTTYPECLR_PIN9_Msk 0x00000200UL /*!< Interrupt type clear for pin 9 */ +#define GPIO_INTTYPECLR_PIN10_Msk 0x00000400UL /*!< Interrupt type clear for pin 10 */ +#define GPIO_INTTYPECLR_PIN11_Msk 0x00000800UL /*!< Interrupt type clear for pin 11 */ +#define GPIO_INTTYPECLR_PIN12_Msk 0x00001000UL /*!< Interrupt type clear for pin 12 */ +#define GPIO_INTTYPECLR_PIN13_Msk 0x00002000UL /*!< Interrupt type clear for pin 13 */ +#define GPIO_INTTYPECLR_PIN14_Msk 0x00004000UL /*!< Interrupt type clear for pin 14 */ +#define GPIO_INTTYPECLR_PIN15_Msk 0x00008000UL /*!< Interrupt type clear for pin 15 */ + +/*-- INTPOLSET: Interrupt polarity set register --------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Interrupt polarity set for pin 0 */ + uint32_t PIN1 :1; /*!< Interrupt polarity set for pin 1 */ + uint32_t PIN2 :1; /*!< Interrupt polarity set for pin 2 */ + uint32_t PIN3 :1; /*!< Interrupt polarity set for pin 3 */ + uint32_t PIN4 :1; /*!< Interrupt polarity set for pin 4 */ + uint32_t PIN5 :1; /*!< Interrupt polarity set for pin 5 */ + uint32_t PIN6 :1; /*!< Interrupt polarity set for pin 6 */ + uint32_t PIN7 :1; /*!< Interrupt polarity set for pin 7 */ + uint32_t PIN8 :1; /*!< Interrupt polarity set for pin 8 */ + uint32_t PIN9 :1; /*!< Interrupt polarity set for pin 9 */ + uint32_t PIN10 :1; /*!< Interrupt polarity set for pin 10 */ + uint32_t PIN11 :1; /*!< Interrupt polarity set for pin 11 */ + uint32_t PIN12 :1; /*!< Interrupt polarity set for pin 12 */ + uint32_t PIN13 :1; /*!< Interrupt polarity set for pin 13 */ + uint32_t PIN14 :1; /*!< Interrupt polarity set for pin 14 */ + uint32_t PIN15 :1; /*!< Interrupt polarity set for pin 15 */ +} _GPIO_INTPOLSET_bits; + +/* Bit field positions: */ +#define GPIO_INTPOLSET_PIN0_Pos 0 /*!< Interrupt polarity set for pin 0 */ +#define GPIO_INTPOLSET_PIN1_Pos 1 /*!< Interrupt polarity set for pin 1 */ +#define GPIO_INTPOLSET_PIN2_Pos 2 /*!< Interrupt polarity set for pin 2 */ +#define GPIO_INTPOLSET_PIN3_Pos 3 /*!< Interrupt polarity set for pin 3 */ +#define GPIO_INTPOLSET_PIN4_Pos 4 /*!< Interrupt polarity set for pin 4 */ +#define GPIO_INTPOLSET_PIN5_Pos 5 /*!< Interrupt polarity set for pin 5 */ +#define GPIO_INTPOLSET_PIN6_Pos 6 /*!< Interrupt polarity set for pin 6 */ +#define GPIO_INTPOLSET_PIN7_Pos 7 /*!< Interrupt polarity set for pin 7 */ +#define GPIO_INTPOLSET_PIN8_Pos 8 /*!< Interrupt polarity set for pin 8 */ +#define GPIO_INTPOLSET_PIN9_Pos 9 /*!< Interrupt polarity set for pin 9 */ +#define GPIO_INTPOLSET_PIN10_Pos 10 /*!< Interrupt polarity set for pin 10 */ +#define GPIO_INTPOLSET_PIN11_Pos 11 /*!< Interrupt polarity set for pin 11 */ +#define GPIO_INTPOLSET_PIN12_Pos 12 /*!< Interrupt polarity set for pin 12 */ +#define GPIO_INTPOLSET_PIN13_Pos 13 /*!< Interrupt polarity set for pin 13 */ +#define GPIO_INTPOLSET_PIN14_Pos 14 /*!< Interrupt polarity set for pin 14 */ +#define GPIO_INTPOLSET_PIN15_Pos 15 /*!< Interrupt polarity set for pin 15 */ + +/* Bit field masks: */ +#define GPIO_INTPOLSET_PIN0_Msk 0x00000001UL /*!< Interrupt polarity set for pin 0 */ +#define GPIO_INTPOLSET_PIN1_Msk 0x00000002UL /*!< Interrupt polarity set for pin 1 */ +#define GPIO_INTPOLSET_PIN2_Msk 0x00000004UL /*!< Interrupt polarity set for pin 2 */ +#define GPIO_INTPOLSET_PIN3_Msk 0x00000008UL /*!< Interrupt polarity set for pin 3 */ +#define GPIO_INTPOLSET_PIN4_Msk 0x00000010UL /*!< Interrupt polarity set for pin 4 */ +#define GPIO_INTPOLSET_PIN5_Msk 0x00000020UL /*!< Interrupt polarity set for pin 5 */ +#define GPIO_INTPOLSET_PIN6_Msk 0x00000040UL /*!< Interrupt polarity set for pin 6 */ +#define GPIO_INTPOLSET_PIN7_Msk 0x00000080UL /*!< Interrupt polarity set for pin 7 */ +#define GPIO_INTPOLSET_PIN8_Msk 0x00000100UL /*!< Interrupt polarity set for pin 8 */ +#define GPIO_INTPOLSET_PIN9_Msk 0x00000200UL /*!< Interrupt polarity set for pin 9 */ +#define GPIO_INTPOLSET_PIN10_Msk 0x00000400UL /*!< Interrupt polarity set for pin 10 */ +#define GPIO_INTPOLSET_PIN11_Msk 0x00000800UL /*!< Interrupt polarity set for pin 11 */ +#define GPIO_INTPOLSET_PIN12_Msk 0x00001000UL /*!< Interrupt polarity set for pin 12 */ +#define GPIO_INTPOLSET_PIN13_Msk 0x00002000UL /*!< Interrupt polarity set for pin 13 */ +#define GPIO_INTPOLSET_PIN14_Msk 0x00004000UL /*!< Interrupt polarity set for pin 14 */ +#define GPIO_INTPOLSET_PIN15_Msk 0x00008000UL /*!< Interrupt polarity set for pin 15 */ + +/*-- INTPOLCLR: Interrupt polarity clear register ------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Interrupt polarity clear for pin 0 */ + uint32_t PIN1 :1; /*!< Interrupt polarity clear for pin 1 */ + uint32_t PIN2 :1; /*!< Interrupt polarity clear for pin 2 */ + uint32_t PIN3 :1; /*!< Interrupt polarity clear for pin 3 */ + uint32_t PIN4 :1; /*!< Interrupt polarity clear for pin 4 */ + uint32_t PIN5 :1; /*!< Interrupt polarity clear for pin 5 */ + uint32_t PIN6 :1; /*!< Interrupt polarity clear for pin 6 */ + uint32_t PIN7 :1; /*!< Interrupt polarity clear for pin 7 */ + uint32_t PIN8 :1; /*!< Interrupt polarity clear for pin 8 */ + uint32_t PIN9 :1; /*!< Interrupt polarity clear for pin 9 */ + uint32_t PIN10 :1; /*!< Interrupt polarity clear for pin 10 */ + uint32_t PIN11 :1; /*!< Interrupt polarity clear for pin 11 */ + uint32_t PIN12 :1; /*!< Interrupt polarity clear for pin 12 */ + uint32_t PIN13 :1; /*!< Interrupt polarity clear for pin 13 */ + uint32_t PIN14 :1; /*!< Interrupt polarity clear for pin 14 */ + uint32_t PIN15 :1; /*!< Interrupt polarity clear for pin 15 */ +} _GPIO_INTPOLCLR_bits; + +/* Bit field positions: */ +#define GPIO_INTPOLCLR_PIN0_Pos 0 /*!< Interrupt polarity clear for pin 0 */ +#define GPIO_INTPOLCLR_PIN1_Pos 1 /*!< Interrupt polarity clear for pin 1 */ +#define GPIO_INTPOLCLR_PIN2_Pos 2 /*!< Interrupt polarity clear for pin 2 */ +#define GPIO_INTPOLCLR_PIN3_Pos 3 /*!< Interrupt polarity clear for pin 3 */ +#define GPIO_INTPOLCLR_PIN4_Pos 4 /*!< Interrupt polarity clear for pin 4 */ +#define GPIO_INTPOLCLR_PIN5_Pos 5 /*!< Interrupt polarity clear for pin 5 */ +#define GPIO_INTPOLCLR_PIN6_Pos 6 /*!< Interrupt polarity clear for pin 6 */ +#define GPIO_INTPOLCLR_PIN7_Pos 7 /*!< Interrupt polarity clear for pin 7 */ +#define GPIO_INTPOLCLR_PIN8_Pos 8 /*!< Interrupt polarity clear for pin 8 */ +#define GPIO_INTPOLCLR_PIN9_Pos 9 /*!< Interrupt polarity clear for pin 9 */ +#define GPIO_INTPOLCLR_PIN10_Pos 10 /*!< Interrupt polarity clear for pin 10 */ +#define GPIO_INTPOLCLR_PIN11_Pos 11 /*!< Interrupt polarity clear for pin 11 */ +#define GPIO_INTPOLCLR_PIN12_Pos 12 /*!< Interrupt polarity clear for pin 12 */ +#define GPIO_INTPOLCLR_PIN13_Pos 13 /*!< Interrupt polarity clear for pin 13 */ +#define GPIO_INTPOLCLR_PIN14_Pos 14 /*!< Interrupt polarity clear for pin 14 */ +#define GPIO_INTPOLCLR_PIN15_Pos 15 /*!< Interrupt polarity clear for pin 15 */ + +/* Bit field masks: */ +#define GPIO_INTPOLCLR_PIN0_Msk 0x00000001UL /*!< Interrupt polarity clear for pin 0 */ +#define GPIO_INTPOLCLR_PIN1_Msk 0x00000002UL /*!< Interrupt polarity clear for pin 1 */ +#define GPIO_INTPOLCLR_PIN2_Msk 0x00000004UL /*!< Interrupt polarity clear for pin 2 */ +#define GPIO_INTPOLCLR_PIN3_Msk 0x00000008UL /*!< Interrupt polarity clear for pin 3 */ +#define GPIO_INTPOLCLR_PIN4_Msk 0x00000010UL /*!< Interrupt polarity clear for pin 4 */ +#define GPIO_INTPOLCLR_PIN5_Msk 0x00000020UL /*!< Interrupt polarity clear for pin 5 */ +#define GPIO_INTPOLCLR_PIN6_Msk 0x00000040UL /*!< Interrupt polarity clear for pin 6 */ +#define GPIO_INTPOLCLR_PIN7_Msk 0x00000080UL /*!< Interrupt polarity clear for pin 7 */ +#define GPIO_INTPOLCLR_PIN8_Msk 0x00000100UL /*!< Interrupt polarity clear for pin 8 */ +#define GPIO_INTPOLCLR_PIN9_Msk 0x00000200UL /*!< Interrupt polarity clear for pin 9 */ +#define GPIO_INTPOLCLR_PIN10_Msk 0x00000400UL /*!< Interrupt polarity clear for pin 10 */ +#define GPIO_INTPOLCLR_PIN11_Msk 0x00000800UL /*!< Interrupt polarity clear for pin 11 */ +#define GPIO_INTPOLCLR_PIN12_Msk 0x00001000UL /*!< Interrupt polarity clear for pin 12 */ +#define GPIO_INTPOLCLR_PIN13_Msk 0x00002000UL /*!< Interrupt polarity clear for pin 13 */ +#define GPIO_INTPOLCLR_PIN14_Msk 0x00004000UL /*!< Interrupt polarity clear for pin 14 */ +#define GPIO_INTPOLCLR_PIN15_Msk 0x00008000UL /*!< Interrupt polarity clear for pin 15 */ + +/*-- INTEDGESET: Interrupt every edge set register -----------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Interrupt every edge set for pin 0 */ + uint32_t PIN1 :1; /*!< Interrupt every edge set for pin 1 */ + uint32_t PIN2 :1; /*!< Interrupt every edge set for pin 2 */ + uint32_t PIN3 :1; /*!< Interrupt every edge set for pin 3 */ + uint32_t PIN4 :1; /*!< Interrupt every edge set for pin 4 */ + uint32_t PIN5 :1; /*!< Interrupt every edge set for pin 5 */ + uint32_t PIN6 :1; /*!< Interrupt every edge set for pin 6 */ + uint32_t PIN7 :1; /*!< Interrupt every edge set for pin 7 */ + uint32_t PIN8 :1; /*!< Interrupt every edge set for pin 8 */ + uint32_t PIN9 :1; /*!< Interrupt every edge set for pin 9 */ + uint32_t PIN10 :1; /*!< Interrupt every edge set for pin 10 */ + uint32_t PIN11 :1; /*!< Interrupt every edge set for pin 11 */ + uint32_t PIN12 :1; /*!< Interrupt every edge set for pin 12 */ + uint32_t PIN13 :1; /*!< Interrupt every edge set for pin 13 */ + uint32_t PIN14 :1; /*!< Interrupt every edge set for pin 14 */ + uint32_t PIN15 :1; /*!< Interrupt every edge set for pin 15 */ +} _GPIO_INTEDGESET_bits; + +/* Bit field positions: */ +#define GPIO_INTEDGESET_PIN0_Pos 0 /*!< Interrupt every edge set for pin 0 */ +#define GPIO_INTEDGESET_PIN1_Pos 1 /*!< Interrupt every edge set for pin 1 */ +#define GPIO_INTEDGESET_PIN2_Pos 2 /*!< Interrupt every edge set for pin 2 */ +#define GPIO_INTEDGESET_PIN3_Pos 3 /*!< Interrupt every edge set for pin 3 */ +#define GPIO_INTEDGESET_PIN4_Pos 4 /*!< Interrupt every edge set for pin 4 */ +#define GPIO_INTEDGESET_PIN5_Pos 5 /*!< Interrupt every edge set for pin 5 */ +#define GPIO_INTEDGESET_PIN6_Pos 6 /*!< Interrupt every edge set for pin 6 */ +#define GPIO_INTEDGESET_PIN7_Pos 7 /*!< Interrupt every edge set for pin 7 */ +#define GPIO_INTEDGESET_PIN8_Pos 8 /*!< Interrupt every edge set for pin 8 */ +#define GPIO_INTEDGESET_PIN9_Pos 9 /*!< Interrupt every edge set for pin 9 */ +#define GPIO_INTEDGESET_PIN10_Pos 10 /*!< Interrupt every edge set for pin 10 */ +#define GPIO_INTEDGESET_PIN11_Pos 11 /*!< Interrupt every edge set for pin 11 */ +#define GPIO_INTEDGESET_PIN12_Pos 12 /*!< Interrupt every edge set for pin 12 */ +#define GPIO_INTEDGESET_PIN13_Pos 13 /*!< Interrupt every edge set for pin 13 */ +#define GPIO_INTEDGESET_PIN14_Pos 14 /*!< Interrupt every edge set for pin 14 */ +#define GPIO_INTEDGESET_PIN15_Pos 15 /*!< Interrupt every edge set for pin 15 */ + +/* Bit field masks: */ +#define GPIO_INTEDGESET_PIN0_Msk 0x00000001UL /*!< Interrupt every edge set for pin 0 */ +#define GPIO_INTEDGESET_PIN1_Msk 0x00000002UL /*!< Interrupt every edge set for pin 1 */ +#define GPIO_INTEDGESET_PIN2_Msk 0x00000004UL /*!< Interrupt every edge set for pin 2 */ +#define GPIO_INTEDGESET_PIN3_Msk 0x00000008UL /*!< Interrupt every edge set for pin 3 */ +#define GPIO_INTEDGESET_PIN4_Msk 0x00000010UL /*!< Interrupt every edge set for pin 4 */ +#define GPIO_INTEDGESET_PIN5_Msk 0x00000020UL /*!< Interrupt every edge set for pin 5 */ +#define GPIO_INTEDGESET_PIN6_Msk 0x00000040UL /*!< Interrupt every edge set for pin 6 */ +#define GPIO_INTEDGESET_PIN7_Msk 0x00000080UL /*!< Interrupt every edge set for pin 7 */ +#define GPIO_INTEDGESET_PIN8_Msk 0x00000100UL /*!< Interrupt every edge set for pin 8 */ +#define GPIO_INTEDGESET_PIN9_Msk 0x00000200UL /*!< Interrupt every edge set for pin 9 */ +#define GPIO_INTEDGESET_PIN10_Msk 0x00000400UL /*!< Interrupt every edge set for pin 10 */ +#define GPIO_INTEDGESET_PIN11_Msk 0x00000800UL /*!< Interrupt every edge set for pin 11 */ +#define GPIO_INTEDGESET_PIN12_Msk 0x00001000UL /*!< Interrupt every edge set for pin 12 */ +#define GPIO_INTEDGESET_PIN13_Msk 0x00002000UL /*!< Interrupt every edge set for pin 13 */ +#define GPIO_INTEDGESET_PIN14_Msk 0x00004000UL /*!< Interrupt every edge set for pin 14 */ +#define GPIO_INTEDGESET_PIN15_Msk 0x00008000UL /*!< Interrupt every edge set for pin 15 */ + +/*-- INTEDGECLR: Interrupt every edge clear register ---------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Interrupt every edge clear for pin 0 */ + uint32_t PIN1 :1; /*!< Interrupt every edge clear for pin 1 */ + uint32_t PIN2 :1; /*!< Interrupt every edge clear for pin 2 */ + uint32_t PIN3 :1; /*!< Interrupt every edge clear for pin 3 */ + uint32_t PIN4 :1; /*!< Interrupt every edge clear for pin 4 */ + uint32_t PIN5 :1; /*!< Interrupt every edge clear for pin 5 */ + uint32_t PIN6 :1; /*!< Interrupt every edge clear for pin 6 */ + uint32_t PIN7 :1; /*!< Interrupt every edge clear for pin 7 */ + uint32_t PIN8 :1; /*!< Interrupt every edge clear for pin 8 */ + uint32_t PIN9 :1; /*!< Interrupt every edge clear for pin 9 */ + uint32_t PIN10 :1; /*!< Interrupt every edge clear for pin 10 */ + uint32_t PIN11 :1; /*!< Interrupt every edge clear for pin 11 */ + uint32_t PIN12 :1; /*!< Interrupt every edge clear for pin 12 */ + uint32_t PIN13 :1; /*!< Interrupt every edge clear for pin 13 */ + uint32_t PIN14 :1; /*!< Interrupt every edge clear for pin 14 */ + uint32_t PIN15 :1; /*!< Interrupt every edge clear for pin 15 */ +} _GPIO_INTEDGECLR_bits; + +/* Bit field positions: */ +#define GPIO_INTEDGECLR_PIN0_Pos 0 /*!< Interrupt every edge clear for pin 0 */ +#define GPIO_INTEDGECLR_PIN1_Pos 1 /*!< Interrupt every edge clear for pin 1 */ +#define GPIO_INTEDGECLR_PIN2_Pos 2 /*!< Interrupt every edge clear for pin 2 */ +#define GPIO_INTEDGECLR_PIN3_Pos 3 /*!< Interrupt every edge clear for pin 3 */ +#define GPIO_INTEDGECLR_PIN4_Pos 4 /*!< Interrupt every edge clear for pin 4 */ +#define GPIO_INTEDGECLR_PIN5_Pos 5 /*!< Interrupt every edge clear for pin 5 */ +#define GPIO_INTEDGECLR_PIN6_Pos 6 /*!< Interrupt every edge clear for pin 6 */ +#define GPIO_INTEDGECLR_PIN7_Pos 7 /*!< Interrupt every edge clear for pin 7 */ +#define GPIO_INTEDGECLR_PIN8_Pos 8 /*!< Interrupt every edge clear for pin 8 */ +#define GPIO_INTEDGECLR_PIN9_Pos 9 /*!< Interrupt every edge clear for pin 9 */ +#define GPIO_INTEDGECLR_PIN10_Pos 10 /*!< Interrupt every edge clear for pin 10 */ +#define GPIO_INTEDGECLR_PIN11_Pos 11 /*!< Interrupt every edge clear for pin 11 */ +#define GPIO_INTEDGECLR_PIN12_Pos 12 /*!< Interrupt every edge clear for pin 12 */ +#define GPIO_INTEDGECLR_PIN13_Pos 13 /*!< Interrupt every edge clear for pin 13 */ +#define GPIO_INTEDGECLR_PIN14_Pos 14 /*!< Interrupt every edge clear for pin 14 */ +#define GPIO_INTEDGECLR_PIN15_Pos 15 /*!< Interrupt every edge clear for pin 15 */ + +/* Bit field masks: */ +#define GPIO_INTEDGECLR_PIN0_Msk 0x00000001UL /*!< Interrupt every edge clear for pin 0 */ +#define GPIO_INTEDGECLR_PIN1_Msk 0x00000002UL /*!< Interrupt every edge clear for pin 1 */ +#define GPIO_INTEDGECLR_PIN2_Msk 0x00000004UL /*!< Interrupt every edge clear for pin 2 */ +#define GPIO_INTEDGECLR_PIN3_Msk 0x00000008UL /*!< Interrupt every edge clear for pin 3 */ +#define GPIO_INTEDGECLR_PIN4_Msk 0x00000010UL /*!< Interrupt every edge clear for pin 4 */ +#define GPIO_INTEDGECLR_PIN5_Msk 0x00000020UL /*!< Interrupt every edge clear for pin 5 */ +#define GPIO_INTEDGECLR_PIN6_Msk 0x00000040UL /*!< Interrupt every edge clear for pin 6 */ +#define GPIO_INTEDGECLR_PIN7_Msk 0x00000080UL /*!< Interrupt every edge clear for pin 7 */ +#define GPIO_INTEDGECLR_PIN8_Msk 0x00000100UL /*!< Interrupt every edge clear for pin 8 */ +#define GPIO_INTEDGECLR_PIN9_Msk 0x00000200UL /*!< Interrupt every edge clear for pin 9 */ +#define GPIO_INTEDGECLR_PIN10_Msk 0x00000400UL /*!< Interrupt every edge clear for pin 10 */ +#define GPIO_INTEDGECLR_PIN11_Msk 0x00000800UL /*!< Interrupt every edge clear for pin 11 */ +#define GPIO_INTEDGECLR_PIN12_Msk 0x00001000UL /*!< Interrupt every edge clear for pin 12 */ +#define GPIO_INTEDGECLR_PIN13_Msk 0x00002000UL /*!< Interrupt every edge clear for pin 13 */ +#define GPIO_INTEDGECLR_PIN14_Msk 0x00004000UL /*!< Interrupt every edge clear for pin 14 */ +#define GPIO_INTEDGECLR_PIN15_Msk 0x00008000UL /*!< Interrupt every edge clear for pin 15 */ + +/*-- INTSTATUS: Interrupt status -----------------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Interrupt status of pin 0 */ + uint32_t PIN1 :1; /*!< Interrupt status of pin 1 */ + uint32_t PIN2 :1; /*!< Interrupt status of pin 2 */ + uint32_t PIN3 :1; /*!< Interrupt status of pin 3 */ + uint32_t PIN4 :1; /*!< Interrupt status of pin 4 */ + uint32_t PIN5 :1; /*!< Interrupt status of pin 5 */ + uint32_t PIN6 :1; /*!< Interrupt status of pin 6 */ + uint32_t PIN7 :1; /*!< Interrupt status of pin 7 */ + uint32_t PIN8 :1; /*!< Interrupt status of pin 8 */ + uint32_t PIN9 :1; /*!< Interrupt status of pin 9 */ + uint32_t PIN10 :1; /*!< Interrupt status of pin 10 */ + uint32_t PIN11 :1; /*!< Interrupt status of pin 11 */ + uint32_t PIN12 :1; /*!< Interrupt status of pin 12 */ + uint32_t PIN13 :1; /*!< Interrupt status of pin 13 */ + uint32_t PIN14 :1; /*!< Interrupt status of pin 14 */ + uint32_t PIN15 :1; /*!< Interrupt status of pin 15 */ +} _GPIO_INTSTATUS_bits; + +/* Bit field positions: */ +#define GPIO_INTSTATUS_PIN0_Pos 0 /*!< Interrupt status of pin 0 */ +#define GPIO_INTSTATUS_PIN1_Pos 1 /*!< Interrupt status of pin 1 */ +#define GPIO_INTSTATUS_PIN2_Pos 2 /*!< Interrupt status of pin 2 */ +#define GPIO_INTSTATUS_PIN3_Pos 3 /*!< Interrupt status of pin 3 */ +#define GPIO_INTSTATUS_PIN4_Pos 4 /*!< Interrupt status of pin 4 */ +#define GPIO_INTSTATUS_PIN5_Pos 5 /*!< Interrupt status of pin 5 */ +#define GPIO_INTSTATUS_PIN6_Pos 6 /*!< Interrupt status of pin 6 */ +#define GPIO_INTSTATUS_PIN7_Pos 7 /*!< Interrupt status of pin 7 */ +#define GPIO_INTSTATUS_PIN8_Pos 8 /*!< Interrupt status of pin 8 */ +#define GPIO_INTSTATUS_PIN9_Pos 9 /*!< Interrupt status of pin 9 */ +#define GPIO_INTSTATUS_PIN10_Pos 10 /*!< Interrupt status of pin 10 */ +#define GPIO_INTSTATUS_PIN11_Pos 11 /*!< Interrupt status of pin 11 */ +#define GPIO_INTSTATUS_PIN12_Pos 12 /*!< Interrupt status of pin 12 */ +#define GPIO_INTSTATUS_PIN13_Pos 13 /*!< Interrupt status of pin 13 */ +#define GPIO_INTSTATUS_PIN14_Pos 14 /*!< Interrupt status of pin 14 */ +#define GPIO_INTSTATUS_PIN15_Pos 15 /*!< Interrupt status of pin 15 */ + +/* Bit field masks: */ +#define GPIO_INTSTATUS_PIN0_Msk 0x00000001UL /*!< Interrupt status of pin 0 */ +#define GPIO_INTSTATUS_PIN1_Msk 0x00000002UL /*!< Interrupt status of pin 1 */ +#define GPIO_INTSTATUS_PIN2_Msk 0x00000004UL /*!< Interrupt status of pin 2 */ +#define GPIO_INTSTATUS_PIN3_Msk 0x00000008UL /*!< Interrupt status of pin 3 */ +#define GPIO_INTSTATUS_PIN4_Msk 0x00000010UL /*!< Interrupt status of pin 4 */ +#define GPIO_INTSTATUS_PIN5_Msk 0x00000020UL /*!< Interrupt status of pin 5 */ +#define GPIO_INTSTATUS_PIN6_Msk 0x00000040UL /*!< Interrupt status of pin 6 */ +#define GPIO_INTSTATUS_PIN7_Msk 0x00000080UL /*!< Interrupt status of pin 7 */ +#define GPIO_INTSTATUS_PIN8_Msk 0x00000100UL /*!< Interrupt status of pin 8 */ +#define GPIO_INTSTATUS_PIN9_Msk 0x00000200UL /*!< Interrupt status of pin 9 */ +#define GPIO_INTSTATUS_PIN10_Msk 0x00000400UL /*!< Interrupt status of pin 10 */ +#define GPIO_INTSTATUS_PIN11_Msk 0x00000800UL /*!< Interrupt status of pin 11 */ +#define GPIO_INTSTATUS_PIN12_Msk 0x00001000UL /*!< Interrupt status of pin 12 */ +#define GPIO_INTSTATUS_PIN13_Msk 0x00002000UL /*!< Interrupt status of pin 13 */ +#define GPIO_INTSTATUS_PIN14_Msk 0x00004000UL /*!< Interrupt status of pin 14 */ +#define GPIO_INTSTATUS_PIN15_Msk 0x00008000UL /*!< Interrupt status of pin 15 */ + +/*-- DMAREQSET: DMA request enable register ------------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< DMA request enable for pin 0 */ + uint32_t PIN1 :1; /*!< DMA request enable for pin 1 */ + uint32_t PIN2 :1; /*!< DMA request enable for pin 2 */ + uint32_t PIN3 :1; /*!< DMA request enable for pin 3 */ + uint32_t PIN4 :1; /*!< DMA request enable for pin 4 */ + uint32_t PIN5 :1; /*!< DMA request enable for pin 5 */ + uint32_t PIN6 :1; /*!< DMA request enable for pin 6 */ + uint32_t PIN7 :1; /*!< DMA request enable for pin 7 */ + uint32_t PIN8 :1; /*!< DMA request enable for pin 8 */ + uint32_t PIN9 :1; /*!< DMA request enable for pin 9 */ + uint32_t PIN10 :1; /*!< DMA request enable for pin 10 */ + uint32_t PIN11 :1; /*!< DMA request enable for pin 11 */ + uint32_t PIN12 :1; /*!< DMA request enable for pin 12 */ + uint32_t PIN13 :1; /*!< DMA request enable for pin 13 */ + uint32_t PIN14 :1; /*!< DMA request enable for pin 14 */ + uint32_t PIN15 :1; /*!< DMA request enable for pin 15 */ +} _GPIO_DMAREQSET_bits; + +/* Bit field positions: */ +#define GPIO_DMAREQSET_PIN0_Pos 0 /*!< DMA request enable for pin 0 */ +#define GPIO_DMAREQSET_PIN1_Pos 1 /*!< DMA request enable for pin 1 */ +#define GPIO_DMAREQSET_PIN2_Pos 2 /*!< DMA request enable for pin 2 */ +#define GPIO_DMAREQSET_PIN3_Pos 3 /*!< DMA request enable for pin 3 */ +#define GPIO_DMAREQSET_PIN4_Pos 4 /*!< DMA request enable for pin 4 */ +#define GPIO_DMAREQSET_PIN5_Pos 5 /*!< DMA request enable for pin 5 */ +#define GPIO_DMAREQSET_PIN6_Pos 6 /*!< DMA request enable for pin 6 */ +#define GPIO_DMAREQSET_PIN7_Pos 7 /*!< DMA request enable for pin 7 */ +#define GPIO_DMAREQSET_PIN8_Pos 8 /*!< DMA request enable for pin 8 */ +#define GPIO_DMAREQSET_PIN9_Pos 9 /*!< DMA request enable for pin 9 */ +#define GPIO_DMAREQSET_PIN10_Pos 10 /*!< DMA request enable for pin 10 */ +#define GPIO_DMAREQSET_PIN11_Pos 11 /*!< DMA request enable for pin 11 */ +#define GPIO_DMAREQSET_PIN12_Pos 12 /*!< DMA request enable for pin 12 */ +#define GPIO_DMAREQSET_PIN13_Pos 13 /*!< DMA request enable for pin 13 */ +#define GPIO_DMAREQSET_PIN14_Pos 14 /*!< DMA request enable for pin 14 */ +#define GPIO_DMAREQSET_PIN15_Pos 15 /*!< DMA request enable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_DMAREQSET_PIN0_Msk 0x00000001UL /*!< DMA request enable for pin 0 */ +#define GPIO_DMAREQSET_PIN1_Msk 0x00000002UL /*!< DMA request enable for pin 1 */ +#define GPIO_DMAREQSET_PIN2_Msk 0x00000004UL /*!< DMA request enable for pin 2 */ +#define GPIO_DMAREQSET_PIN3_Msk 0x00000008UL /*!< DMA request enable for pin 3 */ +#define GPIO_DMAREQSET_PIN4_Msk 0x00000010UL /*!< DMA request enable for pin 4 */ +#define GPIO_DMAREQSET_PIN5_Msk 0x00000020UL /*!< DMA request enable for pin 5 */ +#define GPIO_DMAREQSET_PIN6_Msk 0x00000040UL /*!< DMA request enable for pin 6 */ +#define GPIO_DMAREQSET_PIN7_Msk 0x00000080UL /*!< DMA request enable for pin 7 */ +#define GPIO_DMAREQSET_PIN8_Msk 0x00000100UL /*!< DMA request enable for pin 8 */ +#define GPIO_DMAREQSET_PIN9_Msk 0x00000200UL /*!< DMA request enable for pin 9 */ +#define GPIO_DMAREQSET_PIN10_Msk 0x00000400UL /*!< DMA request enable for pin 10 */ +#define GPIO_DMAREQSET_PIN11_Msk 0x00000800UL /*!< DMA request enable for pin 11 */ +#define GPIO_DMAREQSET_PIN12_Msk 0x00001000UL /*!< DMA request enable for pin 12 */ +#define GPIO_DMAREQSET_PIN13_Msk 0x00002000UL /*!< DMA request enable for pin 13 */ +#define GPIO_DMAREQSET_PIN14_Msk 0x00004000UL /*!< DMA request enable for pin 14 */ +#define GPIO_DMAREQSET_PIN15_Msk 0x00008000UL /*!< DMA request enable for pin 15 */ + +/*-- DMAREQCLR: DMA request disable register -----------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< DMA request disable for pin 0 */ + uint32_t PIN1 :1; /*!< DMA request disable for pin 1 */ + uint32_t PIN2 :1; /*!< DMA request disable for pin 2 */ + uint32_t PIN3 :1; /*!< DMA request disable for pin 3 */ + uint32_t PIN4 :1; /*!< DMA request disable for pin 4 */ + uint32_t PIN5 :1; /*!< DMA request disable for pin 5 */ + uint32_t PIN6 :1; /*!< DMA request disable for pin 6 */ + uint32_t PIN7 :1; /*!< DMA request disable for pin 7 */ + uint32_t PIN8 :1; /*!< DMA request disable for pin 8 */ + uint32_t PIN9 :1; /*!< DMA request disable for pin 9 */ + uint32_t PIN10 :1; /*!< DMA request disable for pin 10 */ + uint32_t PIN11 :1; /*!< DMA request disable for pin 11 */ + uint32_t PIN12 :1; /*!< DMA request disable for pin 12 */ + uint32_t PIN13 :1; /*!< DMA request disable for pin 13 */ + uint32_t PIN14 :1; /*!< DMA request disable for pin 14 */ + uint32_t PIN15 :1; /*!< DMA request disable for pin 15 */ +} _GPIO_DMAREQCLR_bits; + +/* Bit field positions: */ +#define GPIO_DMAREQCLR_PIN0_Pos 0 /*!< DMA request disable for pin 0 */ +#define GPIO_DMAREQCLR_PIN1_Pos 1 /*!< DMA request disable for pin 1 */ +#define GPIO_DMAREQCLR_PIN2_Pos 2 /*!< DMA request disable for pin 2 */ +#define GPIO_DMAREQCLR_PIN3_Pos 3 /*!< DMA request disable for pin 3 */ +#define GPIO_DMAREQCLR_PIN4_Pos 4 /*!< DMA request disable for pin 4 */ +#define GPIO_DMAREQCLR_PIN5_Pos 5 /*!< DMA request disable for pin 5 */ +#define GPIO_DMAREQCLR_PIN6_Pos 6 /*!< DMA request disable for pin 6 */ +#define GPIO_DMAREQCLR_PIN7_Pos 7 /*!< DMA request disable for pin 7 */ +#define GPIO_DMAREQCLR_PIN8_Pos 8 /*!< DMA request disable for pin 8 */ +#define GPIO_DMAREQCLR_PIN9_Pos 9 /*!< DMA request disable for pin 9 */ +#define GPIO_DMAREQCLR_PIN10_Pos 10 /*!< DMA request disable for pin 10 */ +#define GPIO_DMAREQCLR_PIN11_Pos 11 /*!< DMA request disable for pin 11 */ +#define GPIO_DMAREQCLR_PIN12_Pos 12 /*!< DMA request disable for pin 12 */ +#define GPIO_DMAREQCLR_PIN13_Pos 13 /*!< DMA request disable for pin 13 */ +#define GPIO_DMAREQCLR_PIN14_Pos 14 /*!< DMA request disable for pin 14 */ +#define GPIO_DMAREQCLR_PIN15_Pos 15 /*!< DMA request disable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_DMAREQCLR_PIN0_Msk 0x00000001UL /*!< DMA request disable for pin 0 */ +#define GPIO_DMAREQCLR_PIN1_Msk 0x00000002UL /*!< DMA request disable for pin 1 */ +#define GPIO_DMAREQCLR_PIN2_Msk 0x00000004UL /*!< DMA request disable for pin 2 */ +#define GPIO_DMAREQCLR_PIN3_Msk 0x00000008UL /*!< DMA request disable for pin 3 */ +#define GPIO_DMAREQCLR_PIN4_Msk 0x00000010UL /*!< DMA request disable for pin 4 */ +#define GPIO_DMAREQCLR_PIN5_Msk 0x00000020UL /*!< DMA request disable for pin 5 */ +#define GPIO_DMAREQCLR_PIN6_Msk 0x00000040UL /*!< DMA request disable for pin 6 */ +#define GPIO_DMAREQCLR_PIN7_Msk 0x00000080UL /*!< DMA request disable for pin 7 */ +#define GPIO_DMAREQCLR_PIN8_Msk 0x00000100UL /*!< DMA request disable for pin 8 */ +#define GPIO_DMAREQCLR_PIN9_Msk 0x00000200UL /*!< DMA request disable for pin 9 */ +#define GPIO_DMAREQCLR_PIN10_Msk 0x00000400UL /*!< DMA request disable for pin 10 */ +#define GPIO_DMAREQCLR_PIN11_Msk 0x00000800UL /*!< DMA request disable for pin 11 */ +#define GPIO_DMAREQCLR_PIN12_Msk 0x00001000UL /*!< DMA request disable for pin 12 */ +#define GPIO_DMAREQCLR_PIN13_Msk 0x00002000UL /*!< DMA request disable for pin 13 */ +#define GPIO_DMAREQCLR_PIN14_Msk 0x00004000UL /*!< DMA request disable for pin 14 */ +#define GPIO_DMAREQCLR_PIN15_Msk 0x00008000UL /*!< DMA request disable for pin 15 */ + +/*-- ADCSOCSET: ADC Start Of Conversion enable register ------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< ADC SOC enable for pin 0 */ + uint32_t PIN1 :1; /*!< ADC SOC enable for pin 1 */ + uint32_t PIN2 :1; /*!< ADC SOC enable for pin 2 */ + uint32_t PIN3 :1; /*!< ADC SOC enable for pin 3 */ + uint32_t PIN4 :1; /*!< ADC SOC enable for pin 4 */ + uint32_t PIN5 :1; /*!< ADC SOC enable for pin 5 */ + uint32_t PIN6 :1; /*!< ADC SOC enable for pin 6 */ + uint32_t PIN7 :1; /*!< ADC SOC enable for pin 7 */ + uint32_t PIN8 :1; /*!< ADC SOC enable for pin 8 */ + uint32_t PIN9 :1; /*!< ADC SOC enable for pin 9 */ + uint32_t PIN10 :1; /*!< ADC SOC enable for pin 10 */ + uint32_t PIN11 :1; /*!< ADC SOC enable for pin 11 */ + uint32_t PIN12 :1; /*!< ADC SOC enable for pin 12 */ + uint32_t PIN13 :1; /*!< ADC SOC enable for pin 13 */ + uint32_t PIN14 :1; /*!< ADC SOC enable for pin 14 */ + uint32_t PIN15 :1; /*!< ADC SOC enable for pin 15 */ +} _GPIO_ADCSOCSET_bits; + +/* Bit field positions: */ +#define GPIO_ADCSOCSET_PIN0_Pos 0 /*!< ADC SOC enable for pin 0 */ +#define GPIO_ADCSOCSET_PIN1_Pos 1 /*!< ADC SOC enable for pin 1 */ +#define GPIO_ADCSOCSET_PIN2_Pos 2 /*!< ADC SOC enable for pin 2 */ +#define GPIO_ADCSOCSET_PIN3_Pos 3 /*!< ADC SOC enable for pin 3 */ +#define GPIO_ADCSOCSET_PIN4_Pos 4 /*!< ADC SOC enable for pin 4 */ +#define GPIO_ADCSOCSET_PIN5_Pos 5 /*!< ADC SOC enable for pin 5 */ +#define GPIO_ADCSOCSET_PIN6_Pos 6 /*!< ADC SOC enable for pin 6 */ +#define GPIO_ADCSOCSET_PIN7_Pos 7 /*!< ADC SOC enable for pin 7 */ +#define GPIO_ADCSOCSET_PIN8_Pos 8 /*!< ADC SOC enable for pin 8 */ +#define GPIO_ADCSOCSET_PIN9_Pos 9 /*!< ADC SOC enable for pin 9 */ +#define GPIO_ADCSOCSET_PIN10_Pos 10 /*!< ADC SOC enable for pin 10 */ +#define GPIO_ADCSOCSET_PIN11_Pos 11 /*!< ADC SOC enable for pin 11 */ +#define GPIO_ADCSOCSET_PIN12_Pos 12 /*!< ADC SOC enable for pin 12 */ +#define GPIO_ADCSOCSET_PIN13_Pos 13 /*!< ADC SOC enable for pin 13 */ +#define GPIO_ADCSOCSET_PIN14_Pos 14 /*!< ADC SOC enable for pin 14 */ +#define GPIO_ADCSOCSET_PIN15_Pos 15 /*!< ADC SOC enable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_ADCSOCSET_PIN0_Msk 0x00000001UL /*!< ADC SOC enable for pin 0 */ +#define GPIO_ADCSOCSET_PIN1_Msk 0x00000002UL /*!< ADC SOC enable for pin 1 */ +#define GPIO_ADCSOCSET_PIN2_Msk 0x00000004UL /*!< ADC SOC enable for pin 2 */ +#define GPIO_ADCSOCSET_PIN3_Msk 0x00000008UL /*!< ADC SOC enable for pin 3 */ +#define GPIO_ADCSOCSET_PIN4_Msk 0x00000010UL /*!< ADC SOC enable for pin 4 */ +#define GPIO_ADCSOCSET_PIN5_Msk 0x00000020UL /*!< ADC SOC enable for pin 5 */ +#define GPIO_ADCSOCSET_PIN6_Msk 0x00000040UL /*!< ADC SOC enable for pin 6 */ +#define GPIO_ADCSOCSET_PIN7_Msk 0x00000080UL /*!< ADC SOC enable for pin 7 */ +#define GPIO_ADCSOCSET_PIN8_Msk 0x00000100UL /*!< ADC SOC enable for pin 8 */ +#define GPIO_ADCSOCSET_PIN9_Msk 0x00000200UL /*!< ADC SOC enable for pin 9 */ +#define GPIO_ADCSOCSET_PIN10_Msk 0x00000400UL /*!< ADC SOC enable for pin 10 */ +#define GPIO_ADCSOCSET_PIN11_Msk 0x00000800UL /*!< ADC SOC enable for pin 11 */ +#define GPIO_ADCSOCSET_PIN12_Msk 0x00001000UL /*!< ADC SOC enable for pin 12 */ +#define GPIO_ADCSOCSET_PIN13_Msk 0x00002000UL /*!< ADC SOC enable for pin 13 */ +#define GPIO_ADCSOCSET_PIN14_Msk 0x00004000UL /*!< ADC SOC enable for pin 14 */ +#define GPIO_ADCSOCSET_PIN15_Msk 0x00008000UL /*!< ADC SOC enable for pin 15 */ + +/*-- ADCSOCCLR: ADC Start Of Conversion disable register -----------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< ADC SOC disable for pin 0 */ + uint32_t PIN1 :1; /*!< ADC SOC disable for pin 1 */ + uint32_t PIN2 :1; /*!< ADC SOC disable for pin 2 */ + uint32_t PIN3 :1; /*!< ADC SOC disable for pin 3 */ + uint32_t PIN4 :1; /*!< ADC SOC disable for pin 4 */ + uint32_t PIN5 :1; /*!< ADC SOC disable for pin 5 */ + uint32_t PIN6 :1; /*!< ADC SOC disable for pin 6 */ + uint32_t PIN7 :1; /*!< ADC SOC disable for pin 7 */ + uint32_t PIN8 :1; /*!< ADC SOC disable for pin 8 */ + uint32_t PIN9 :1; /*!< ADC SOC disable for pin 9 */ + uint32_t PIN10 :1; /*!< ADC SOC disable for pin 10 */ + uint32_t PIN11 :1; /*!< ADC SOC disable for pin 11 */ + uint32_t PIN12 :1; /*!< ADC SOC disable for pin 12 */ + uint32_t PIN13 :1; /*!< ADC SOC disable for pin 13 */ + uint32_t PIN14 :1; /*!< ADC SOC disable for pin 14 */ + uint32_t PIN15 :1; /*!< ADC SOC disable for pin 15 */ +} _GPIO_ADCSOCCLR_bits; + +/* Bit field positions: */ +#define GPIO_ADCSOCCLR_PIN0_Pos 0 /*!< ADC SOC disable for pin 0 */ +#define GPIO_ADCSOCCLR_PIN1_Pos 1 /*!< ADC SOC disable for pin 1 */ +#define GPIO_ADCSOCCLR_PIN2_Pos 2 /*!< ADC SOC disable for pin 2 */ +#define GPIO_ADCSOCCLR_PIN3_Pos 3 /*!< ADC SOC disable for pin 3 */ +#define GPIO_ADCSOCCLR_PIN4_Pos 4 /*!< ADC SOC disable for pin 4 */ +#define GPIO_ADCSOCCLR_PIN5_Pos 5 /*!< ADC SOC disable for pin 5 */ +#define GPIO_ADCSOCCLR_PIN6_Pos 6 /*!< ADC SOC disable for pin 6 */ +#define GPIO_ADCSOCCLR_PIN7_Pos 7 /*!< ADC SOC disable for pin 7 */ +#define GPIO_ADCSOCCLR_PIN8_Pos 8 /*!< ADC SOC disable for pin 8 */ +#define GPIO_ADCSOCCLR_PIN9_Pos 9 /*!< ADC SOC disable for pin 9 */ +#define GPIO_ADCSOCCLR_PIN10_Pos 10 /*!< ADC SOC disable for pin 10 */ +#define GPIO_ADCSOCCLR_PIN11_Pos 11 /*!< ADC SOC disable for pin 11 */ +#define GPIO_ADCSOCCLR_PIN12_Pos 12 /*!< ADC SOC disable for pin 12 */ +#define GPIO_ADCSOCCLR_PIN13_Pos 13 /*!< ADC SOC disable for pin 13 */ +#define GPIO_ADCSOCCLR_PIN14_Pos 14 /*!< ADC SOC disable for pin 14 */ +#define GPIO_ADCSOCCLR_PIN15_Pos 15 /*!< ADC SOC disable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_ADCSOCCLR_PIN0_Msk 0x00000001UL /*!< ADC SOC disable for pin 0 */ +#define GPIO_ADCSOCCLR_PIN1_Msk 0x00000002UL /*!< ADC SOC disable for pin 1 */ +#define GPIO_ADCSOCCLR_PIN2_Msk 0x00000004UL /*!< ADC SOC disable for pin 2 */ +#define GPIO_ADCSOCCLR_PIN3_Msk 0x00000008UL /*!< ADC SOC disable for pin 3 */ +#define GPIO_ADCSOCCLR_PIN4_Msk 0x00000010UL /*!< ADC SOC disable for pin 4 */ +#define GPIO_ADCSOCCLR_PIN5_Msk 0x00000020UL /*!< ADC SOC disable for pin 5 */ +#define GPIO_ADCSOCCLR_PIN6_Msk 0x00000040UL /*!< ADC SOC disable for pin 6 */ +#define GPIO_ADCSOCCLR_PIN7_Msk 0x00000080UL /*!< ADC SOC disable for pin 7 */ +#define GPIO_ADCSOCCLR_PIN8_Msk 0x00000100UL /*!< ADC SOC disable for pin 8 */ +#define GPIO_ADCSOCCLR_PIN9_Msk 0x00000200UL /*!< ADC SOC disable for pin 9 */ +#define GPIO_ADCSOCCLR_PIN10_Msk 0x00000400UL /*!< ADC SOC disable for pin 10 */ +#define GPIO_ADCSOCCLR_PIN11_Msk 0x00000800UL /*!< ADC SOC disable for pin 11 */ +#define GPIO_ADCSOCCLR_PIN12_Msk 0x00001000UL /*!< ADC SOC disable for pin 12 */ +#define GPIO_ADCSOCCLR_PIN13_Msk 0x00002000UL /*!< ADC SOC disable for pin 13 */ +#define GPIO_ADCSOCCLR_PIN14_Msk 0x00004000UL /*!< ADC SOC disable for pin 14 */ +#define GPIO_ADCSOCCLR_PIN15_Msk 0x00008000UL /*!< ADC SOC disable for pin 15 */ + +/*-- RXEVSET: Core RXEV request enable register --------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< RXEV enable for pin 0 */ + uint32_t PIN1 :1; /*!< RXEV enable for pin 1 */ + uint32_t PIN2 :1; /*!< RXEV enable for pin 2 */ + uint32_t PIN3 :1; /*!< RXEV enable for pin 3 */ + uint32_t PIN4 :1; /*!< RXEV enable for pin 4 */ + uint32_t PIN5 :1; /*!< RXEV enable for pin 5 */ + uint32_t PIN6 :1; /*!< RXEV enable for pin 6 */ + uint32_t PIN7 :1; /*!< RXEV enable for pin 7 */ + uint32_t PIN8 :1; /*!< RXEV enable for pin 8 */ + uint32_t PIN9 :1; /*!< RXEV enable for pin 9 */ + uint32_t PIN10 :1; /*!< RXEV enable for pin 10 */ + uint32_t PIN11 :1; /*!< RXEV enable for pin 11 */ + uint32_t PIN12 :1; /*!< RXEV enable for pin 12 */ + uint32_t PIN13 :1; /*!< RXEV enable for pin 13 */ + uint32_t PIN14 :1; /*!< RXEV enable for pin 14 */ + uint32_t PIN15 :1; /*!< RXEV enable for pin 15 */ +} _GPIO_RXEVSET_bits; + +/* Bit field positions: */ +#define GPIO_RXEVSET_PIN0_Pos 0 /*!< RXEV enable for pin 0 */ +#define GPIO_RXEVSET_PIN1_Pos 1 /*!< RXEV enable for pin 1 */ +#define GPIO_RXEVSET_PIN2_Pos 2 /*!< RXEV enable for pin 2 */ +#define GPIO_RXEVSET_PIN3_Pos 3 /*!< RXEV enable for pin 3 */ +#define GPIO_RXEVSET_PIN4_Pos 4 /*!< RXEV enable for pin 4 */ +#define GPIO_RXEVSET_PIN5_Pos 5 /*!< RXEV enable for pin 5 */ +#define GPIO_RXEVSET_PIN6_Pos 6 /*!< RXEV enable for pin 6 */ +#define GPIO_RXEVSET_PIN7_Pos 7 /*!< RXEV enable for pin 7 */ +#define GPIO_RXEVSET_PIN8_Pos 8 /*!< RXEV enable for pin 8 */ +#define GPIO_RXEVSET_PIN9_Pos 9 /*!< RXEV enable for pin 9 */ +#define GPIO_RXEVSET_PIN10_Pos 10 /*!< RXEV enable for pin 10 */ +#define GPIO_RXEVSET_PIN11_Pos 11 /*!< RXEV enable for pin 11 */ +#define GPIO_RXEVSET_PIN12_Pos 12 /*!< RXEV enable for pin 12 */ +#define GPIO_RXEVSET_PIN13_Pos 13 /*!< RXEV enable for pin 13 */ +#define GPIO_RXEVSET_PIN14_Pos 14 /*!< RXEV enable for pin 14 */ +#define GPIO_RXEVSET_PIN15_Pos 15 /*!< RXEV enable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_RXEVSET_PIN0_Msk 0x00000001UL /*!< RXEV enable for pin 0 */ +#define GPIO_RXEVSET_PIN1_Msk 0x00000002UL /*!< RXEV enable for pin 1 */ +#define GPIO_RXEVSET_PIN2_Msk 0x00000004UL /*!< RXEV enable for pin 2 */ +#define GPIO_RXEVSET_PIN3_Msk 0x00000008UL /*!< RXEV enable for pin 3 */ +#define GPIO_RXEVSET_PIN4_Msk 0x00000010UL /*!< RXEV enable for pin 4 */ +#define GPIO_RXEVSET_PIN5_Msk 0x00000020UL /*!< RXEV enable for pin 5 */ +#define GPIO_RXEVSET_PIN6_Msk 0x00000040UL /*!< RXEV enable for pin 6 */ +#define GPIO_RXEVSET_PIN7_Msk 0x00000080UL /*!< RXEV enable for pin 7 */ +#define GPIO_RXEVSET_PIN8_Msk 0x00000100UL /*!< RXEV enable for pin 8 */ +#define GPIO_RXEVSET_PIN9_Msk 0x00000200UL /*!< RXEV enable for pin 9 */ +#define GPIO_RXEVSET_PIN10_Msk 0x00000400UL /*!< RXEV enable for pin 10 */ +#define GPIO_RXEVSET_PIN11_Msk 0x00000800UL /*!< RXEV enable for pin 11 */ +#define GPIO_RXEVSET_PIN12_Msk 0x00001000UL /*!< RXEV enable for pin 12 */ +#define GPIO_RXEVSET_PIN13_Msk 0x00002000UL /*!< RXEV enable for pin 13 */ +#define GPIO_RXEVSET_PIN14_Msk 0x00004000UL /*!< RXEV enable for pin 14 */ +#define GPIO_RXEVSET_PIN15_Msk 0x00008000UL /*!< RXEV enable for pin 15 */ + +/*-- RXEVCLR: Core RXEV request disable register -------------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< RXEV disable for pin 0 */ + uint32_t PIN1 :1; /*!< RXEV disable for pin 1 */ + uint32_t PIN2 :1; /*!< RXEV disable for pin 2 */ + uint32_t PIN3 :1; /*!< RXEV disable for pin 3 */ + uint32_t PIN4 :1; /*!< RXEV disable for pin 4 */ + uint32_t PIN5 :1; /*!< RXEV disable for pin 5 */ + uint32_t PIN6 :1; /*!< RXEV disable for pin 6 */ + uint32_t PIN7 :1; /*!< RXEV disable for pin 7 */ + uint32_t PIN8 :1; /*!< RXEV disable for pin 8 */ + uint32_t PIN9 :1; /*!< RXEV disable for pin 9 */ + uint32_t PIN10 :1; /*!< RXEV disable for pin 10 */ + uint32_t PIN11 :1; /*!< RXEV disable for pin 11 */ + uint32_t PIN12 :1; /*!< RXEV disable for pin 12 */ + uint32_t PIN13 :1; /*!< RXEV disable for pin 13 */ + uint32_t PIN14 :1; /*!< RXEV disable for pin 14 */ + uint32_t PIN15 :1; /*!< RXEV disable for pin 15 */ +} _GPIO_RXEVCLR_bits; + +/* Bit field positions: */ +#define GPIO_RXEVCLR_PIN0_Pos 0 /*!< RXEV disable for pin 0 */ +#define GPIO_RXEVCLR_PIN1_Pos 1 /*!< RXEV disable for pin 1 */ +#define GPIO_RXEVCLR_PIN2_Pos 2 /*!< RXEV disable for pin 2 */ +#define GPIO_RXEVCLR_PIN3_Pos 3 /*!< RXEV disable for pin 3 */ +#define GPIO_RXEVCLR_PIN4_Pos 4 /*!< RXEV disable for pin 4 */ +#define GPIO_RXEVCLR_PIN5_Pos 5 /*!< RXEV disable for pin 5 */ +#define GPIO_RXEVCLR_PIN6_Pos 6 /*!< RXEV disable for pin 6 */ +#define GPIO_RXEVCLR_PIN7_Pos 7 /*!< RXEV disable for pin 7 */ +#define GPIO_RXEVCLR_PIN8_Pos 8 /*!< RXEV disable for pin 8 */ +#define GPIO_RXEVCLR_PIN9_Pos 9 /*!< RXEV disable for pin 9 */ +#define GPIO_RXEVCLR_PIN10_Pos 10 /*!< RXEV disable for pin 10 */ +#define GPIO_RXEVCLR_PIN11_Pos 11 /*!< RXEV disable for pin 11 */ +#define GPIO_RXEVCLR_PIN12_Pos 12 /*!< RXEV disable for pin 12 */ +#define GPIO_RXEVCLR_PIN13_Pos 13 /*!< RXEV disable for pin 13 */ +#define GPIO_RXEVCLR_PIN14_Pos 14 /*!< RXEV disable for pin 14 */ +#define GPIO_RXEVCLR_PIN15_Pos 15 /*!< RXEV disable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_RXEVCLR_PIN0_Msk 0x00000001UL /*!< RXEV disable for pin 0 */ +#define GPIO_RXEVCLR_PIN1_Msk 0x00000002UL /*!< RXEV disable for pin 1 */ +#define GPIO_RXEVCLR_PIN2_Msk 0x00000004UL /*!< RXEV disable for pin 2 */ +#define GPIO_RXEVCLR_PIN3_Msk 0x00000008UL /*!< RXEV disable for pin 3 */ +#define GPIO_RXEVCLR_PIN4_Msk 0x00000010UL /*!< RXEV disable for pin 4 */ +#define GPIO_RXEVCLR_PIN5_Msk 0x00000020UL /*!< RXEV disable for pin 5 */ +#define GPIO_RXEVCLR_PIN6_Msk 0x00000040UL /*!< RXEV disable for pin 6 */ +#define GPIO_RXEVCLR_PIN7_Msk 0x00000080UL /*!< RXEV disable for pin 7 */ +#define GPIO_RXEVCLR_PIN8_Msk 0x00000100UL /*!< RXEV disable for pin 8 */ +#define GPIO_RXEVCLR_PIN9_Msk 0x00000200UL /*!< RXEV disable for pin 9 */ +#define GPIO_RXEVCLR_PIN10_Msk 0x00000400UL /*!< RXEV disable for pin 10 */ +#define GPIO_RXEVCLR_PIN11_Msk 0x00000800UL /*!< RXEV disable for pin 11 */ +#define GPIO_RXEVCLR_PIN12_Msk 0x00001000UL /*!< RXEV disable for pin 12 */ +#define GPIO_RXEVCLR_PIN13_Msk 0x00002000UL /*!< RXEV disable for pin 13 */ +#define GPIO_RXEVCLR_PIN14_Msk 0x00004000UL /*!< RXEV disable for pin 14 */ +#define GPIO_RXEVCLR_PIN15_Msk 0x00008000UL /*!< RXEV disable for pin 15 */ + +/*-- LOCKKEY: Key register to unlock LOCKSET/LOCKCLR registers for write (KEY=0xADEADBEE) ---------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Key to unlock LOCKSET/LOCKCLR registers for write (KEY=0xADEADBEE) */ +} _GPIO_LOCKKEY_bits; + +/* Bit field positions: */ +#define GPIO_LOCKKEY_VAL_Pos 0 /*!< Key to unlock LOCKSET/LOCKCLR registers for write (KEY=0xADEADBEE) */ + +/* Bit field masks: */ +#define GPIO_LOCKKEY_VAL_Msk 0xFFFFFFFFUL /*!< Key to unlock LOCKSET/LOCKCLR registers for write (KEY=0xADEADBEE) */ + +/* Bit field enums: */ +typedef enum { + GPIO_LOCKKEY_VAL_LOCK = -286331154, /*!< 0xEEEEEEEE, 0xEEEEEEEE, key to lock registers */ + GPIO_LOCKKEY_VAL_UNLOCK = -1377117202, /*!< 0xADEADBEE, 0xADEADBEE, key to unlock registers */ +} GPIO_LOCKKEY_VAL_Enum; + +/*-- LOCKSTAT: LOCKSET/LOCKCLR write enable status register --------------------------------------------------*/ +typedef struct { + uint32_t WREN :1; /*!< LOCKSET/LOCKCLR write enable status */ +} _GPIO_LOCKSTAT_bits; + +/* Bit field positions: */ +#define GPIO_LOCKSTAT_WREN_Pos 0 /*!< LOCKSET/LOCKCLR write enable status */ + +/* Bit field masks: */ +#define GPIO_LOCKSTAT_WREN_Msk 0x00000001UL /*!< LOCKSET/LOCKCLR write enable status */ + +/*-- LOCKSET: Lock pins configuration enable register --------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Lock configuration enable for pin 0 */ + uint32_t PIN1 :1; /*!< Lock configuration enable for pin 1 */ + uint32_t PIN2 :1; /*!< Lock configuration enable for pin 2 */ + uint32_t PIN3 :1; /*!< Lock configuration enable for pin 3 */ + uint32_t PIN4 :1; /*!< Lock configuration enable for pin 4 */ + uint32_t PIN5 :1; /*!< Lock configuration enable for pin 5 */ + uint32_t PIN6 :1; /*!< Lock configuration enable for pin 6 */ + uint32_t PIN7 :1; /*!< Lock configuration enable for pin 7 */ + uint32_t PIN8 :1; /*!< Lock configuration enable for pin 8 */ + uint32_t PIN9 :1; /*!< Lock configuration enable for pin 9 */ + uint32_t PIN10 :1; /*!< Lock configuration enable for pin 10 */ + uint32_t PIN11 :1; /*!< Lock configuration enable for pin 11 */ + uint32_t PIN12 :1; /*!< Lock configuration enable for pin 12 */ + uint32_t PIN13 :1; /*!< Lock configuration enable for pin 13 */ + uint32_t PIN14 :1; /*!< Lock configuration enable for pin 14 */ + uint32_t PIN15 :1; /*!< Lock configuration enable for pin 15 */ +} _GPIO_LOCKSET_bits; + +/* Bit field positions: */ +#define GPIO_LOCKSET_PIN0_Pos 0 /*!< Lock configuration enable for pin 0 */ +#define GPIO_LOCKSET_PIN1_Pos 1 /*!< Lock configuration enable for pin 1 */ +#define GPIO_LOCKSET_PIN2_Pos 2 /*!< Lock configuration enable for pin 2 */ +#define GPIO_LOCKSET_PIN3_Pos 3 /*!< Lock configuration enable for pin 3 */ +#define GPIO_LOCKSET_PIN4_Pos 4 /*!< Lock configuration enable for pin 4 */ +#define GPIO_LOCKSET_PIN5_Pos 5 /*!< Lock configuration enable for pin 5 */ +#define GPIO_LOCKSET_PIN6_Pos 6 /*!< Lock configuration enable for pin 6 */ +#define GPIO_LOCKSET_PIN7_Pos 7 /*!< Lock configuration enable for pin 7 */ +#define GPIO_LOCKSET_PIN8_Pos 8 /*!< Lock configuration enable for pin 8 */ +#define GPIO_LOCKSET_PIN9_Pos 9 /*!< Lock configuration enable for pin 9 */ +#define GPIO_LOCKSET_PIN10_Pos 10 /*!< Lock configuration enable for pin 10 */ +#define GPIO_LOCKSET_PIN11_Pos 11 /*!< Lock configuration enable for pin 11 */ +#define GPIO_LOCKSET_PIN12_Pos 12 /*!< Lock configuration enable for pin 12 */ +#define GPIO_LOCKSET_PIN13_Pos 13 /*!< Lock configuration enable for pin 13 */ +#define GPIO_LOCKSET_PIN14_Pos 14 /*!< Lock configuration enable for pin 14 */ +#define GPIO_LOCKSET_PIN15_Pos 15 /*!< Lock configuration enable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_LOCKSET_PIN0_Msk 0x00000001UL /*!< Lock configuration enable for pin 0 */ +#define GPIO_LOCKSET_PIN1_Msk 0x00000002UL /*!< Lock configuration enable for pin 1 */ +#define GPIO_LOCKSET_PIN2_Msk 0x00000004UL /*!< Lock configuration enable for pin 2 */ +#define GPIO_LOCKSET_PIN3_Msk 0x00000008UL /*!< Lock configuration enable for pin 3 */ +#define GPIO_LOCKSET_PIN4_Msk 0x00000010UL /*!< Lock configuration enable for pin 4 */ +#define GPIO_LOCKSET_PIN5_Msk 0x00000020UL /*!< Lock configuration enable for pin 5 */ +#define GPIO_LOCKSET_PIN6_Msk 0x00000040UL /*!< Lock configuration enable for pin 6 */ +#define GPIO_LOCKSET_PIN7_Msk 0x00000080UL /*!< Lock configuration enable for pin 7 */ +#define GPIO_LOCKSET_PIN8_Msk 0x00000100UL /*!< Lock configuration enable for pin 8 */ +#define GPIO_LOCKSET_PIN9_Msk 0x00000200UL /*!< Lock configuration enable for pin 9 */ +#define GPIO_LOCKSET_PIN10_Msk 0x00000400UL /*!< Lock configuration enable for pin 10 */ +#define GPIO_LOCKSET_PIN11_Msk 0x00000800UL /*!< Lock configuration enable for pin 11 */ +#define GPIO_LOCKSET_PIN12_Msk 0x00001000UL /*!< Lock configuration enable for pin 12 */ +#define GPIO_LOCKSET_PIN13_Msk 0x00002000UL /*!< Lock configuration enable for pin 13 */ +#define GPIO_LOCKSET_PIN14_Msk 0x00004000UL /*!< Lock configuration enable for pin 14 */ +#define GPIO_LOCKSET_PIN15_Msk 0x00008000UL /*!< Lock configuration enable for pin 15 */ + +/*-- LOCKCLR: Lock pins configuration disable register -------------------------------------------------------*/ +typedef struct { + uint32_t PIN0 :1; /*!< Lock configuration disable for pin 0 */ + uint32_t PIN1 :1; /*!< Lock configuration disable for pin 1 */ + uint32_t PIN2 :1; /*!< Lock configuration disable for pin 2 */ + uint32_t PIN3 :1; /*!< Lock configuration disable for pin 3 */ + uint32_t PIN4 :1; /*!< Lock configuration disable for pin 4 */ + uint32_t PIN5 :1; /*!< Lock configuration disable for pin 5 */ + uint32_t PIN6 :1; /*!< Lock configuration disable for pin 6 */ + uint32_t PIN7 :1; /*!< Lock configuration disable for pin 7 */ + uint32_t PIN8 :1; /*!< Lock configuration disable for pin 8 */ + uint32_t PIN9 :1; /*!< Lock configuration disable for pin 9 */ + uint32_t PIN10 :1; /*!< Lock configuration disable for pin 10 */ + uint32_t PIN11 :1; /*!< Lock configuration disable for pin 11 */ + uint32_t PIN12 :1; /*!< Lock configuration disable for pin 12 */ + uint32_t PIN13 :1; /*!< Lock configuration disable for pin 13 */ + uint32_t PIN14 :1; /*!< Lock configuration disable for pin 14 */ + uint32_t PIN15 :1; /*!< Lock configuration disable for pin 15 */ +} _GPIO_LOCKCLR_bits; + +/* Bit field positions: */ +#define GPIO_LOCKCLR_PIN0_Pos 0 /*!< Lock configuration disable for pin 0 */ +#define GPIO_LOCKCLR_PIN1_Pos 1 /*!< Lock configuration disable for pin 1 */ +#define GPIO_LOCKCLR_PIN2_Pos 2 /*!< Lock configuration disable for pin 2 */ +#define GPIO_LOCKCLR_PIN3_Pos 3 /*!< Lock configuration disable for pin 3 */ +#define GPIO_LOCKCLR_PIN4_Pos 4 /*!< Lock configuration disable for pin 4 */ +#define GPIO_LOCKCLR_PIN5_Pos 5 /*!< Lock configuration disable for pin 5 */ +#define GPIO_LOCKCLR_PIN6_Pos 6 /*!< Lock configuration disable for pin 6 */ +#define GPIO_LOCKCLR_PIN7_Pos 7 /*!< Lock configuration disable for pin 7 */ +#define GPIO_LOCKCLR_PIN8_Pos 8 /*!< Lock configuration disable for pin 8 */ +#define GPIO_LOCKCLR_PIN9_Pos 9 /*!< Lock configuration disable for pin 9 */ +#define GPIO_LOCKCLR_PIN10_Pos 10 /*!< Lock configuration disable for pin 10 */ +#define GPIO_LOCKCLR_PIN11_Pos 11 /*!< Lock configuration disable for pin 11 */ +#define GPIO_LOCKCLR_PIN12_Pos 12 /*!< Lock configuration disable for pin 12 */ +#define GPIO_LOCKCLR_PIN13_Pos 13 /*!< Lock configuration disable for pin 13 */ +#define GPIO_LOCKCLR_PIN14_Pos 14 /*!< Lock configuration disable for pin 14 */ +#define GPIO_LOCKCLR_PIN15_Pos 15 /*!< Lock configuration disable for pin 15 */ + +/* Bit field masks: */ +#define GPIO_LOCKCLR_PIN0_Msk 0x00000001UL /*!< Lock configuration disable for pin 0 */ +#define GPIO_LOCKCLR_PIN1_Msk 0x00000002UL /*!< Lock configuration disable for pin 1 */ +#define GPIO_LOCKCLR_PIN2_Msk 0x00000004UL /*!< Lock configuration disable for pin 2 */ +#define GPIO_LOCKCLR_PIN3_Msk 0x00000008UL /*!< Lock configuration disable for pin 3 */ +#define GPIO_LOCKCLR_PIN4_Msk 0x00000010UL /*!< Lock configuration disable for pin 4 */ +#define GPIO_LOCKCLR_PIN5_Msk 0x00000020UL /*!< Lock configuration disable for pin 5 */ +#define GPIO_LOCKCLR_PIN6_Msk 0x00000040UL /*!< Lock configuration disable for pin 6 */ +#define GPIO_LOCKCLR_PIN7_Msk 0x00000080UL /*!< Lock configuration disable for pin 7 */ +#define GPIO_LOCKCLR_PIN8_Msk 0x00000100UL /*!< Lock configuration disable for pin 8 */ +#define GPIO_LOCKCLR_PIN9_Msk 0x00000200UL /*!< Lock configuration disable for pin 9 */ +#define GPIO_LOCKCLR_PIN10_Msk 0x00000400UL /*!< Lock configuration disable for pin 10 */ +#define GPIO_LOCKCLR_PIN11_Msk 0x00000800UL /*!< Lock configuration disable for pin 11 */ +#define GPIO_LOCKCLR_PIN12_Msk 0x00001000UL /*!< Lock configuration disable for pin 12 */ +#define GPIO_LOCKCLR_PIN13_Msk 0x00002000UL /*!< Lock configuration disable for pin 13 */ +#define GPIO_LOCKCLR_PIN14_Msk 0x00004000UL /*!< Lock configuration disable for pin 14 */ +#define GPIO_LOCKCLR_PIN15_Msk 0x00008000UL /*!< Lock configuration disable for pin 15 */ + +/*-- MASKLB: MASKLB: Mask register low byte of port -----------------------------------------------------------*/ +typedef struct { + uint32_t VAL :8; /*!< Mask low byte */ +} _GPIO_MASKLB_MASKLB_bits; + +/* Bit field positions: */ +#define GPIO_MASKLB_MASKLB_VAL_Pos 0 /*!< Mask low byte */ + +/* Bit field masks: */ +#define GPIO_MASKLB_MASKLB_VAL_Msk 0x000000FFUL /*!< Mask low byte */ + +/*-- MASKHB: MASKHB: Mask register High byte of port ----------------------------------------------------------*/ +typedef struct { + uint32_t :8; /*!< RESERVED */ + uint32_t VAL :8; /*!< Mask high byte */ +} _GPIO_MASKHB_MASKHB_bits; + +/* Bit field positions: */ +#define GPIO_MASKHB_MASKHB_VAL_Pos 8 /*!< Mask high byte */ + +/* Bit field masks: */ +#define GPIO_MASKHB_MASKHB_VAL_Msk 0x0000FF00UL /*!< Mask high byte */ + +//Cluster MASKLB: +typedef struct { + union { + /*!< Mask register low byte of port */ + __IO uint32_t MASKLB; /*!< MASKLB : type used for word access */ + __IO _GPIO_MASKLB_MASKLB_bits MASKLB_bit; /*!< MASKLB_bit: structure used for bit access */ + }; +} _GPIO_MASKLB_TypeDef; +//Cluster MASKHB: +typedef struct { + union { + /*!< Mask register High byte of port */ + __IO uint32_t MASKHB; /*!< MASKHB : type used for word access */ + __IO _GPIO_MASKHB_MASKHB_bits MASKHB_bit; /*!< MASKHB_bit: structure used for bit access */ + }; +} _GPIO_MASKHB_TypeDef; +typedef struct { + union { /*!< Data Input register */ + __IO uint32_t DATA; /*!< DATA : type used for word access */ + __IO _GPIO_DATA_bits DATA_bit; /*!< DATA_bit: structure used for bit access */ + }; + union { /*!< Data output register */ + __IO uint32_t DATAOUT; /*!< DATAOUT : type used for word access */ + __IO _GPIO_DATAOUT_bits DATAOUT_bit; /*!< DATAOUT_bit: structure used for bit access */ + }; + union { /*!< Data output set bits register */ + __IO uint32_t DATAOUTSET; /*!< DATAOUTSET : type used for word access */ + __IO _GPIO_DATAOUTSET_bits DATAOUTSET_bit; /*!< DATAOUTSET_bit: structure used for bit access */ + }; + union { /*!< Data output clear bits register */ + __IO uint32_t DATAOUTCLR; /*!< DATAOUTCLR : type used for word access */ + __IO _GPIO_DATAOUTCLR_bits DATAOUTCLR_bit; /*!< DATAOUTCLR_bit: structure used for bit access */ + }; + union { /*!< Data output toogle bits register */ + __IO uint32_t DATAOUTTGL; /*!< DATAOUTTGL : type used for word access */ + __IO _GPIO_DATAOUTTGL_bits DATAOUTTGL_bit; /*!< DATAOUTTGL_bit: structure used for bit access */ + }; + union { /*!< Digital function (PAD) enable register */ + __IO uint32_t DENSET; /*!< DENSET : type used for word access */ + __IO _GPIO_DENSET_bits DENSET_bit; /*!< DENSET_bit: structure used for bit access */ + }; + union { /*!< Digital function (PAD) disable register */ + __IO uint32_t DENCLR; /*!< DENCLR : type used for word access */ + __IO _GPIO_DENCLR_bits DENCLR_bit; /*!< DENCLR_bit: structure used for bit access */ + }; + union { /*!< Select input mode register */ + __IO uint32_t INMODE; /*!< INMODE : type used for word access */ + __IO _GPIO_INMODE_bits INMODE_bit; /*!< INMODE_bit: structure used for bit access */ + }; + union { /*!< Select pull mode register */ + __IO uint32_t PULLMODE; /*!< PULLMODE : type used for word access */ + __IO _GPIO_PULLMODE_bits PULLMODE_bit; /*!< PULLMODE_bit: structure used for bit access */ + }; + union { /*!< Select output mode register */ + __IO uint32_t OUTMODE; /*!< OUTMODE : type used for word access */ + __IO _GPIO_OUTMODE_bits OUTMODE_bit; /*!< OUTMODE_bit: structure used for bit access */ + }; + union { /*!< Select drive mode register */ + __IO uint32_t DRIVEMODE; /*!< DRIVEMODE : type used for word access */ + __IO _GPIO_DRIVEMODE_bits DRIVEMODE_bit; /*!< DRIVEMODE_bit: structure used for bit access */ + }; + union { /*!< Output enable register */ + __IO uint32_t OUTENSET; /*!< OUTENSET : type used for word access */ + __IO _GPIO_OUTENSET_bits OUTENSET_bit; /*!< OUTENSET_bit: structure used for bit access */ + }; + union { /*!< Output disable register */ + __IO uint32_t OUTENCLR; /*!< OUTENCLR : type used for word access */ + __IO _GPIO_OUTENCLR_bits OUTENCLR_bit; /*!< OUTENCLR_bit: structure used for bit access */ + }; + union { /*!< Alternative function enable register */ + __IO uint32_t ALTFUNCSET; /*!< ALTFUNCSET : type used for word access */ + __IO _GPIO_ALTFUNCSET_bits ALTFUNCSET_bit; /*!< ALTFUNCSET_bit: structure used for bit access */ + }; + union { /*!< Alternative function disable register */ + __IO uint32_t ALTFUNCCLR; /*!< ALTFUNCCLR : type used for word access */ + __IO _GPIO_ALTFUNCCLR_bits ALTFUNCCLR_bit; /*!< ALTFUNCCLR_bit: structure used for bit access */ + }; + __IO uint32_t Reserved0[2]; + union { /*!< Additional double flip-flop syncronization enable register */ + __IO uint32_t SYNCSET; /*!< SYNCSET : type used for word access */ + __IO _GPIO_SYNCSET_bits SYNCSET_bit; /*!< SYNCSET_bit: structure used for bit access */ + }; + union { /*!< Additional double flip-flop syncronization disable register */ + __IO uint32_t SYNCCLR; /*!< SYNCCLR : type used for word access */ + __IO _GPIO_SYNCCLR_bits SYNCCLR_bit; /*!< SYNCCLR_bit: structure used for bit access */ + }; + union { /*!< Qualifier enable register */ + __IO uint32_t QUALSET; /*!< QUALSET : type used for word access */ + __IO _GPIO_QUALSET_bits QUALSET_bit; /*!< QUALSET_bit: structure used for bit access */ + }; + union { /*!< Qualifier disable register */ + __IO uint32_t QUALCLR; /*!< QUALCLR : type used for word access */ + __IO _GPIO_QUALCLR_bits QUALCLR_bit; /*!< QUALCLR_bit: structure used for bit access */ + }; + union { /*!< Qualifier mode set register */ + __IO uint32_t QUALMODESET; /*!< QUALMODESET : type used for word access */ + __IO _GPIO_QUALMODESET_bits QUALMODESET_bit; /*!< QUALMODESET_bit: structure used for bit access */ + }; + union { /*!< Qualifier mode clear register */ + __IO uint32_t QUALMODECLR; /*!< QUALMODECLR : type used for word access */ + __IO _GPIO_QUALMODECLR_bits QUALMODECLR_bit; /*!< QUALMODECLR_bit: structure used for bit access */ + }; + union { /*!< Qualifier sample period register */ + __IO uint32_t QUALSAMPLE; /*!< QUALSAMPLE : type used for word access */ + __IO _GPIO_QUALSAMPLE_bits QUALSAMPLE_bit; /*!< QUALSAMPLE_bit: structure used for bit access */ + }; + union { /*!< Interrupt enable register */ + __IO uint32_t INTENSET; /*!< INTENSET : type used for word access */ + __IO _GPIO_INTENSET_bits INTENSET_bit; /*!< INTENSET_bit: structure used for bit access */ + }; + union { /*!< Interrupt disable register */ + __IO uint32_t INTENCLR; /*!< INTENCLR : type used for word access */ + __IO _GPIO_INTENCLR_bits INTENCLR_bit; /*!< INTENCLR_bit: structure used for bit access */ + }; + union { /*!< Interrupt type set register */ + __IO uint32_t INTTYPESET; /*!< INTTYPESET : type used for word access */ + __IO _GPIO_INTTYPESET_bits INTTYPESET_bit; /*!< INTTYPESET_bit: structure used for bit access */ + }; + union { /*!< Interrupt type clear register */ + __IO uint32_t INTTYPECLR; /*!< INTTYPECLR : type used for word access */ + __IO _GPIO_INTTYPECLR_bits INTTYPECLR_bit; /*!< INTTYPECLR_bit: structure used for bit access */ + }; + union { /*!< Interrupt polarity set register */ + __IO uint32_t INTPOLSET; /*!< INTPOLSET : type used for word access */ + __IO _GPIO_INTPOLSET_bits INTPOLSET_bit; /*!< INTPOLSET_bit: structure used for bit access */ + }; + union { /*!< Interrupt polarity clear register */ + __IO uint32_t INTPOLCLR; /*!< INTPOLCLR : type used for word access */ + __IO _GPIO_INTPOLCLR_bits INTPOLCLR_bit; /*!< INTPOLCLR_bit: structure used for bit access */ + }; + union { /*!< Interrupt every edge set register */ + __IO uint32_t INTEDGESET; /*!< INTEDGESET : type used for word access */ + __IO _GPIO_INTEDGESET_bits INTEDGESET_bit; /*!< INTEDGESET_bit: structure used for bit access */ + }; + union { /*!< Interrupt every edge clear register */ + __IO uint32_t INTEDGECLR; /*!< INTEDGECLR : type used for word access */ + __IO _GPIO_INTEDGECLR_bits INTEDGECLR_bit; /*!< INTEDGECLR_bit: structure used for bit access */ + }; + union { /*!< Interrupt status */ + __IO uint32_t INTSTATUS; /*!< INTSTATUS : type used for word access */ + __IO _GPIO_INTSTATUS_bits INTSTATUS_bit; /*!< INTSTATUS_bit: structure used for bit access */ + }; + union { /*!< DMA request enable register */ + __IO uint32_t DMAREQSET; /*!< DMAREQSET : type used for word access */ + __IO _GPIO_DMAREQSET_bits DMAREQSET_bit; /*!< DMAREQSET_bit: structure used for bit access */ + }; + union { /*!< DMA request disable register */ + __IO uint32_t DMAREQCLR; /*!< DMAREQCLR : type used for word access */ + __IO _GPIO_DMAREQCLR_bits DMAREQCLR_bit; /*!< DMAREQCLR_bit: structure used for bit access */ + }; + union { /*!< ADC Start Of Conversion enable register */ + __IO uint32_t ADCSOCSET; /*!< ADCSOCSET : type used for word access */ + __IO _GPIO_ADCSOCSET_bits ADCSOCSET_bit; /*!< ADCSOCSET_bit: structure used for bit access */ + }; + union { /*!< ADC Start Of Conversion disable register */ + __IO uint32_t ADCSOCCLR; /*!< ADCSOCCLR : type used for word access */ + __IO _GPIO_ADCSOCCLR_bits ADCSOCCLR_bit; /*!< ADCSOCCLR_bit: structure used for bit access */ + }; + union { /*!< Core RXEV request enable register */ + __IO uint32_t RXEVSET; /*!< RXEVSET : type used for word access */ + __IO _GPIO_RXEVSET_bits RXEVSET_bit; /*!< RXEVSET_bit: structure used for bit access */ + }; + union { /*!< Core RXEV request disable register */ + __IO uint32_t RXEVCLR; /*!< RXEVCLR : type used for word access */ + __IO _GPIO_RXEVCLR_bits RXEVCLR_bit; /*!< RXEVCLR_bit: structure used for bit access */ + }; + union { + union { /*!< Key register to unlock LOCKSET/LOCKCLR registers for write (KEY=0xADEADBEE) */ + __O uint32_t LOCKKEY; /*!< LOCKKEY : type used for word access */ + __O _GPIO_LOCKKEY_bits LOCKKEY_bit; /*!< LOCKKEY_bit: structure used for bit access */ + }; + struct { + union { /*!< LOCKSET/LOCKCLR write enable status register */ + __I uint32_t LOCKSTAT; /*!< LOCKSTAT : type used for word access */ + __I _GPIO_LOCKSTAT_bits LOCKSTAT_bit; /*!< LOCKSTAT_bit: structure used for bit access */ + }; + }; + }; + union { /*!< Lock pins configuration enable register */ + __IO uint32_t LOCKSET; /*!< LOCKSET : type used for word access */ + __IO _GPIO_LOCKSET_bits LOCKSET_bit; /*!< LOCKSET_bit: structure used for bit access */ + }; + union { /*!< Lock pins configuration disable register */ + __IO uint32_t LOCKCLR; /*!< LOCKCLR : type used for word access */ + __IO _GPIO_LOCKCLR_bits LOCKCLR_bit; /*!< LOCKCLR_bit: structure used for bit access */ + }; + __IO uint32_t Reserved1[214]; + _GPIO_MASKLB_TypeDef MASKLB[256]; + _GPIO_MASKHB_TypeDef MASKHB[256]; +} GPIO_TypeDef; + + +/******************************************************************************/ +/* UART registers */ +/******************************************************************************/ + +/*-- DR: Data Register ---------------------------------------------------------------------------------------*/ +typedef struct { + uint32_t DATA :8; /*!< Received/Transmitted data character */ + uint32_t FE :1; /*!< Framing error */ + uint32_t PE :1; /*!< Parity error */ + uint32_t BE :1; /*!< Break error */ + uint32_t OE :1; /*!< Overrun error */ +} _UART_DR_bits; + +/* Bit field positions: */ +#define UART_DR_DATA_Pos 0 /*!< Received/Transmitted data character */ +#define UART_DR_FE_Pos 8 /*!< Framing error */ +#define UART_DR_PE_Pos 9 /*!< Parity error */ +#define UART_DR_BE_Pos 10 /*!< Break error */ +#define UART_DR_OE_Pos 11 /*!< Overrun error */ + +/* Bit field masks: */ +#define UART_DR_DATA_Msk 0x000000FFUL /*!< Received/Transmitted data character */ +#define UART_DR_FE_Msk 0x00000100UL /*!< Framing error */ +#define UART_DR_PE_Msk 0x00000200UL /*!< Parity error */ +#define UART_DR_BE_Msk 0x00000400UL /*!< Break error */ +#define UART_DR_OE_Msk 0x00000800UL /*!< Overrun error */ + +/*-- RSR: Receive Status Register/Error Clear Register -------------------------------------------------------*/ +typedef struct { + uint32_t FE :1; /*!< Framing error */ + uint32_t PE :1; /*!< Parity error */ + uint32_t BE :1; /*!< Break error */ + uint32_t OE :1; /*!< Overrun error */ +} _UART_RSR_bits; + +/* Bit field positions: */ +#define UART_RSR_FE_Pos 0 /*!< Framing error */ +#define UART_RSR_PE_Pos 1 /*!< Parity error */ +#define UART_RSR_BE_Pos 2 /*!< Break error */ +#define UART_RSR_OE_Pos 3 /*!< Overrun error */ + +/* Bit field masks: */ +#define UART_RSR_FE_Msk 0x00000001UL /*!< Framing error */ +#define UART_RSR_PE_Msk 0x00000002UL /*!< Parity error */ +#define UART_RSR_BE_Msk 0x00000004UL /*!< Break error */ +#define UART_RSR_OE_Msk 0x00000008UL /*!< Overrun error */ + +/*-- FR: Flag Register ---------------------------------------------------------------------------------------*/ +typedef struct { + uint32_t :3; /*!< RESERVED */ + uint32_t BUSY :1; /*!< UART busy */ + uint32_t RXFE :1; /*!< Receive FIFO empty */ + uint32_t TXFF :1; /*!< Transmit FIFO full */ + uint32_t RXFF :1; /*!< Receive FIFO full */ + uint32_t TXFE :1; /*!< Transmit FIFO empty */ +} _UART_FR_bits; + +/* Bit field positions: */ +#define UART_FR_BUSY_Pos 3 /*!< UART busy */ +#define UART_FR_RXFE_Pos 4 /*!< Receive FIFO empty */ +#define UART_FR_TXFF_Pos 5 /*!< Transmit FIFO full */ +#define UART_FR_RXFF_Pos 6 /*!< Receive FIFO full */ +#define UART_FR_TXFE_Pos 7 /*!< Transmit FIFO empty */ + +/* Bit field masks: */ +#define UART_FR_BUSY_Msk 0x00000008UL /*!< UART busy */ +#define UART_FR_RXFE_Msk 0x00000010UL /*!< Receive FIFO empty */ +#define UART_FR_TXFF_Msk 0x00000020UL /*!< Transmit FIFO full */ +#define UART_FR_RXFF_Msk 0x00000040UL /*!< Receive FIFO full */ +#define UART_FR_TXFE_Msk 0x00000080UL /*!< Transmit FIFO empty */ + +/*-- IBRD: Integer Baud Rate Register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t DIVINT :16; /*!< The integer baud rate divisor */ +} _UART_IBRD_bits; + +/* Bit field positions: */ +#define UART_IBRD_DIVINT_Pos 0 /*!< The integer baud rate divisor */ + +/* Bit field masks: */ +#define UART_IBRD_DIVINT_Msk 0x0000FFFFUL /*!< The integer baud rate divisor */ + +/*-- FBRD: Fractional Baud Rate Register ---------------------------------------------------------------------*/ +typedef struct { + uint32_t DIVFRAC :6; /*!< The fractional baud rate divisor */ +} _UART_FBRD_bits; + +/* Bit field positions: */ +#define UART_FBRD_DIVFRAC_Pos 0 /*!< The fractional baud rate divisor */ + +/* Bit field masks: */ +#define UART_FBRD_DIVFRAC_Msk 0x0000003FUL /*!< The fractional baud rate divisor */ + +/*-- LCRH: Line Control Register -----------------------------------------------------------------------------*/ +typedef struct { + uint32_t BRK :1; /*!< Send break */ + uint32_t PEN :1; /*!< Parity enable */ + uint32_t EPS :1; /*!< Even parity select */ + uint32_t STP2 :1; /*!< Two stop bits select */ + uint32_t FEN :1; /*!< Enable FIFOs */ + uint32_t WLEN :2; /*!< Word length */ + uint32_t SPS :1; /*!< Stick parity select */ +} _UART_LCRH_bits; + +/* Bit field positions: */ +#define UART_LCRH_BRK_Pos 0 /*!< Send break */ +#define UART_LCRH_PEN_Pos 1 /*!< Parity enable */ +#define UART_LCRH_EPS_Pos 2 /*!< Even parity select */ +#define UART_LCRH_STP2_Pos 3 /*!< Two stop bits select */ +#define UART_LCRH_FEN_Pos 4 /*!< Enable FIFOs */ +#define UART_LCRH_WLEN_Pos 5 /*!< Word length */ +#define UART_LCRH_SPS_Pos 7 /*!< Stick parity select */ + +/* Bit field masks: */ +#define UART_LCRH_BRK_Msk 0x00000001UL /*!< Send break */ +#define UART_LCRH_PEN_Msk 0x00000002UL /*!< Parity enable */ +#define UART_LCRH_EPS_Msk 0x00000004UL /*!< Even parity select */ +#define UART_LCRH_STP2_Msk 0x00000008UL /*!< Two stop bits select */ +#define UART_LCRH_FEN_Msk 0x00000010UL /*!< Enable FIFOs */ +#define UART_LCRH_WLEN_Msk 0x00000060UL /*!< Word length */ +#define UART_LCRH_SPS_Msk 0x00000080UL /*!< Stick parity select */ + +/* Bit field enums: */ +typedef enum { + UART_LCRH_WLEN_5bit = 0x0UL, /*!< 5 bit in informational word */ + UART_LCRH_WLEN_6bit = 0x1UL, /*!< 6 bit in informational word */ + UART_LCRH_WLEN_7bit = 0x2UL, /*!< 7 bit in informational word */ + UART_LCRH_WLEN_8bit = 0x3UL, /*!< 8 bit in informational word */ +} UART_LCRH_WLEN_Enum; + +/*-- CR: Control Register ------------------------------------------------------------------------------------*/ +typedef struct { + uint32_t UARTEN :1; /*!< UART enable */ + uint32_t :7; /*!< RESERVED */ + uint32_t TXE :1; /*!< Transmit enable */ + uint32_t RXE :1; /*!< Receive enable */ +} _UART_CR_bits; + +/* Bit field positions: */ +#define UART_CR_UARTEN_Pos 0 /*!< UART enable */ +#define UART_CR_TXE_Pos 8 /*!< Transmit enable */ +#define UART_CR_RXE_Pos 9 /*!< Receive enable */ + +/* Bit field masks: */ +#define UART_CR_UARTEN_Msk 0x00000001UL /*!< UART enable */ +#define UART_CR_TXE_Msk 0x00000100UL /*!< Transmit enable */ +#define UART_CR_RXE_Msk 0x00000200UL /*!< Receive enable */ + +/*-- IFLS: Interrupt FIFO Level Select Register --------------------------------------------------------------*/ +typedef struct { + uint32_t TXIFLSEL :3; /*!< Transmit interrupt FIFO level select */ + uint32_t RXIFLSEL :3; /*!< Receive interrupt FIFO level select */ +} _UART_IFLS_bits; + +/* Bit field positions: */ +#define UART_IFLS_TXIFLSEL_Pos 0 /*!< Transmit interrupt FIFO level select */ +#define UART_IFLS_RXIFLSEL_Pos 3 /*!< Receive interrupt FIFO level select */ + +/* Bit field masks: */ +#define UART_IFLS_TXIFLSEL_Msk 0x00000007UL /*!< Transmit interrupt FIFO level select */ +#define UART_IFLS_RXIFLSEL_Msk 0x00000038UL /*!< Receive interrupt FIFO level select */ + +/* Bit field enums: */ +typedef enum { + UART_IFLS_TXIFLSEL_Lvl18 = 0x0UL, /*!< interrupt on 1/8 */ + UART_IFLS_TXIFLSEL_Lvl14 = 0x1UL, /*!< interrupt on 1/4 */ + UART_IFLS_TXIFLSEL_Lvl12 = 0x2UL, /*!< interrupt on 1/2 */ + UART_IFLS_TXIFLSEL_Lvl34 = 0x3UL, /*!< interrupt on 3/4 */ + UART_IFLS_TXIFLSEL_Lvl78 = 0x4UL, /*!< interrupt on 7/8 */ +} UART_IFLS_TXIFLSEL_Enum; + +typedef enum { + UART_IFLS_RXIFLSEL_Lvl18 = 0x0UL, /*!< interrupt on 1/8 */ + UART_IFLS_RXIFLSEL_Lvl14 = 0x1UL, /*!< interrupt on 1/4 */ + UART_IFLS_RXIFLSEL_Lvl12 = 0x2UL, /*!< interrupt on 1/2 */ + UART_IFLS_RXIFLSEL_Lvl34 = 0x3UL, /*!< interrupt on 3/4 */ + UART_IFLS_RXIFLSEL_Lvl78 = 0x4UL, /*!< interrupt on 7/8 */ +} UART_IFLS_RXIFLSEL_Enum; + +/*-- IMSC: Interrupt Mask Set/Clear Register -----------------------------------------------------------------*/ +typedef struct { + uint32_t :4; /*!< RESERVED */ + uint32_t RXIM :1; /*!< Receive interrupt mask */ + uint32_t TXIM :1; /*!< Transmit interrupt mask */ + uint32_t RTIM :1; /*!< Receive timeout interrupt mask */ + uint32_t FERIM :1; /*!< Framing error interrupt mask */ + uint32_t PERIM :1; /*!< Parity error interrupt mask */ + uint32_t BERIM :1; /*!< Break error interrupt mask */ + uint32_t OERIM :1; /*!< Overrun error interrupt mask */ + uint32_t TDIM :1; /*!< Transmit done interrupt mask */ +} _UART_IMSC_bits; + +/* Bit field positions: */ +#define UART_IMSC_RXIM_Pos 4 /*!< Receive interrupt mask */ +#define UART_IMSC_TXIM_Pos 5 /*!< Transmit interrupt mask */ +#define UART_IMSC_RTIM_Pos 6 /*!< Receive timeout interrupt mask */ +#define UART_IMSC_FERIM_Pos 7 /*!< Framing error interrupt mask */ +#define UART_IMSC_PERIM_Pos 8 /*!< Parity error interrupt mask */ +#define UART_IMSC_BERIM_Pos 9 /*!< Break error interrupt mask */ +#define UART_IMSC_OERIM_Pos 10 /*!< Overrun error interrupt mask */ +#define UART_IMSC_TDIM_Pos 11 /*!< Transmit done interrupt mask */ + +/* Bit field masks: */ +#define UART_IMSC_RXIM_Msk 0x00000010UL /*!< Receive interrupt mask */ +#define UART_IMSC_TXIM_Msk 0x00000020UL /*!< Transmit interrupt mask */ +#define UART_IMSC_RTIM_Msk 0x00000040UL /*!< Receive timeout interrupt mask */ +#define UART_IMSC_FERIM_Msk 0x00000080UL /*!< Framing error interrupt mask */ +#define UART_IMSC_PERIM_Msk 0x00000100UL /*!< Parity error interrupt mask */ +#define UART_IMSC_BERIM_Msk 0x00000200UL /*!< Break error interrupt mask */ +#define UART_IMSC_OERIM_Msk 0x00000400UL /*!< Overrun error interrupt mask */ +#define UART_IMSC_TDIM_Msk 0x00000800UL /*!< Transmit done interrupt mask */ + +/*-- RIS: Raw Interrupt Status Register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t :4; /*!< RESERVED */ + uint32_t RXRIS :1; /*!< Receive interrupt status */ + uint32_t TXRIS :1; /*!< Transmit interrupt status */ + uint32_t RTRIS :1; /*!< Receive timeout interrupt status */ + uint32_t FERIS :1; /*!< Framing error interrupt status */ + uint32_t PERIS :1; /*!< Parity error interrupt status */ + uint32_t BERIS :1; /*!< Break error interrupt status */ + uint32_t OERIS :1; /*!< Overrun error interrupt status */ + uint32_t TDRIS :1; /*!< Transmit done raw interrupt status */ +} _UART_RIS_bits; + +/* Bit field positions: */ +#define UART_RIS_RXRIS_Pos 4 /*!< Receive interrupt status */ +#define UART_RIS_TXRIS_Pos 5 /*!< Transmit interrupt status */ +#define UART_RIS_RTRIS_Pos 6 /*!< Receive timeout interrupt status */ +#define UART_RIS_FERIS_Pos 7 /*!< Framing error interrupt status */ +#define UART_RIS_PERIS_Pos 8 /*!< Parity error interrupt status */ +#define UART_RIS_BERIS_Pos 9 /*!< Break error interrupt status */ +#define UART_RIS_OERIS_Pos 10 /*!< Overrun error interrupt status */ +#define UART_RIS_TDRIS_Pos 11 /*!< Transmit done raw interrupt status */ + +/* Bit field masks: */ +#define UART_RIS_RXRIS_Msk 0x00000010UL /*!< Receive interrupt status */ +#define UART_RIS_TXRIS_Msk 0x00000020UL /*!< Transmit interrupt status */ +#define UART_RIS_RTRIS_Msk 0x00000040UL /*!< Receive timeout interrupt status */ +#define UART_RIS_FERIS_Msk 0x00000080UL /*!< Framing error interrupt status */ +#define UART_RIS_PERIS_Msk 0x00000100UL /*!< Parity error interrupt status */ +#define UART_RIS_BERIS_Msk 0x00000200UL /*!< Break error interrupt status */ +#define UART_RIS_OERIS_Msk 0x00000400UL /*!< Overrun error interrupt status */ +#define UART_RIS_TDRIS_Msk 0x00000800UL /*!< Transmit done raw interrupt status */ + +/*-- MIS: Masked Interrupt Status Register -------------------------------------------------------------------*/ +typedef struct { + uint32_t :4; /*!< RESERVED */ + uint32_t RXMIS :1; /*!< Receive masked interrupt status */ + uint32_t TXMIS :1; /*!< Transmit masked interrupt status */ + uint32_t RTMIS :1; /*!< Receive timeout masked interrupt status */ + uint32_t FEMIS :1; /*!< Framing error masked interrupt status */ + uint32_t PEMIS :1; /*!< Parity error masked interrupt status */ + uint32_t BEMIS :1; /*!< Break error masked interrupt status */ + uint32_t OEMIS :1; /*!< Overrun error masked interrupt status */ + uint32_t TDMIS :1; /*!< Transmit done masked interrupt status */ +} _UART_MIS_bits; + +/* Bit field positions: */ +#define UART_MIS_RXMIS_Pos 4 /*!< Receive masked interrupt status */ +#define UART_MIS_TXMIS_Pos 5 /*!< Transmit masked interrupt status */ +#define UART_MIS_RTMIS_Pos 6 /*!< Receive timeout masked interrupt status */ +#define UART_MIS_FEMIS_Pos 7 /*!< Framing error masked interrupt status */ +#define UART_MIS_PEMIS_Pos 8 /*!< Parity error masked interrupt status */ +#define UART_MIS_BEMIS_Pos 9 /*!< Break error masked interrupt status */ +#define UART_MIS_OEMIS_Pos 10 /*!< Overrun error masked interrupt status */ +#define UART_MIS_TDMIS_Pos 11 /*!< Transmit done masked interrupt status */ + +/* Bit field masks: */ +#define UART_MIS_RXMIS_Msk 0x00000010UL /*!< Receive masked interrupt status */ +#define UART_MIS_TXMIS_Msk 0x00000020UL /*!< Transmit masked interrupt status */ +#define UART_MIS_RTMIS_Msk 0x00000040UL /*!< Receive timeout masked interrupt status */ +#define UART_MIS_FEMIS_Msk 0x00000080UL /*!< Framing error masked interrupt status */ +#define UART_MIS_PEMIS_Msk 0x00000100UL /*!< Parity error masked interrupt status */ +#define UART_MIS_BEMIS_Msk 0x00000200UL /*!< Break error masked interrupt status */ +#define UART_MIS_OEMIS_Msk 0x00000400UL /*!< Overrun error masked interrupt status */ +#define UART_MIS_TDMIS_Msk 0x00000800UL /*!< Transmit done masked interrupt status */ + +/*-- ICR: Interrupt Clear Register ---------------------------------------------------------------------------*/ +typedef struct { + uint32_t :4; /*!< RESERVED */ + uint32_t RXIC :1; /*!< Receive interrupt clear */ + uint32_t TXIC :1; /*!< Transmit interrupt clear */ + uint32_t RTIC :1; /*!< Receive timeout interrupt clear */ + uint32_t FEIC :1; /*!< Framing error interrupt clear */ + uint32_t PEIC :1; /*!< Parity error interrupt clear */ + uint32_t BEIC :1; /*!< Break error interrupt clear */ + uint32_t OEIC :1; /*!< Overrun error interrupt clear */ + uint32_t TDIC :1; /*!< Transmit done interrupt clear */ +} _UART_ICR_bits; + +/* Bit field positions: */ +#define UART_ICR_RXIC_Pos 4 /*!< Receive interrupt clear */ +#define UART_ICR_TXIC_Pos 5 /*!< Transmit interrupt clear */ +#define UART_ICR_RTIC_Pos 6 /*!< Receive timeout interrupt clear */ +#define UART_ICR_FEIC_Pos 7 /*!< Framing error interrupt clear */ +#define UART_ICR_PEIC_Pos 8 /*!< Parity error interrupt clear */ +#define UART_ICR_BEIC_Pos 9 /*!< Break error interrupt clear */ +#define UART_ICR_OEIC_Pos 10 /*!< Overrun error interrupt clear */ +#define UART_ICR_TDIC_Pos 11 /*!< Transmit done interrupt clear */ + +/* Bit field masks: */ +#define UART_ICR_RXIC_Msk 0x00000010UL /*!< Receive interrupt clear */ +#define UART_ICR_TXIC_Msk 0x00000020UL /*!< Transmit interrupt clear */ +#define UART_ICR_RTIC_Msk 0x00000040UL /*!< Receive timeout interrupt clear */ +#define UART_ICR_FEIC_Msk 0x00000080UL /*!< Framing error interrupt clear */ +#define UART_ICR_PEIC_Msk 0x00000100UL /*!< Parity error interrupt clear */ +#define UART_ICR_BEIC_Msk 0x00000200UL /*!< Break error interrupt clear */ +#define UART_ICR_OEIC_Msk 0x00000400UL /*!< Overrun error interrupt clear */ +#define UART_ICR_TDIC_Msk 0x00000800UL /*!< Transmit done interrupt clear */ + +/*-- DMACR: DMA Control Register -----------------------------------------------------------------------------*/ +typedef struct { + uint32_t RXDMAE :1; /*!< Receive DMA enable */ + uint32_t TXDMAE :1; /*!< Transmit DMA enable */ + uint32_t DMAONERR :1; /*!< DMA on error */ +} _UART_DMACR_bits; + +/* Bit field positions: */ +#define UART_DMACR_RXDMAE_Pos 0 /*!< Receive DMA enable */ +#define UART_DMACR_TXDMAE_Pos 1 /*!< Transmit DMA enable */ +#define UART_DMACR_DMAONERR_Pos 2 /*!< DMA on error */ + +/* Bit field masks: */ +#define UART_DMACR_RXDMAE_Msk 0x00000001UL /*!< Receive DMA enable */ +#define UART_DMACR_TXDMAE_Msk 0x00000002UL /*!< Transmit DMA enable */ +#define UART_DMACR_DMAONERR_Msk 0x00000004UL /*!< DMA on error */ + +typedef struct { + union { /*!< Data Register */ + __IO uint32_t DR; /*!< DR : type used for word access */ + __IO _UART_DR_bits DR_bit; /*!< DR_bit: structure used for bit access */ + }; + union { /*!< Receive Status Register/Error Clear Register */ + __IO uint32_t RSR; /*!< RSR : type used for word access */ + __IO _UART_RSR_bits RSR_bit; /*!< RSR_bit: structure used for bit access */ + }; + __IO uint32_t Reserved0[4]; + union { /*!< Flag Register */ + __I uint32_t FR; /*!< FR : type used for word access */ + __I _UART_FR_bits FR_bit; /*!< FR_bit: structure used for bit access */ + }; + __IO uint32_t Reserved1[2]; + union { /*!< Integer Baud Rate Register */ + __IO uint32_t IBRD; /*!< IBRD : type used for word access */ + __IO _UART_IBRD_bits IBRD_bit; /*!< IBRD_bit: structure used for bit access */ + }; + union { /*!< Fractional Baud Rate Register */ + __IO uint32_t FBRD; /*!< FBRD : type used for word access */ + __IO _UART_FBRD_bits FBRD_bit; /*!< FBRD_bit: structure used for bit access */ + }; + union { /*!< Line Control Register */ + __IO uint32_t LCRH; /*!< LCRH : type used for word access */ + __IO _UART_LCRH_bits LCRH_bit; /*!< LCRH_bit: structure used for bit access */ + }; + union { /*!< Control Register */ + __IO uint32_t CR; /*!< CR : type used for word access */ + __IO _UART_CR_bits CR_bit; /*!< CR_bit: structure used for bit access */ + }; + union { /*!< Interrupt FIFO Level Select Register */ + __IO uint32_t IFLS; /*!< IFLS : type used for word access */ + __IO _UART_IFLS_bits IFLS_bit; /*!< IFLS_bit: structure used for bit access */ + }; + union { /*!< Interrupt Mask Set/Clear Register */ + __IO uint32_t IMSC; /*!< IMSC : type used for word access */ + __IO _UART_IMSC_bits IMSC_bit; /*!< IMSC_bit: structure used for bit access */ + }; + union { /*!< Raw Interrupt Status Register */ + __IO uint32_t RIS; /*!< RIS : type used for word access */ + __IO _UART_RIS_bits RIS_bit; /*!< RIS_bit: structure used for bit access */ + }; + union { /*!< Masked Interrupt Status Register */ + __IO uint32_t MIS; /*!< MIS : type used for word access */ + __IO _UART_MIS_bits MIS_bit; /*!< MIS_bit: structure used for bit access */ + }; + union { /*!< Interrupt Clear Register */ + __IO uint32_t ICR; /*!< ICR : type used for word access */ + __IO _UART_ICR_bits ICR_bit; /*!< ICR_bit: structure used for bit access */ + }; + union { /*!< DMA Control Register */ + __IO uint32_t DMACR; /*!< DMACR : type used for word access */ + __IO _UART_DMACR_bits DMACR_bit; /*!< DMACR_bit: structure used for bit access */ + }; +} UART_TypeDef; + + +/******************************************************************************/ +/* DMA registers */ +/******************************************************************************/ + +/*-- STATUS: Status DMA register -----------------------------------------------------------------------------*/ +typedef struct { + uint32_t MASTEREN :1; /*!< Indicate enable DMA */ + uint32_t :3; /*!< RESERVED */ + uint32_t STATE :4; /*!< State of DMA */ + uint32_t :8; /*!< RESERVED */ + uint32_t CHNLS :5; /*!< Number channel DMA (write: N-1) */ +} _DMA_STATUS_bits; + +/* Bit field positions: */ +#define DMA_STATUS_MASTEREN_Pos 0 /*!< Indicate enable DMA */ +#define DMA_STATUS_STATE_Pos 4 /*!< State of DMA */ +#define DMA_STATUS_CHNLS_Pos 16 /*!< Number channel DMA (write: N-1) */ + +/* Bit field masks: */ +#define DMA_STATUS_MASTEREN_Msk 0x00000001UL /*!< Indicate enable DMA */ +#define DMA_STATUS_STATE_Msk 0x000000F0UL /*!< State of DMA */ +#define DMA_STATUS_CHNLS_Msk 0x001F0000UL /*!< Number channel DMA (write: N-1) */ + +/* Bit field enums: */ +typedef enum { + DMA_STATUS_STATE_Free = 0x0UL, /*!< At rest */ + DMA_STATUS_STATE_ReadConfigData = 0x1UL, /*!< Reading the config data structure */ + DMA_STATUS_STATE_ReadSrcDataEndPtr = 0x2UL, /*!< Reading sourse data end pointer */ + DMA_STATUS_STATE_ReadDstDataEndPtr = 0x3UL, /*!< Reading destination data end pointer */ + DMA_STATUS_STATE_ReadSrcData = 0x4UL, /*!< Reading source data */ + DMA_STATUS_STATE_WrireDstData = 0x5UL, /*!< Writing data to the destination */ + DMA_STATUS_STATE_WaitReq = 0x6UL, /*!< Waiting for a request */ + DMA_STATUS_STATE_WriteConfigData = 0x7UL, /*!< Write config structure of the channel */ + DMA_STATUS_STATE_Pause = 0x8UL, /*!< Suspended */ + DMA_STATUS_STATE_Done = 0x9UL, /*!< Executed */ + DMA_STATUS_STATE_PeriphScatGath = 0xAUL, /*!< mode "peripheral scather-gather" */ +} DMA_STATUS_STATE_Enum; + +/*-- CFG: DMA configuration register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t MASTEREN :1; /*!< Enable DMA */ + uint32_t :4; /*!< RESERVED */ + uint32_t CHPROT :3; /*!< Sets the AHB-Lite protection */ +} _DMA_CFG_bits; + +/* Bit field positions: */ +#define DMA_CFG_MASTEREN_Pos 0 /*!< Enable DMA */ +#define DMA_CFG_CHPROT_Pos 5 /*!< Sets the AHB-Lite protection */ + +/* Bit field masks: */ +#define DMA_CFG_MASTEREN_Msk 0x00000001UL /*!< Enable DMA */ +#define DMA_CFG_CHPROT_Msk 0x000000E0UL /*!< Sets the AHB-Lite protection */ + +/*-- BASEPTR: Channel control data base pointer --------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Base address of the primary control data */ +} _DMA_BASEPTR_bits; + +/* Bit field positions: */ +#define DMA_BASEPTR_VAL_Pos 0 /*!< Base address of the primary control data */ + +/* Bit field masks: */ +#define DMA_BASEPTR_VAL_Msk 0xFFFFFFFFUL /*!< Base address of the primary control data */ + +/*-- ALTBASEPTR: Channel alternate control data base pointer -------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Base address of alternative control data */ +} _DMA_ALTBASEPTR_bits; + +/* Bit field positions: */ +#define DMA_ALTBASEPTR_VAL_Pos 0 /*!< Base address of alternative control data */ + +/* Bit field masks: */ +#define DMA_ALTBASEPTR_VAL_Msk 0xFFFFFFFFUL /*!< Base address of alternative control data */ + +/*-- WAITONREQ: Channel wait on request status ---------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH1 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH2 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH3 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH4 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH5 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH6 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH7 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH8 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH9 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH10 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH11 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH12 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH13 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH14 :1; /*!< Returns the status of the DMA request signals */ + uint32_t CH15 :1; /*!< Returns the status of the DMA request signals */ +} _DMA_WAITONREQ_bits; + +/* Bit field positions: */ +#define DMA_WAITONREQ_CH0_Pos 0 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH1_Pos 1 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH2_Pos 2 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH3_Pos 3 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH4_Pos 4 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH5_Pos 5 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH6_Pos 6 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH7_Pos 7 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH8_Pos 8 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH9_Pos 9 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH10_Pos 10 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH11_Pos 11 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH12_Pos 12 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH13_Pos 13 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH14_Pos 14 /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH15_Pos 15 /*!< Returns the status of the DMA request signals */ + +/* Bit field masks: */ +#define DMA_WAITONREQ_CH0_Msk 0x00000001UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH1_Msk 0x00000002UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH2_Msk 0x00000004UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH3_Msk 0x00000008UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH4_Msk 0x00000010UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH5_Msk 0x00000020UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH6_Msk 0x00000040UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH7_Msk 0x00000080UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH8_Msk 0x00000100UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH9_Msk 0x00000200UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH10_Msk 0x00000400UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH11_Msk 0x00000800UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH12_Msk 0x00001000UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH13_Msk 0x00002000UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH14_Msk 0x00004000UL /*!< Returns the status of the DMA request signals */ +#define DMA_WAITONREQ_CH15_Msk 0x00008000UL /*!< Returns the status of the DMA request signals */ + +/*-- SWREQ: Channel software request -------------------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< Set software request on channel */ + uint32_t CH1 :1; /*!< Set software request on channel */ + uint32_t CH2 :1; /*!< Set software request on channel */ + uint32_t CH3 :1; /*!< Set software request on channel */ + uint32_t CH4 :1; /*!< Set software request on channel */ + uint32_t CH5 :1; /*!< Set software request on channel */ + uint32_t CH6 :1; /*!< Set software request on channel */ + uint32_t CH7 :1; /*!< Set software request on channel */ + uint32_t CH8 :1; /*!< Set software request on channel */ + uint32_t CH9 :1; /*!< Set software request on channel */ + uint32_t CH10 :1; /*!< Set software request on channel */ + uint32_t CH11 :1; /*!< Set software request on channel */ + uint32_t CH12 :1; /*!< Set software request on channel */ + uint32_t CH13 :1; /*!< Set software request on channel */ + uint32_t CH14 :1; /*!< Set software request on channel */ + uint32_t CH15 :1; /*!< Set software request on channel */ +} _DMA_SWREQ_bits; + +/* Bit field positions: */ +#define DMA_SWREQ_CH0_Pos 0 /*!< Set software request on channel */ +#define DMA_SWREQ_CH1_Pos 1 /*!< Set software request on channel */ +#define DMA_SWREQ_CH2_Pos 2 /*!< Set software request on channel */ +#define DMA_SWREQ_CH3_Pos 3 /*!< Set software request on channel */ +#define DMA_SWREQ_CH4_Pos 4 /*!< Set software request on channel */ +#define DMA_SWREQ_CH5_Pos 5 /*!< Set software request on channel */ +#define DMA_SWREQ_CH6_Pos 6 /*!< Set software request on channel */ +#define DMA_SWREQ_CH7_Pos 7 /*!< Set software request on channel */ +#define DMA_SWREQ_CH8_Pos 8 /*!< Set software request on channel */ +#define DMA_SWREQ_CH9_Pos 9 /*!< Set software request on channel */ +#define DMA_SWREQ_CH10_Pos 10 /*!< Set software request on channel */ +#define DMA_SWREQ_CH11_Pos 11 /*!< Set software request on channel */ +#define DMA_SWREQ_CH12_Pos 12 /*!< Set software request on channel */ +#define DMA_SWREQ_CH13_Pos 13 /*!< Set software request on channel */ +#define DMA_SWREQ_CH14_Pos 14 /*!< Set software request on channel */ +#define DMA_SWREQ_CH15_Pos 15 /*!< Set software request on channel */ + +/* Bit field masks: */ +#define DMA_SWREQ_CH0_Msk 0x00000001UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH1_Msk 0x00000002UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH2_Msk 0x00000004UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH3_Msk 0x00000008UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH4_Msk 0x00000010UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH5_Msk 0x00000020UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH6_Msk 0x00000040UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH7_Msk 0x00000080UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH8_Msk 0x00000100UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH9_Msk 0x00000200UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH10_Msk 0x00000400UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH11_Msk 0x00000800UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH12_Msk 0x00001000UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH13_Msk 0x00002000UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH14_Msk 0x00004000UL /*!< Set software request on channel */ +#define DMA_SWREQ_CH15_Msk 0x00008000UL /*!< Set software request on channel */ + +/*-- USEBURSTSET: Channel useburst set -----------------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< Enable single requests */ + uint32_t CH1 :1; /*!< Enable single requests */ + uint32_t CH2 :1; /*!< Enable single requests */ + uint32_t CH3 :1; /*!< Enable single requests */ + uint32_t CH4 :1; /*!< Enable single requests */ + uint32_t CH5 :1; /*!< Enable single requests */ + uint32_t CH6 :1; /*!< Enable single requests */ + uint32_t CH7 :1; /*!< Enable single requests */ + uint32_t CH8 :1; /*!< Enable single requests */ + uint32_t CH9 :1; /*!< Enable single requests */ + uint32_t CH10 :1; /*!< Enable single requests */ + uint32_t CH11 :1; /*!< Enable single requests */ + uint32_t CH12 :1; /*!< Enable single requests */ + uint32_t CH13 :1; /*!< Enable single requests */ + uint32_t CH14 :1; /*!< Enable single requests */ + uint32_t CH15 :1; /*!< Enable single requests */ +} _DMA_USEBURSTSET_bits; + +/* Bit field positions: */ +#define DMA_USEBURSTSET_CH0_Pos 0 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH1_Pos 1 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH2_Pos 2 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH3_Pos 3 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH4_Pos 4 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH5_Pos 5 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH6_Pos 6 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH7_Pos 7 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH8_Pos 8 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH9_Pos 9 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH10_Pos 10 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH11_Pos 11 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH12_Pos 12 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH13_Pos 13 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH14_Pos 14 /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH15_Pos 15 /*!< Enable single requests */ + +/* Bit field masks: */ +#define DMA_USEBURSTSET_CH0_Msk 0x00000001UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH1_Msk 0x00000002UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH2_Msk 0x00000004UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH3_Msk 0x00000008UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH4_Msk 0x00000010UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH5_Msk 0x00000020UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH6_Msk 0x00000040UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH7_Msk 0x00000080UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH8_Msk 0x00000100UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH9_Msk 0x00000200UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH10_Msk 0x00000400UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH11_Msk 0x00000800UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH12_Msk 0x00001000UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH13_Msk 0x00002000UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH14_Msk 0x00004000UL /*!< Enable single requests */ +#define DMA_USEBURSTSET_CH15_Msk 0x00008000UL /*!< Enable single requests */ + +/*-- USEBURSTCLR: Channel useburst clear ---------------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< Disable single requests */ + uint32_t CH1 :1; /*!< Disable single requests */ + uint32_t CH2 :1; /*!< Disable single requests */ + uint32_t CH3 :1; /*!< Disable single requests */ + uint32_t CH4 :1; /*!< Disable single requests */ + uint32_t CH5 :1; /*!< Disable single requests */ + uint32_t CH6 :1; /*!< Disable single requests */ + uint32_t CH7 :1; /*!< Disable single requests */ + uint32_t CH8 :1; /*!< Disable single requests */ + uint32_t CH9 :1; /*!< Disable single requests */ + uint32_t CH10 :1; /*!< Disable single requests */ + uint32_t CH11 :1; /*!< Disable single requests */ + uint32_t CH12 :1; /*!< Disable single requests */ + uint32_t CH13 :1; /*!< Disable single requests */ + uint32_t CH14 :1; /*!< Disable single requests */ + uint32_t CH15 :1; /*!< Disable single requests */ +} _DMA_USEBURSTCLR_bits; + +/* Bit field positions: */ +#define DMA_USEBURSTCLR_CH0_Pos 0 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH1_Pos 1 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH2_Pos 2 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH3_Pos 3 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH4_Pos 4 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH5_Pos 5 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH6_Pos 6 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH7_Pos 7 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH8_Pos 8 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH9_Pos 9 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH10_Pos 10 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH11_Pos 11 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH12_Pos 12 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH13_Pos 13 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH14_Pos 14 /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH15_Pos 15 /*!< Disable single requests */ + +/* Bit field masks: */ +#define DMA_USEBURSTCLR_CH0_Msk 0x00000001UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH1_Msk 0x00000002UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH2_Msk 0x00000004UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH3_Msk 0x00000008UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH4_Msk 0x00000010UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH5_Msk 0x00000020UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH6_Msk 0x00000040UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH7_Msk 0x00000080UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH8_Msk 0x00000100UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH9_Msk 0x00000200UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH10_Msk 0x00000400UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH11_Msk 0x00000800UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH12_Msk 0x00001000UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH13_Msk 0x00002000UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH14_Msk 0x00004000UL /*!< Disable single requests */ +#define DMA_USEBURSTCLR_CH15_Msk 0x00008000UL /*!< Disable single requests */ + +/*-- REQMASKSET: Channel request mask set --------------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< External requests are enabled for channel */ + uint32_t CH1 :1; /*!< External requests are enabled for channel */ + uint32_t CH2 :1; /*!< External requests are enabled for channel */ + uint32_t CH3 :1; /*!< External requests are enabled for channel */ + uint32_t CH4 :1; /*!< External requests are enabled for channel */ + uint32_t CH5 :1; /*!< External requests are enabled for channel */ + uint32_t CH6 :1; /*!< External requests are enabled for channel */ + uint32_t CH7 :1; /*!< External requests are enabled for channel */ + uint32_t CH8 :1; /*!< External requests are enabled for channel */ + uint32_t CH9 :1; /*!< External requests are enabled for channel */ + uint32_t CH10 :1; /*!< External requests are enabled for channel */ + uint32_t CH11 :1; /*!< External requests are enabled for channel */ + uint32_t CH12 :1; /*!< External requests are enabled for channel */ + uint32_t CH13 :1; /*!< External requests are enabled for channel */ + uint32_t CH14 :1; /*!< External requests are enabled for channel */ + uint32_t CH15 :1; /*!< External requests are enabled for channel */ +} _DMA_REQMASKSET_bits; + +/* Bit field positions: */ +#define DMA_REQMASKSET_CH0_Pos 0 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH1_Pos 1 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH2_Pos 2 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH3_Pos 3 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH4_Pos 4 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH5_Pos 5 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH6_Pos 6 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH7_Pos 7 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH8_Pos 8 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH9_Pos 9 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH10_Pos 10 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH11_Pos 11 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH12_Pos 12 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH13_Pos 13 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH14_Pos 14 /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH15_Pos 15 /*!< External requests are enabled for channel */ + +/* Bit field masks: */ +#define DMA_REQMASKSET_CH0_Msk 0x00000001UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH1_Msk 0x00000002UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH2_Msk 0x00000004UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH3_Msk 0x00000008UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH4_Msk 0x00000010UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH5_Msk 0x00000020UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH6_Msk 0x00000040UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH7_Msk 0x00000080UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH8_Msk 0x00000100UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH9_Msk 0x00000200UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH10_Msk 0x00000400UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH11_Msk 0x00000800UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH12_Msk 0x00001000UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH13_Msk 0x00002000UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH14_Msk 0x00004000UL /*!< External requests are enabled for channel */ +#define DMA_REQMASKSET_CH15_Msk 0x00008000UL /*!< External requests are enabled for channel */ + +/*-- REQMASKCLR: Channel request mask clear ------------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< External requests are disabled for channel */ + uint32_t CH1 :1; /*!< External requests are disabled for channel */ + uint32_t CH2 :1; /*!< External requests are disabled for channel */ + uint32_t CH3 :1; /*!< External requests are disabled for channel */ + uint32_t CH4 :1; /*!< External requests are disabled for channel */ + uint32_t CH5 :1; /*!< External requests are disabled for channel */ + uint32_t CH6 :1; /*!< External requests are disabled for channel */ + uint32_t CH7 :1; /*!< External requests are disabled for channel */ + uint32_t CH8 :1; /*!< External requests are disabled for channel */ + uint32_t CH9 :1; /*!< External requests are disabled for channel */ + uint32_t CH10 :1; /*!< External requests are disabled for channel */ + uint32_t CH11 :1; /*!< External requests are disabled for channel */ + uint32_t CH12 :1; /*!< External requests are disabled for channel */ + uint32_t CH13 :1; /*!< External requests are disabled for channel */ + uint32_t CH14 :1; /*!< External requests are disabled for channel */ + uint32_t CH15 :1; /*!< External requests are disabled for channel */ +} _DMA_REQMASKCLR_bits; + +/* Bit field positions: */ +#define DMA_REQMASKCLR_CH0_Pos 0 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH1_Pos 1 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH2_Pos 2 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH3_Pos 3 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH4_Pos 4 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH5_Pos 5 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH6_Pos 6 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH7_Pos 7 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH8_Pos 8 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH9_Pos 9 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH10_Pos 10 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH11_Pos 11 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH12_Pos 12 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH13_Pos 13 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH14_Pos 14 /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH15_Pos 15 /*!< External requests are disabled for channel */ + +/* Bit field masks: */ +#define DMA_REQMASKCLR_CH0_Msk 0x00000001UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH1_Msk 0x00000002UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH2_Msk 0x00000004UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH3_Msk 0x00000008UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH4_Msk 0x00000010UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH5_Msk 0x00000020UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH6_Msk 0x00000040UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH7_Msk 0x00000080UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH8_Msk 0x00000100UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH9_Msk 0x00000200UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH10_Msk 0x00000400UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH11_Msk 0x00000800UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH12_Msk 0x00001000UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH13_Msk 0x00002000UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH14_Msk 0x00004000UL /*!< External requests are disabled for channel */ +#define DMA_REQMASKCLR_CH15_Msk 0x00008000UL /*!< External requests are disabled for channel */ + +/*-- ENSET: Channel enable set -------------------------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< Enable channel */ + uint32_t CH1 :1; /*!< Enable channel */ + uint32_t CH2 :1; /*!< Enable channel */ + uint32_t CH3 :1; /*!< Enable channel */ + uint32_t CH4 :1; /*!< Enable channel */ + uint32_t CH5 :1; /*!< Enable channel */ + uint32_t CH6 :1; /*!< Enable channel */ + uint32_t CH7 :1; /*!< Enable channel */ + uint32_t CH8 :1; /*!< Enable channel */ + uint32_t CH9 :1; /*!< Enable channel */ + uint32_t CH10 :1; /*!< Enable channel */ + uint32_t CH11 :1; /*!< Enable channel */ + uint32_t CH12 :1; /*!< Enable channel */ + uint32_t CH13 :1; /*!< Enable channel */ + uint32_t CH14 :1; /*!< Enable channel */ + uint32_t CH15 :1; /*!< Enable channel */ +} _DMA_ENSET_bits; + +/* Bit field positions: */ +#define DMA_ENSET_CH0_Pos 0 /*!< Enable channel */ +#define DMA_ENSET_CH1_Pos 1 /*!< Enable channel */ +#define DMA_ENSET_CH2_Pos 2 /*!< Enable channel */ +#define DMA_ENSET_CH3_Pos 3 /*!< Enable channel */ +#define DMA_ENSET_CH4_Pos 4 /*!< Enable channel */ +#define DMA_ENSET_CH5_Pos 5 /*!< Enable channel */ +#define DMA_ENSET_CH6_Pos 6 /*!< Enable channel */ +#define DMA_ENSET_CH7_Pos 7 /*!< Enable channel */ +#define DMA_ENSET_CH8_Pos 8 /*!< Enable channel */ +#define DMA_ENSET_CH9_Pos 9 /*!< Enable channel */ +#define DMA_ENSET_CH10_Pos 10 /*!< Enable channel */ +#define DMA_ENSET_CH11_Pos 11 /*!< Enable channel */ +#define DMA_ENSET_CH12_Pos 12 /*!< Enable channel */ +#define DMA_ENSET_CH13_Pos 13 /*!< Enable channel */ +#define DMA_ENSET_CH14_Pos 14 /*!< Enable channel */ +#define DMA_ENSET_CH15_Pos 15 /*!< Enable channel */ + +/* Bit field masks: */ +#define DMA_ENSET_CH0_Msk 0x00000001UL /*!< Enable channel */ +#define DMA_ENSET_CH1_Msk 0x00000002UL /*!< Enable channel */ +#define DMA_ENSET_CH2_Msk 0x00000004UL /*!< Enable channel */ +#define DMA_ENSET_CH3_Msk 0x00000008UL /*!< Enable channel */ +#define DMA_ENSET_CH4_Msk 0x00000010UL /*!< Enable channel */ +#define DMA_ENSET_CH5_Msk 0x00000020UL /*!< Enable channel */ +#define DMA_ENSET_CH6_Msk 0x00000040UL /*!< Enable channel */ +#define DMA_ENSET_CH7_Msk 0x00000080UL /*!< Enable channel */ +#define DMA_ENSET_CH8_Msk 0x00000100UL /*!< Enable channel */ +#define DMA_ENSET_CH9_Msk 0x00000200UL /*!< Enable channel */ +#define DMA_ENSET_CH10_Msk 0x00000400UL /*!< Enable channel */ +#define DMA_ENSET_CH11_Msk 0x00000800UL /*!< Enable channel */ +#define DMA_ENSET_CH12_Msk 0x00001000UL /*!< Enable channel */ +#define DMA_ENSET_CH13_Msk 0x00002000UL /*!< Enable channel */ +#define DMA_ENSET_CH14_Msk 0x00004000UL /*!< Enable channel */ +#define DMA_ENSET_CH15_Msk 0x00008000UL /*!< Enable channel */ + +/*-- ENCLR: Channel enable clear -----------------------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< Disable channel */ + uint32_t CH1 :1; /*!< Disable channel */ + uint32_t CH2 :1; /*!< Disable channel */ + uint32_t CH3 :1; /*!< Disable channel */ + uint32_t CH4 :1; /*!< Disable channel */ + uint32_t CH5 :1; /*!< Disable channel */ + uint32_t CH6 :1; /*!< Disable channel */ + uint32_t CH7 :1; /*!< Disable channel */ + uint32_t CH8 :1; /*!< Disable channel */ + uint32_t CH9 :1; /*!< Disable channel */ + uint32_t CH10 :1; /*!< Disable channel */ + uint32_t CH11 :1; /*!< Disable channel */ + uint32_t CH12 :1; /*!< Disable channel */ + uint32_t CH13 :1; /*!< Disable channel */ + uint32_t CH14 :1; /*!< Disable channel */ + uint32_t CH15 :1; /*!< Disable channel */ +} _DMA_ENCLR_bits; + +/* Bit field positions: */ +#define DMA_ENCLR_CH0_Pos 0 /*!< Disable channel */ +#define DMA_ENCLR_CH1_Pos 1 /*!< Disable channel */ +#define DMA_ENCLR_CH2_Pos 2 /*!< Disable channel */ +#define DMA_ENCLR_CH3_Pos 3 /*!< Disable channel */ +#define DMA_ENCLR_CH4_Pos 4 /*!< Disable channel */ +#define DMA_ENCLR_CH5_Pos 5 /*!< Disable channel */ +#define DMA_ENCLR_CH6_Pos 6 /*!< Disable channel */ +#define DMA_ENCLR_CH7_Pos 7 /*!< Disable channel */ +#define DMA_ENCLR_CH8_Pos 8 /*!< Disable channel */ +#define DMA_ENCLR_CH9_Pos 9 /*!< Disable channel */ +#define DMA_ENCLR_CH10_Pos 10 /*!< Disable channel */ +#define DMA_ENCLR_CH11_Pos 11 /*!< Disable channel */ +#define DMA_ENCLR_CH12_Pos 12 /*!< Disable channel */ +#define DMA_ENCLR_CH13_Pos 13 /*!< Disable channel */ +#define DMA_ENCLR_CH14_Pos 14 /*!< Disable channel */ +#define DMA_ENCLR_CH15_Pos 15 /*!< Disable channel */ + +/* Bit field masks: */ +#define DMA_ENCLR_CH0_Msk 0x00000001UL /*!< Disable channel */ +#define DMA_ENCLR_CH1_Msk 0x00000002UL /*!< Disable channel */ +#define DMA_ENCLR_CH2_Msk 0x00000004UL /*!< Disable channel */ +#define DMA_ENCLR_CH3_Msk 0x00000008UL /*!< Disable channel */ +#define DMA_ENCLR_CH4_Msk 0x00000010UL /*!< Disable channel */ +#define DMA_ENCLR_CH5_Msk 0x00000020UL /*!< Disable channel */ +#define DMA_ENCLR_CH6_Msk 0x00000040UL /*!< Disable channel */ +#define DMA_ENCLR_CH7_Msk 0x00000080UL /*!< Disable channel */ +#define DMA_ENCLR_CH8_Msk 0x00000100UL /*!< Disable channel */ +#define DMA_ENCLR_CH9_Msk 0x00000200UL /*!< Disable channel */ +#define DMA_ENCLR_CH10_Msk 0x00000400UL /*!< Disable channel */ +#define DMA_ENCLR_CH11_Msk 0x00000800UL /*!< Disable channel */ +#define DMA_ENCLR_CH12_Msk 0x00001000UL /*!< Disable channel */ +#define DMA_ENCLR_CH13_Msk 0x00002000UL /*!< Disable channel */ +#define DMA_ENCLR_CH14_Msk 0x00004000UL /*!< Disable channel */ +#define DMA_ENCLR_CH15_Msk 0x00008000UL /*!< Disable channel */ + +/*-- PRIALTSET: Channel primary-alternate set ----------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH1 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH2 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH3 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH4 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH5 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH6 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH7 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH8 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH9 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH10 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH11 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH12 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH13 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH14 :1; /*!< Set primary / alternate channel control data structure */ + uint32_t CH15 :1; /*!< Set primary / alternate channel control data structure */ +} _DMA_PRIALTSET_bits; + +/* Bit field positions: */ +#define DMA_PRIALTSET_CH0_Pos 0 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH1_Pos 1 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH2_Pos 2 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH3_Pos 3 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH4_Pos 4 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH5_Pos 5 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH6_Pos 6 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH7_Pos 7 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH8_Pos 8 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH9_Pos 9 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH10_Pos 10 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH11_Pos 11 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH12_Pos 12 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH13_Pos 13 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH14_Pos 14 /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH15_Pos 15 /*!< Set primary / alternate channel control data structure */ + +/* Bit field masks: */ +#define DMA_PRIALTSET_CH0_Msk 0x00000001UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH1_Msk 0x00000002UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH2_Msk 0x00000004UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH3_Msk 0x00000008UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH4_Msk 0x00000010UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH5_Msk 0x00000020UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH6_Msk 0x00000040UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH7_Msk 0x00000080UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH8_Msk 0x00000100UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH9_Msk 0x00000200UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH10_Msk 0x00000400UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH11_Msk 0x00000800UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH12_Msk 0x00001000UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH13_Msk 0x00002000UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH14_Msk 0x00004000UL /*!< Set primary / alternate channel control data structure */ +#define DMA_PRIALTSET_CH15_Msk 0x00008000UL /*!< Set primary / alternate channel control data structure */ + +/*-- PRIALTCLR: Channel primary-alternate clear --------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH1 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH2 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH3 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH4 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH5 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH6 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH7 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH8 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH9 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH10 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH11 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH12 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH13 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH14 :1; /*!< Clear primary / alternate channel control data structure */ + uint32_t CH15 :1; /*!< Clear primary / alternate channel control data structure */ +} _DMA_PRIALTCLR_bits; + +/* Bit field positions: */ +#define DMA_PRIALTCLR_CH0_Pos 0 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH1_Pos 1 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH2_Pos 2 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH3_Pos 3 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH4_Pos 4 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH5_Pos 5 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH6_Pos 6 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH7_Pos 7 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH8_Pos 8 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH9_Pos 9 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH10_Pos 10 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH11_Pos 11 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH12_Pos 12 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH13_Pos 13 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH14_Pos 14 /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH15_Pos 15 /*!< Clear primary / alternate channel control data structure */ + +/* Bit field masks: */ +#define DMA_PRIALTCLR_CH0_Msk 0x00000001UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH1_Msk 0x00000002UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH2_Msk 0x00000004UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH3_Msk 0x00000008UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH4_Msk 0x00000010UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH5_Msk 0x00000020UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH6_Msk 0x00000040UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH7_Msk 0x00000080UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH8_Msk 0x00000100UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH9_Msk 0x00000200UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH10_Msk 0x00000400UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH11_Msk 0x00000800UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH12_Msk 0x00001000UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH13_Msk 0x00002000UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH14_Msk 0x00004000UL /*!< Clear primary / alternate channel control data structure */ +#define DMA_PRIALTCLR_CH15_Msk 0x00008000UL /*!< Clear primary / alternate channel control data structure */ + +/*-- PRIORITYSET: Channel priority set -----------------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< Set the priority of channel */ + uint32_t CH1 :1; /*!< Set the priority of channel */ + uint32_t CH2 :1; /*!< Set the priority of channel */ + uint32_t CH3 :1; /*!< Set the priority of channel */ + uint32_t CH4 :1; /*!< Set the priority of channel */ + uint32_t CH5 :1; /*!< Set the priority of channel */ + uint32_t CH6 :1; /*!< Set the priority of channel */ + uint32_t CH7 :1; /*!< Set the priority of channel */ + uint32_t CH8 :1; /*!< Set the priority of channel */ + uint32_t CH9 :1; /*!< Set the priority of channel */ + uint32_t CH10 :1; /*!< Set the priority of channel */ + uint32_t CH11 :1; /*!< Set the priority of channel */ + uint32_t CH12 :1; /*!< Set the priority of channel */ + uint32_t CH13 :1; /*!< Set the priority of channel */ + uint32_t CH14 :1; /*!< Set the priority of channel */ + uint32_t CH15 :1; /*!< Set the priority of channel */ +} _DMA_PRIORITYSET_bits; + +/* Bit field positions: */ +#define DMA_PRIORITYSET_CH0_Pos 0 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH1_Pos 1 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH2_Pos 2 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH3_Pos 3 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH4_Pos 4 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH5_Pos 5 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH6_Pos 6 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH7_Pos 7 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH8_Pos 8 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH9_Pos 9 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH10_Pos 10 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH11_Pos 11 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH12_Pos 12 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH13_Pos 13 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH14_Pos 14 /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH15_Pos 15 /*!< Set the priority of channel */ + +/* Bit field masks: */ +#define DMA_PRIORITYSET_CH0_Msk 0x00000001UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH1_Msk 0x00000002UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH2_Msk 0x00000004UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH3_Msk 0x00000008UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH4_Msk 0x00000010UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH5_Msk 0x00000020UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH6_Msk 0x00000040UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH7_Msk 0x00000080UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH8_Msk 0x00000100UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH9_Msk 0x00000200UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH10_Msk 0x00000400UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH11_Msk 0x00000800UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH12_Msk 0x00001000UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH13_Msk 0x00002000UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH14_Msk 0x00004000UL /*!< Set the priority of channel */ +#define DMA_PRIORITYSET_CH15_Msk 0x00008000UL /*!< Set the priority of channel */ + +/*-- PRIORITYCLR: Channel priority clear ---------------------------------------------------------------------*/ +typedef struct { + uint32_t CH0 :1; /*!< Clear the priority */ + uint32_t CH1 :1; /*!< Clear the priority */ + uint32_t CH2 :1; /*!< Clear the priority */ + uint32_t CH3 :1; /*!< Clear the priority */ + uint32_t CH4 :1; /*!< Clear the priority */ + uint32_t CH5 :1; /*!< Clear the priority */ + uint32_t CH6 :1; /*!< Clear the priority */ + uint32_t CH7 :1; /*!< Clear the priority */ + uint32_t CH8 :1; /*!< Clear the priority */ + uint32_t CH9 :1; /*!< Clear the priority */ + uint32_t CH10 :1; /*!< Clear the priority */ + uint32_t CH11 :1; /*!< Clear the priority */ + uint32_t CH12 :1; /*!< Clear the priority */ + uint32_t CH13 :1; /*!< Clear the priority */ + uint32_t CH14 :1; /*!< Clear the priority */ + uint32_t CH15 :1; /*!< Clear the priority */ +} _DMA_PRIORITYCLR_bits; + +/* Bit field positions: */ +#define DMA_PRIORITYCLR_CH0_Pos 0 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH1_Pos 1 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH2_Pos 2 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH3_Pos 3 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH4_Pos 4 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH5_Pos 5 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH6_Pos 6 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH7_Pos 7 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH8_Pos 8 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH9_Pos 9 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH10_Pos 10 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH11_Pos 11 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH12_Pos 12 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH13_Pos 13 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH14_Pos 14 /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH15_Pos 15 /*!< Clear the priority */ + +/* Bit field masks: */ +#define DMA_PRIORITYCLR_CH0_Msk 0x00000001UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH1_Msk 0x00000002UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH2_Msk 0x00000004UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH3_Msk 0x00000008UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH4_Msk 0x00000010UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH5_Msk 0x00000020UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH6_Msk 0x00000040UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH7_Msk 0x00000080UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH8_Msk 0x00000100UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH9_Msk 0x00000200UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH10_Msk 0x00000400UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH11_Msk 0x00000800UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH12_Msk 0x00001000UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH13_Msk 0x00002000UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH14_Msk 0x00004000UL /*!< Clear the priority */ +#define DMA_PRIORITYCLR_CH15_Msk 0x00008000UL /*!< Clear the priority */ + +/*-- ERRCLR: Bus error register ------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :1; /*!< Indicate Error on bus AHB-Lite */ +} _DMA_ERRCLR_bits; + +/* Bit field positions: */ +#define DMA_ERRCLR_VAL_Pos 0 /*!< Indicate Error on bus AHB-Lite */ + +/* Bit field masks: */ +#define DMA_ERRCLR_VAL_Msk 0x00000001UL /*!< Indicate Error on bus AHB-Lite */ + +typedef struct { + union { /*!< Status DMA register */ + __I uint32_t STATUS; /*!< STATUS : type used for word access */ + __I _DMA_STATUS_bits STATUS_bit; /*!< STATUS_bit: structure used for bit access */ + }; + union { /*!< DMA configuration register */ + __O uint32_t CFG; /*!< CFG : type used for word access */ + __O _DMA_CFG_bits CFG_bit; /*!< CFG_bit: structure used for bit access */ + }; + union { /*!< Channel control data base pointer */ + __IO uint32_t BASEPTR; /*!< BASEPTR : type used for word access */ + __IO _DMA_BASEPTR_bits BASEPTR_bit; /*!< BASEPTR_bit: structure used for bit access */ + }; + union { /*!< Channel alternate control data base pointer */ + __I uint32_t ALTBASEPTR; /*!< ALTBASEPTR : type used for word access */ + __I _DMA_ALTBASEPTR_bits ALTBASEPTR_bit; /*!< ALTBASEPTR_bit: structure used for bit access */ + }; + union { /*!< Channel wait on request status */ + __I uint32_t WAITONREQ; /*!< WAITONREQ : type used for word access */ + __I _DMA_WAITONREQ_bits WAITONREQ_bit; /*!< WAITONREQ_bit: structure used for bit access */ + }; + union { /*!< Channel software request */ + __O uint32_t SWREQ; /*!< SWREQ : type used for word access */ + __O _DMA_SWREQ_bits SWREQ_bit; /*!< SWREQ_bit: structure used for bit access */ + }; + union { /*!< Channel useburst set */ + __IO uint32_t USEBURSTSET; /*!< USEBURSTSET : type used for word access */ + __IO _DMA_USEBURSTSET_bits USEBURSTSET_bit; /*!< USEBURSTSET_bit: structure used for bit access */ + }; + union { /*!< Channel useburst clear */ + __O uint32_t USEBURSTCLR; /*!< USEBURSTCLR : type used for word access */ + __O _DMA_USEBURSTCLR_bits USEBURSTCLR_bit; /*!< USEBURSTCLR_bit: structure used for bit access */ + }; + union { /*!< Channel request mask set */ + __IO uint32_t REQMASKSET; /*!< REQMASKSET : type used for word access */ + __IO _DMA_REQMASKSET_bits REQMASKSET_bit; /*!< REQMASKSET_bit: structure used for bit access */ + }; + union { /*!< Channel request mask clear */ + __O uint32_t REQMASKCLR; /*!< REQMASKCLR : type used for word access */ + __O _DMA_REQMASKCLR_bits REQMASKCLR_bit; /*!< REQMASKCLR_bit: structure used for bit access */ + }; + union { /*!< Channel enable set */ + __IO uint32_t ENSET; /*!< ENSET : type used for word access */ + __IO _DMA_ENSET_bits ENSET_bit; /*!< ENSET_bit: structure used for bit access */ + }; + union { /*!< Channel enable clear */ + __O uint32_t ENCLR; /*!< ENCLR : type used for word access */ + __O _DMA_ENCLR_bits ENCLR_bit; /*!< ENCLR_bit: structure used for bit access */ + }; + union { /*!< Channel primary-alternate set */ + __IO uint32_t PRIALTSET; /*!< PRIALTSET : type used for word access */ + __IO _DMA_PRIALTSET_bits PRIALTSET_bit; /*!< PRIALTSET_bit: structure used for bit access */ + }; + union { /*!< Channel primary-alternate clear */ + __O uint32_t PRIALTCLR; /*!< PRIALTCLR : type used for word access */ + __O _DMA_PRIALTCLR_bits PRIALTCLR_bit; /*!< PRIALTCLR_bit: structure used for bit access */ + }; + union { /*!< Channel priority set */ + __IO uint32_t PRIORITYSET; /*!< PRIORITYSET : type used for word access */ + __IO _DMA_PRIORITYSET_bits PRIORITYSET_bit; /*!< PRIORITYSET_bit: structure used for bit access */ + }; + union { /*!< Channel priority clear */ + __O uint32_t PRIORITYCLR; /*!< PRIORITYCLR : type used for word access */ + __O _DMA_PRIORITYCLR_bits PRIORITYCLR_bit; /*!< PRIORITYCLR_bit: structure used for bit access */ + }; + __IO uint32_t Reserved0[3]; + union { /*!< Bus error register */ + __IO uint32_t ERRCLR; /*!< ERRCLR : type used for word access */ + __IO _DMA_ERRCLR_bits ERRCLR_bit; /*!< ERRCLR_bit: structure used for bit access */ + }; +} DMA_TypeDef; + + +/******************************************************************************/ +/* MFLASH registers */ +/******************************************************************************/ + +/*-- ADDR: Address Register ----------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Address value for flash operations */ +} _MFLASH_ADDR_bits; + +/* Bit field positions: */ +#define MFLASH_ADDR_VAL_Pos 0 /*!< Address value for flash operations */ + +/* Bit field masks: */ +#define MFLASH_ADDR_VAL_Msk 0xFFFFFFFFUL /*!< Address value for flash operations */ + +/*-- DATA: DATA: Data Register --------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Data register value for flash operations */ +} _MFLASH_DATA_DATA_bits; + +/* Bit field positions: */ +#define MFLASH_DATA_DATA_VAL_Pos 0 /*!< Data register value for flash operations */ + +/* Bit field masks: */ +#define MFLASH_DATA_DATA_VAL_Msk 0xFFFFFFFFUL /*!< Data register value for flash operations */ + +/*-- CMD: Command Register -----------------------------------------------------------------------------------*/ +typedef struct { + uint32_t RD :1; /*!< Read enable command */ + uint32_t WR :1; /*!< Write enable command */ + uint32_t ERSEC :1; /*!< Erase sector enable command */ + uint32_t ERALL :1; /*!< Erase all enable command */ + uint32_t :4; /*!< RESERVED */ + uint32_t NVRON :1; /*!< NVR access bit */ + uint32_t :7; /*!< RESERVED */ + uint32_t KEY :16; /*!< Magic Key for flash access "C0DE" */ +} _MFLASH_CMD_bits; + +/* Bit field positions: */ +#define MFLASH_CMD_RD_Pos 0 /*!< Read enable command */ +#define MFLASH_CMD_WR_Pos 1 /*!< Write enable command */ +#define MFLASH_CMD_ERSEC_Pos 2 /*!< Erase sector enable command */ +#define MFLASH_CMD_ERALL_Pos 3 /*!< Erase all enable command */ +#define MFLASH_CMD_NVRON_Pos 8 /*!< NVR access bit */ +#define MFLASH_CMD_KEY_Pos 16 /*!< Magic Key for flash access "C0DE" */ + +/* Bit field masks: */ +#define MFLASH_CMD_RD_Msk 0x00000001UL /*!< Read enable command */ +#define MFLASH_CMD_WR_Msk 0x00000002UL /*!< Write enable command */ +#define MFLASH_CMD_ERSEC_Msk 0x00000004UL /*!< Erase sector enable command */ +#define MFLASH_CMD_ERALL_Msk 0x00000008UL /*!< Erase all enable command */ +#define MFLASH_CMD_NVRON_Msk 0x00000100UL /*!< NVR access bit */ +#define MFLASH_CMD_KEY_Msk 0xFFFF0000UL /*!< Magic Key for flash access "C0DE" */ + +/* Bit field enums: */ +typedef enum { + MFLASH_CMD_KEY_Access = 0xC0DEUL, /*!< magic Key for flash access */ +} MFLASH_CMD_KEY_Enum; + +/*-- STAT: Status Register -----------------------------------------------------------------------------------*/ +typedef struct { + uint32_t BUSY :1; /*!< Busy status bit when command is processing */ + uint32_t IRQF :1; /*!< IRQ Flag set when command done. Set by hardware only if IRQEN bit is set. */ +} _MFLASH_STAT_bits; + +/* Bit field positions: */ +#define MFLASH_STAT_BUSY_Pos 0 /*!< Busy status bit when command is processing */ +#define MFLASH_STAT_IRQF_Pos 1 /*!< IRQ Flag set when command done. Set by hardware only if IRQEN bit is set. */ + +/* Bit field masks: */ +#define MFLASH_STAT_BUSY_Msk 0x00000001UL /*!< Busy status bit when command is processing */ +#define MFLASH_STAT_IRQF_Msk 0x00000002UL /*!< IRQ Flag set when command done. Set by hardware only if IRQEN bit is set. */ + +/*-- CTRL: Control Register ----------------------------------------------------------------------------------*/ +typedef struct { + uint32_t PEN :1; /*!< Prefetch enable bit */ + uint32_t ICEN :1; /*!< I-Cache enable bit */ + uint32_t DCEN :1; /*!< D-Cache enable bit */ + uint32_t :1; /*!< RESERVED */ + uint32_t IRQEN :1; /*!< Interrupt enable bit */ + uint32_t :3; /*!< RESERVED */ + uint32_t IFLUSH :1; /*!< Flush I-Cache request bit */ + uint32_t DFLUSH :1; /*!< Flush D-Cache request bit */ + uint32_t :6; /*!< RESERVED */ + uint32_t LAT :4; /*!< Flash latency */ +} _MFLASH_CTRL_bits; + +/* Bit field positions: */ +#define MFLASH_CTRL_PEN_Pos 0 /*!< Prefetch enable bit */ +#define MFLASH_CTRL_ICEN_Pos 1 /*!< I-Cache enable bit */ +#define MFLASH_CTRL_DCEN_Pos 2 /*!< D-Cache enable bit */ +#define MFLASH_CTRL_IRQEN_Pos 4 /*!< Interrupt enable bit */ +#define MFLASH_CTRL_IFLUSH_Pos 8 /*!< Flush I-Cache request bit */ +#define MFLASH_CTRL_DFLUSH_Pos 9 /*!< Flush D-Cache request bit */ +#define MFLASH_CTRL_LAT_Pos 16 /*!< Flash latency */ + +/* Bit field masks: */ +#define MFLASH_CTRL_PEN_Msk 0x00000001UL /*!< Prefetch enable bit */ +#define MFLASH_CTRL_ICEN_Msk 0x00000002UL /*!< I-Cache enable bit */ +#define MFLASH_CTRL_DCEN_Msk 0x00000004UL /*!< D-Cache enable bit */ +#define MFLASH_CTRL_IRQEN_Msk 0x00000010UL /*!< Interrupt enable bit */ +#define MFLASH_CTRL_IFLUSH_Msk 0x00000100UL /*!< Flush I-Cache request bit */ +#define MFLASH_CTRL_DFLUSH_Msk 0x00000200UL /*!< Flush D-Cache request bit */ +#define MFLASH_CTRL_LAT_Msk 0x000F0000UL /*!< Flash latency */ + +/*-- ICSTAT: ICACHE Status Register --------------------------------------------------------------------------*/ +typedef struct { + uint32_t BUSY :1; /*!< Busy flag for I-Cache flush/test system */ +} _MFLASH_ICSTAT_bits; + +/* Bit field positions: */ +#define MFLASH_ICSTAT_BUSY_Pos 0 /*!< Busy flag for I-Cache flush/test system */ + +/* Bit field masks: */ +#define MFLASH_ICSTAT_BUSY_Msk 0x00000001UL /*!< Busy flag for I-Cache flush/test system */ + +/*-- DCSTAT: DCACHE Status Register --------------------------------------------------------------------------*/ +typedef struct { + uint32_t BUSY :1; /*!< Busy flag for D-Cache flush/test system */ +} _MFLASH_DCSTAT_bits; + +/* Bit field positions: */ +#define MFLASH_DCSTAT_BUSY_Pos 0 /*!< Busy flag for D-Cache flush/test system */ + +/* Bit field masks: */ +#define MFLASH_DCSTAT_BUSY_Msk 0x00000001UL /*!< Busy flag for D-Cache flush/test system */ + +/*-- BDIS: Boot Mode Disable register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t BMDIS :1; /*!< Disable boot mode after system reset command */ +} _MFLASH_BDIS_bits; + +/* Bit field positions: */ +#define MFLASH_BDIS_BMDIS_Pos 0 /*!< Disable boot mode after system reset command */ + +/* Bit field masks: */ +#define MFLASH_BDIS_BMDIS_Msk 0x00000001UL /*!< Disable boot mode after system reset command */ + +//Cluster DATA: +typedef struct { + union { + /*!< Data Register */ + __IO uint32_t DATA; /*!< DATA : type used for word access */ + __IO _MFLASH_DATA_DATA_bits DATA_bit; /*!< DATA_bit: structure used for bit access */ + }; +} _MFLASH_DATA_TypeDef; +typedef struct { + union { /*!< Address Register */ + __IO uint32_t ADDR; /*!< ADDR : type used for word access */ + __IO _MFLASH_ADDR_bits ADDR_bit; /*!< ADDR_bit: structure used for bit access */ + }; + _MFLASH_DATA_TypeDef DATA[2]; + __IO uint32_t Reserved0[6]; + union { /*!< Command Register */ + __IO uint32_t CMD; /*!< CMD : type used for word access */ + __IO _MFLASH_CMD_bits CMD_bit; /*!< CMD_bit: structure used for bit access */ + }; + union { /*!< Status Register */ + __IO uint32_t STAT; /*!< STAT : type used for word access */ + __IO _MFLASH_STAT_bits STAT_bit; /*!< STAT_bit: structure used for bit access */ + }; + union { /*!< Control Register */ + __IO uint32_t CTRL; /*!< CTRL : type used for word access */ + __IO _MFLASH_CTRL_bits CTRL_bit; /*!< CTRL_bit: structure used for bit access */ + }; + __IO uint32_t Reserved1; + union { /*!< ICACHE Status Register */ + __I uint32_t ICSTAT; /*!< ICSTAT : type used for word access */ + __I _MFLASH_ICSTAT_bits ICSTAT_bit; /*!< ICSTAT_bit: structure used for bit access */ + }; + union { /*!< DCACHE Status Register */ + __I uint32_t DCSTAT; /*!< DCSTAT : type used for word access */ + __I _MFLASH_DCSTAT_bits DCSTAT_bit; /*!< DCSTAT_bit: structure used for bit access */ + }; + __IO uint32_t Reserved2[15]; + union { /*!< Boot Mode Disable register */ + __IO uint32_t BDIS; /*!< BDIS : type used for word access */ + __IO _MFLASH_BDIS_bits BDIS_bit; /*!< BDIS_bit: structure used for bit access */ + }; +} MFLASH_TypeDef; + + +/******************************************************************************/ +/* QEP registers */ +/******************************************************************************/ + +/*-- QPOSCNT: Position Counter register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QPOSCNT_bits; + +/* Bit field positions: */ +#define QEP_QPOSCNT_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QPOSCNT_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QPOSINIT: Position Counter Initialization register ------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QPOSINIT_bits; + +/* Bit field positions: */ +#define QEP_QPOSINIT_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QPOSINIT_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QPOSMAX: Maximum Position Count register ----------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QPOSMAX_bits; + +/* Bit field positions: */ +#define QEP_QPOSMAX_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QPOSMAX_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QPOSCMP: Position-compare register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QPOSCMP_bits; + +/* Bit field positions: */ +#define QEP_QPOSCMP_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QPOSCMP_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QPOSILAT: Index Position Latch register -----------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QPOSILAT_bits; + +/* Bit field positions: */ +#define QEP_QPOSILAT_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QPOSILAT_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QPOSSLAT: Strobe Position Latch register ----------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QPOSSLAT_bits; + +/* Bit field positions: */ +#define QEP_QPOSSLAT_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QPOSSLAT_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QPOSLAT: Position Counter Latch register ----------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QPOSLAT_bits; + +/* Bit field positions: */ +#define QEP_QPOSLAT_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QPOSLAT_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QUTMR: Unit Timer register ------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QUTMR_bits; + +/* Bit field positions: */ +#define QEP_QUTMR_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QUTMR_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QUPRD: Unit Period register -----------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QUPRD_bits; + +/* Bit field positions: */ +#define QEP_QUPRD_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QUPRD_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QWDTMR: Watchdog Timer register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QWDTMR_bits; + +/* Bit field positions: */ +#define QEP_QWDTMR_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QWDTMR_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QWDPRD: Watchdog Period register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QWDPRD_bits; + +/* Bit field positions: */ +#define QEP_QWDPRD_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QWDPRD_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QDECCTL: Decoder Control register -----------------------------------------------------------------------*/ +typedef struct { + uint32_t :5; /*!< RESERVED */ + uint32_t QSP :1; /*!< QEPS input polarity */ + uint32_t QIP :1; /*!< QEPI input polarity */ + uint32_t QBP :1; /*!< QEPB input polarity */ + uint32_t QAP :1; /*!< QEPA input polarity */ + uint32_t IGATE :1; /*!< Index pulse gating option */ + uint32_t SWAP :1; /*!< Swap quadrature clock inputs */ + uint32_t XCR :1; /*!< External clock rate */ + uint32_t SPSEL :1; /*!< Sync output pin selection */ + uint32_t SOEN :1; /*!< Sync output-enable */ + uint32_t QSRC :2; /*!< Position-counter source selection */ +} _QEP_QDECCTL_bits; + +/* Bit field positions: */ +#define QEP_QDECCTL_QSP_Pos 5 /*!< QEPS input polarity */ +#define QEP_QDECCTL_QIP_Pos 6 /*!< QEPI input polarity */ +#define QEP_QDECCTL_QBP_Pos 7 /*!< QEPB input polarity */ +#define QEP_QDECCTL_QAP_Pos 8 /*!< QEPA input polarity */ +#define QEP_QDECCTL_IGATE_Pos 9 /*!< Index pulse gating option */ +#define QEP_QDECCTL_SWAP_Pos 10 /*!< Swap quadrature clock inputs */ +#define QEP_QDECCTL_XCR_Pos 11 /*!< External clock rate */ +#define QEP_QDECCTL_SPSEL_Pos 12 /*!< Sync output pin selection */ +#define QEP_QDECCTL_SOEN_Pos 13 /*!< Sync output-enable */ +#define QEP_QDECCTL_QSRC_Pos 14 /*!< Position-counter source selection */ + +/* Bit field masks: */ +#define QEP_QDECCTL_QSP_Msk 0x00000020UL /*!< QEPS input polarity */ +#define QEP_QDECCTL_QIP_Msk 0x00000040UL /*!< QEPI input polarity */ +#define QEP_QDECCTL_QBP_Msk 0x00000080UL /*!< QEPB input polarity */ +#define QEP_QDECCTL_QAP_Msk 0x00000100UL /*!< QEPA input polarity */ +#define QEP_QDECCTL_IGATE_Msk 0x00000200UL /*!< Index pulse gating option */ +#define QEP_QDECCTL_SWAP_Msk 0x00000400UL /*!< Swap quadrature clock inputs */ +#define QEP_QDECCTL_XCR_Msk 0x00000800UL /*!< External clock rate */ +#define QEP_QDECCTL_SPSEL_Msk 0x00001000UL /*!< Sync output pin selection */ +#define QEP_QDECCTL_SOEN_Msk 0x00002000UL /*!< Sync output-enable */ +#define QEP_QDECCTL_QSRC_Msk 0x0000C000UL /*!< Position-counter source selection */ + +/* Bit field enums: */ +typedef enum { + QEP_QDECCTL_QSRC_Quad = 0x0UL, /*!< quadrature mode */ + QEP_QDECCTL_QSRC_CountDir = 0x1UL, /*!< count/direction mode */ + QEP_QDECCTL_QSRC_Up = 0x2UL, /*!< count up */ + QEP_QDECCTL_QSRC_Down = 0x3UL, /*!< count down */ +} QEP_QDECCTL_QSRC_Enum; + +/*-- QEPCTL: Control register --------------------------------------------------------------------------------*/ +typedef struct { + uint32_t WDE :1; /*!< QEP watchdog enable */ + uint32_t UTE :1; /*!< QEP unit timer enable */ + uint32_t QCLM :1; /*!< QEP capture latch mode */ + uint32_t QPEN :1; /*!< Quadrature position counter enable/software reset */ + uint32_t IEL :2; /*!< Index event latch of position counter (software index marker) */ + uint32_t SEL :1; /*!< Strobe event latch of position counter */ + uint32_t SWI :1; /*!< Software initialization of position counter */ + uint32_t IEI :2; /*!< Index event initialization of position counter */ + uint32_t SEI :2; /*!< Strobe event initialization of position counter */ + uint32_t PCRM :2; /*!< Position counter reset mode */ + uint32_t FREESOFT :2; /*!< Emulation Control Bits */ +} _QEP_QEPCTL_bits; + +/* Bit field positions: */ +#define QEP_QEPCTL_WDE_Pos 0 /*!< QEP watchdog enable */ +#define QEP_QEPCTL_UTE_Pos 1 /*!< QEP unit timer enable */ +#define QEP_QEPCTL_QCLM_Pos 2 /*!< QEP capture latch mode */ +#define QEP_QEPCTL_QPEN_Pos 3 /*!< Quadrature position counter enable/software reset */ +#define QEP_QEPCTL_IEL_Pos 4 /*!< Index event latch of position counter (software index marker) */ +#define QEP_QEPCTL_SEL_Pos 6 /*!< Strobe event latch of position counter */ +#define QEP_QEPCTL_SWI_Pos 7 /*!< Software initialization of position counter */ +#define QEP_QEPCTL_IEI_Pos 8 /*!< Index event initialization of position counter */ +#define QEP_QEPCTL_SEI_Pos 10 /*!< Strobe event initialization of position counter */ +#define QEP_QEPCTL_PCRM_Pos 12 /*!< Position counter reset mode */ +#define QEP_QEPCTL_FREESOFT_Pos 14 /*!< Emulation Control Bits */ + +/* Bit field masks: */ +#define QEP_QEPCTL_WDE_Msk 0x00000001UL /*!< QEP watchdog enable */ +#define QEP_QEPCTL_UTE_Msk 0x00000002UL /*!< QEP unit timer enable */ +#define QEP_QEPCTL_QCLM_Msk 0x00000004UL /*!< QEP capture latch mode */ +#define QEP_QEPCTL_QPEN_Msk 0x00000008UL /*!< Quadrature position counter enable/software reset */ +#define QEP_QEPCTL_IEL_Msk 0x00000030UL /*!< Index event latch of position counter (software index marker) */ +#define QEP_QEPCTL_SEL_Msk 0x00000040UL /*!< Strobe event latch of position counter */ +#define QEP_QEPCTL_SWI_Msk 0x00000080UL /*!< Software initialization of position counter */ +#define QEP_QEPCTL_IEI_Msk 0x00000300UL /*!< Index event initialization of position counter */ +#define QEP_QEPCTL_SEI_Msk 0x00000C00UL /*!< Strobe event initialization of position counter */ +#define QEP_QEPCTL_PCRM_Msk 0x00003000UL /*!< Position counter reset mode */ +#define QEP_QEPCTL_FREESOFT_Msk 0x0000C000UL /*!< Emulation Control Bits */ + +/* Bit field enums: */ +typedef enum { + QEP_QEPCTL_IEL_NoLatch = 0x0UL, /*!< no position counter latch */ + QEP_QEPCTL_IEL_IndPos = 0x1UL, /*!< latch on index signal posedge */ + QEP_QEPCTL_IEL_IndNeg = 0x2UL, /*!< latch on index signal negedge */ + QEP_QEPCTL_IEL_IndMark = 0x3UL, /*!< latch on index marker */ +} QEP_QEPCTL_IEL_Enum; + +typedef enum { + QEP_QEPCTL_IEI_NoInit = 0x0UL, /*!< no initialization */ + QEP_QEPCTL_IEI_QEPIPos = 0x2UL, /*!< init on posedge QEPI */ + QEP_QEPCTL_IEI_QEPINeg = 0x3UL, /*!< init on negedge QEPI */ +} QEP_QEPCTL_IEI_Enum; + +typedef enum { + QEP_QEPCTL_SEI_NoInit = 0x0UL, /*!< no initialization */ + QEP_QEPCTL_SEI_QEPSPos = 0x2UL, /*!< init on posedge QEPI */ + QEP_QEPCTL_SEI_QEPSDir = 0x3UL, /*!< init depends on direction - on posedge if direction is up, on negedge if direction is down */ +} QEP_QEPCTL_SEI_Enum; + +typedef enum { + QEP_QEPCTL_PCRM_Ind = 0x0UL, /*!< reset on index */ + QEP_QEPCTL_PCRM_PosMax = 0x1UL, /*!< reset on max position count */ + QEP_QEPCTL_PCRM_FirstInd = 0x2UL, /*!< reset on the first index */ + QEP_QEPCTL_PCRM_Time = 0x3UL, /*!< reset on time counter */ +} QEP_QEPCTL_PCRM_Enum; + +typedef enum { + QEP_QEPCTL_FREESOFT_Stop = 0x0UL, /*!< counters are blocked */ + QEP_QEPCTL_FREESOFT_StopAtOvf = 0x1UL, /*!< stop after overflow */ + QEP_QEPCTL_FREESOFT_Free = 0x2UL, /*!< no count stop in debug mode */ +} QEP_QEPCTL_FREESOFT_Enum; + +/*-- QCAPCTL: Capture Control register -----------------------------------------------------------------------*/ +typedef struct { + uint32_t UPPS :4; /*!< Unit position event prescaler */ + uint32_t CCPS :3; /*!< QEP capture timer clock prescaler */ + uint32_t SELEVENT :1; /*!< Reset timer control */ + uint32_t :7; /*!< RESERVED */ + uint32_t CEN :1; /*!< Enable eQEP capture */ + uint32_t EPSLD :1; /*!< Enhanced prescalers load */ +} _QEP_QCAPCTL_bits; + +/* Bit field positions: */ +#define QEP_QCAPCTL_UPPS_Pos 0 /*!< Unit position event prescaler */ +#define QEP_QCAPCTL_CCPS_Pos 4 /*!< QEP capture timer clock prescaler */ +#define QEP_QCAPCTL_SELEVENT_Pos 7 /*!< Reset timer control */ +#define QEP_QCAPCTL_CEN_Pos 15 /*!< Enable eQEP capture */ +#define QEP_QCAPCTL_EPSLD_Pos 16 /*!< Enhanced prescalers load */ + +/* Bit field masks: */ +#define QEP_QCAPCTL_UPPS_Msk 0x0000000FUL /*!< Unit position event prescaler */ +#define QEP_QCAPCTL_CCPS_Msk 0x00000070UL /*!< QEP capture timer clock prescaler */ +#define QEP_QCAPCTL_SELEVENT_Msk 0x00000080UL /*!< Reset timer control */ +#define QEP_QCAPCTL_CEN_Msk 0x00008000UL /*!< Enable eQEP capture */ +#define QEP_QCAPCTL_EPSLD_Msk 0x00010000UL /*!< Enhanced prescalers load */ + +/* Bit field enums: */ +typedef enum { + QEP_QCAPCTL_UPPS_Disable = 0x0UL, /*!< quad signal not divided */ + QEP_QCAPCTL_UPPS_Div2 = 0x1UL, /*!< quad signal divided by 2 */ + QEP_QCAPCTL_UPPS_Div4 = 0x2UL, /*!< quad signal divided by 4 */ + QEP_QCAPCTL_UPPS_Div8 = 0x3UL, /*!< quad signal divided by 8 */ + QEP_QCAPCTL_UPPS_Div16 = 0x4UL, /*!< quad signal divided by 16 */ + QEP_QCAPCTL_UPPS_Div32 = 0x5UL, /*!< quad signal divided by 32 */ + QEP_QCAPCTL_UPPS_Div64 = 0x6UL, /*!< quad signal divided by 64 */ + QEP_QCAPCTL_UPPS_Div128 = 0x7UL, /*!< quad signal divided by 128 */ + QEP_QCAPCTL_UPPS_Div256 = 0x8UL, /*!< quad signal divided by 256 */ + QEP_QCAPCTL_UPPS_Div512 = 0x9UL, /*!< quad signal divided by 512 */ + QEP_QCAPCTL_UPPS_Div1024 = 0xAUL, /*!< quad signal divided by 1024 */ + QEP_QCAPCTL_UPPS_Div2048 = 0xBUL, /*!< quad signal divided by 2048 */ +} QEP_QCAPCTL_UPPS_Enum; + +typedef enum { + QEP_QCAPCTL_CCPS_Disable = 0x0UL, /*!< no divider */ + QEP_QCAPCTL_CCPS_Div2 = 0x1UL, /*!< sysclk divided by 2 */ + QEP_QCAPCTL_CCPS_Div4 = 0x2UL, /*!< sysclk divided by 4 */ + QEP_QCAPCTL_CCPS_Div8 = 0x3UL, /*!< sysclk divided by 8 */ + QEP_QCAPCTL_CCPS_Div16 = 0x4UL, /*!< sysclk divided by 16 */ + QEP_QCAPCTL_CCPS_Div32 = 0x5UL, /*!< sysclk divided by 32 */ + QEP_QCAPCTL_CCPS_Div64 = 0x6UL, /*!< sysclk divided by 64 */ + QEP_QCAPCTL_CCPS_Div128 = 0x7UL, /*!< sysclk divided by 128 */ +} QEP_QCAPCTL_CCPS_Enum; + +/*-- QPOSCTL: Position-compare Control register --------------------------------------------------------------*/ +typedef struct { + uint32_t PCSPW :12; /*!< Select-position-compare sync output pulse width */ + uint32_t PCE :1; /*!< Position-compare enable/disable */ + uint32_t PCPOL :1; /*!< Polarity of sync output */ + uint32_t PCLOAD :1; /*!< Position-compare shadow load mode */ + uint32_t PCSHDW :1; /*!< Position-compare shadow enable */ +} _QEP_QPOSCTL_bits; + +/* Bit field positions: */ +#define QEP_QPOSCTL_PCSPW_Pos 0 /*!< Select-position-compare sync output pulse width */ +#define QEP_QPOSCTL_PCE_Pos 12 /*!< Position-compare enable/disable */ +#define QEP_QPOSCTL_PCPOL_Pos 13 /*!< Polarity of sync output */ +#define QEP_QPOSCTL_PCLOAD_Pos 14 /*!< Position-compare shadow load mode */ +#define QEP_QPOSCTL_PCSHDW_Pos 15 /*!< Position-compare shadow enable */ + +/* Bit field masks: */ +#define QEP_QPOSCTL_PCSPW_Msk 0x00000FFFUL /*!< Select-position-compare sync output pulse width */ +#define QEP_QPOSCTL_PCE_Msk 0x00001000UL /*!< Position-compare enable/disable */ +#define QEP_QPOSCTL_PCPOL_Msk 0x00002000UL /*!< Polarity of sync output */ +#define QEP_QPOSCTL_PCLOAD_Msk 0x00004000UL /*!< Position-compare shadow load mode */ +#define QEP_QPOSCTL_PCSHDW_Msk 0x00008000UL /*!< Position-compare shadow enable */ + +/*-- QEINT: Interrupt Enable register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t :1; /*!< RESERVED */ + uint32_t PCE :1; /*!< Position counter error interrupt enable */ + uint32_t QPE :1; /*!< Quadrature phase error interrupt enable */ + uint32_t QDC :1; /*!< Quadrature direction change interrupt enable */ + uint32_t WTO :1; /*!< Watchdog time out interrupt enable */ + uint32_t PCU :1; /*!< Position counter underflow interrupt enable */ + uint32_t PCO :1; /*!< Position counter overflow interrupt enable */ + uint32_t PCR :1; /*!< Position-compare ready interrupt enable */ + uint32_t PCM :1; /*!< Position-compare match interrupt enable */ + uint32_t SEL :1; /*!< Strobe event latch interrupt enable */ + uint32_t IEL :1; /*!< Index event latch interrupt enable */ + uint32_t UTO :1; /*!< Unit time out interrupt enable */ +} _QEP_QEINT_bits; + +/* Bit field positions: */ +#define QEP_QEINT_PCE_Pos 1 /*!< Position counter error interrupt enable */ +#define QEP_QEINT_QPE_Pos 2 /*!< Quadrature phase error interrupt enable */ +#define QEP_QEINT_QDC_Pos 3 /*!< Quadrature direction change interrupt enable */ +#define QEP_QEINT_WTO_Pos 4 /*!< Watchdog time out interrupt enable */ +#define QEP_QEINT_PCU_Pos 5 /*!< Position counter underflow interrupt enable */ +#define QEP_QEINT_PCO_Pos 6 /*!< Position counter overflow interrupt enable */ +#define QEP_QEINT_PCR_Pos 7 /*!< Position-compare ready interrupt enable */ +#define QEP_QEINT_PCM_Pos 8 /*!< Position-compare match interrupt enable */ +#define QEP_QEINT_SEL_Pos 9 /*!< Strobe event latch interrupt enable */ +#define QEP_QEINT_IEL_Pos 10 /*!< Index event latch interrupt enable */ +#define QEP_QEINT_UTO_Pos 11 /*!< Unit time out interrupt enable */ + +/* Bit field masks: */ +#define QEP_QEINT_PCE_Msk 0x00000002UL /*!< Position counter error interrupt enable */ +#define QEP_QEINT_QPE_Msk 0x00000004UL /*!< Quadrature phase error interrupt enable */ +#define QEP_QEINT_QDC_Msk 0x00000008UL /*!< Quadrature direction change interrupt enable */ +#define QEP_QEINT_WTO_Msk 0x00000010UL /*!< Watchdog time out interrupt enable */ +#define QEP_QEINT_PCU_Msk 0x00000020UL /*!< Position counter underflow interrupt enable */ +#define QEP_QEINT_PCO_Msk 0x00000040UL /*!< Position counter overflow interrupt enable */ +#define QEP_QEINT_PCR_Msk 0x00000080UL /*!< Position-compare ready interrupt enable */ +#define QEP_QEINT_PCM_Msk 0x00000100UL /*!< Position-compare match interrupt enable */ +#define QEP_QEINT_SEL_Msk 0x00000200UL /*!< Strobe event latch interrupt enable */ +#define QEP_QEINT_IEL_Msk 0x00000400UL /*!< Index event latch interrupt enable */ +#define QEP_QEINT_UTO_Msk 0x00000800UL /*!< Unit time out interrupt enable */ + +/*-- QFLG: Interrupt Flag register ---------------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Global interrupt status flag */ + uint32_t PCE :1; /*!< Position counter error interrupt flag */ + uint32_t QPE :1; /*!< Quadrature phase error interrupt flag */ + uint32_t QDC :1; /*!< Quadrature direction change interrupt flag */ + uint32_t WTO :1; /*!< Watchdog timeout interrupt flag */ + uint32_t PCU :1; /*!< Position counter underflow interrupt flag */ + uint32_t PCO :1; /*!< Position counter overflow interrupt flag */ + uint32_t PCR :1; /*!< Position-compare ready interrupt flag */ + uint32_t PCM :1; /*!< QEP compare match event interrupt flag */ + uint32_t SEL :1; /*!< Strobe event latch interrupt flag + */ + uint32_t IEL :1; /*!< Index event latch interrupt flag */ + uint32_t UTO :1; /*!< Unit time out interrupt flag */ +} _QEP_QFLG_bits; + +/* Bit field positions: */ +#define QEP_QFLG_INT_Pos 0 /*!< Global interrupt status flag */ +#define QEP_QFLG_PCE_Pos 1 /*!< Position counter error interrupt flag */ +#define QEP_QFLG_QPE_Pos 2 /*!< Quadrature phase error interrupt flag */ +#define QEP_QFLG_QDC_Pos 3 /*!< Quadrature direction change interrupt flag */ +#define QEP_QFLG_WTO_Pos 4 /*!< Watchdog timeout interrupt flag */ +#define QEP_QFLG_PCU_Pos 5 /*!< Position counter underflow interrupt flag */ +#define QEP_QFLG_PCO_Pos 6 /*!< Position counter overflow interrupt flag */ +#define QEP_QFLG_PCR_Pos 7 /*!< Position-compare ready interrupt flag */ +#define QEP_QFLG_PCM_Pos 8 /*!< QEP compare match event interrupt flag */ +#define QEP_QFLG_SEL_Pos 9 /*!< Strobe event latch interrupt flag + */ +#define QEP_QFLG_IEL_Pos 10 /*!< Index event latch interrupt flag */ +#define QEP_QFLG_UTO_Pos 11 /*!< Unit time out interrupt flag */ + +/* Bit field masks: */ +#define QEP_QFLG_INT_Msk 0x00000001UL /*!< Global interrupt status flag */ +#define QEP_QFLG_PCE_Msk 0x00000002UL /*!< Position counter error interrupt flag */ +#define QEP_QFLG_QPE_Msk 0x00000004UL /*!< Quadrature phase error interrupt flag */ +#define QEP_QFLG_QDC_Msk 0x00000008UL /*!< Quadrature direction change interrupt flag */ +#define QEP_QFLG_WTO_Msk 0x00000010UL /*!< Watchdog timeout interrupt flag */ +#define QEP_QFLG_PCU_Msk 0x00000020UL /*!< Position counter underflow interrupt flag */ +#define QEP_QFLG_PCO_Msk 0x00000040UL /*!< Position counter overflow interrupt flag */ +#define QEP_QFLG_PCR_Msk 0x00000080UL /*!< Position-compare ready interrupt flag */ +#define QEP_QFLG_PCM_Msk 0x00000100UL /*!< QEP compare match event interrupt flag */ +#define QEP_QFLG_SEL_Msk 0x00000200UL /*!< Strobe event latch interrupt flag + */ +#define QEP_QFLG_IEL_Msk 0x00000400UL /*!< Index event latch interrupt flag */ +#define QEP_QFLG_UTO_Msk 0x00000800UL /*!< Unit time out interrupt flag */ + +/*-- QCLR: Interrupt Clear register --------------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Global interrupt clear flag */ + uint32_t PCE :1; /*!< Clear position counter error interrupt flag */ + uint32_t QPE :1; /*!< Clear quadrature phase error interrupt flag */ + uint32_t QDC :1; /*!< Clear quadrature direction change interrupt flag */ + uint32_t WTO :1; /*!< Clear watchdog timeout interrupt flag */ + uint32_t PCU :1; /*!< Clear position counter underflow interrupt flag */ + uint32_t PCO :1; /*!< Clear position counter overflow interrupt flag */ + uint32_t PCR :1; /*!< Clear position-compare ready interrupt flag */ + uint32_t PCM :1; /*!< Clear eQEP compare match event interrupt flag */ + uint32_t SEL :1; /*!< Clear strobe event latch interrupt flag */ + uint32_t IEL :1; /*!< Clear index event latch interrupt flag */ + uint32_t UTO :1; /*!< Clear unit time out interrupt flag */ +} _QEP_QCLR_bits; + +/* Bit field positions: */ +#define QEP_QCLR_INT_Pos 0 /*!< Global interrupt clear flag */ +#define QEP_QCLR_PCE_Pos 1 /*!< Clear position counter error interrupt flag */ +#define QEP_QCLR_QPE_Pos 2 /*!< Clear quadrature phase error interrupt flag */ +#define QEP_QCLR_QDC_Pos 3 /*!< Clear quadrature direction change interrupt flag */ +#define QEP_QCLR_WTO_Pos 4 /*!< Clear watchdog timeout interrupt flag */ +#define QEP_QCLR_PCU_Pos 5 /*!< Clear position counter underflow interrupt flag */ +#define QEP_QCLR_PCO_Pos 6 /*!< Clear position counter overflow interrupt flag */ +#define QEP_QCLR_PCR_Pos 7 /*!< Clear position-compare ready interrupt flag */ +#define QEP_QCLR_PCM_Pos 8 /*!< Clear eQEP compare match event interrupt flag */ +#define QEP_QCLR_SEL_Pos 9 /*!< Clear strobe event latch interrupt flag */ +#define QEP_QCLR_IEL_Pos 10 /*!< Clear index event latch interrupt flag */ +#define QEP_QCLR_UTO_Pos 11 /*!< Clear unit time out interrupt flag */ + +/* Bit field masks: */ +#define QEP_QCLR_INT_Msk 0x00000001UL /*!< Global interrupt clear flag */ +#define QEP_QCLR_PCE_Msk 0x00000002UL /*!< Clear position counter error interrupt flag */ +#define QEP_QCLR_QPE_Msk 0x00000004UL /*!< Clear quadrature phase error interrupt flag */ +#define QEP_QCLR_QDC_Msk 0x00000008UL /*!< Clear quadrature direction change interrupt flag */ +#define QEP_QCLR_WTO_Msk 0x00000010UL /*!< Clear watchdog timeout interrupt flag */ +#define QEP_QCLR_PCU_Msk 0x00000020UL /*!< Clear position counter underflow interrupt flag */ +#define QEP_QCLR_PCO_Msk 0x00000040UL /*!< Clear position counter overflow interrupt flag */ +#define QEP_QCLR_PCR_Msk 0x00000080UL /*!< Clear position-compare ready interrupt flag */ +#define QEP_QCLR_PCM_Msk 0x00000100UL /*!< Clear eQEP compare match event interrupt flag */ +#define QEP_QCLR_SEL_Msk 0x00000200UL /*!< Clear strobe event latch interrupt flag */ +#define QEP_QCLR_IEL_Msk 0x00000400UL /*!< Clear index event latch interrupt flag */ +#define QEP_QCLR_UTO_Msk 0x00000800UL /*!< Clear unit time out interrupt flag */ + +/*-- QFRC: Interrupt Force register --------------------------------------------------------------------------*/ +typedef struct { + uint32_t :1; /*!< RESERVED */ + uint32_t PCE :1; /*!< Force position counter error interrupt */ + uint32_t QPE :1; /*!< Force quadrature phase error interrupt */ + uint32_t QDC :1; /*!< Force quadrature direction change interrupt */ + uint32_t WTO :1; /*!< Force watchdog time out interrupt */ + uint32_t PCU :1; /*!< Force position counter underflow interrupt */ + uint32_t PCO :1; /*!< Force position counter overflow interrupt */ + uint32_t PCR :1; /*!< Force position-compare ready interrupt */ + uint32_t PCM :1; /*!< Force position-compare match interrupt */ + uint32_t SEL :1; /*!< Force strobe event latch interrupt */ + uint32_t IEL :1; /*!< Force index event latch interrupt */ + uint32_t UTO :1; /*!< Force unit time out interrupt */ +} _QEP_QFRC_bits; + +/* Bit field positions: */ +#define QEP_QFRC_PCE_Pos 1 /*!< Force position counter error interrupt */ +#define QEP_QFRC_QPE_Pos 2 /*!< Force quadrature phase error interrupt */ +#define QEP_QFRC_QDC_Pos 3 /*!< Force quadrature direction change interrupt */ +#define QEP_QFRC_WTO_Pos 4 /*!< Force watchdog time out interrupt */ +#define QEP_QFRC_PCU_Pos 5 /*!< Force position counter underflow interrupt */ +#define QEP_QFRC_PCO_Pos 6 /*!< Force position counter overflow interrupt */ +#define QEP_QFRC_PCR_Pos 7 /*!< Force position-compare ready interrupt */ +#define QEP_QFRC_PCM_Pos 8 /*!< Force position-compare match interrupt */ +#define QEP_QFRC_SEL_Pos 9 /*!< Force strobe event latch interrupt */ +#define QEP_QFRC_IEL_Pos 10 /*!< Force index event latch interrupt */ +#define QEP_QFRC_UTO_Pos 11 /*!< Force unit time out interrupt */ + +/* Bit field masks: */ +#define QEP_QFRC_PCE_Msk 0x00000002UL /*!< Force position counter error interrupt */ +#define QEP_QFRC_QPE_Msk 0x00000004UL /*!< Force quadrature phase error interrupt */ +#define QEP_QFRC_QDC_Msk 0x00000008UL /*!< Force quadrature direction change interrupt */ +#define QEP_QFRC_WTO_Msk 0x00000010UL /*!< Force watchdog time out interrupt */ +#define QEP_QFRC_PCU_Msk 0x00000020UL /*!< Force position counter underflow interrupt */ +#define QEP_QFRC_PCO_Msk 0x00000040UL /*!< Force position counter overflow interrupt */ +#define QEP_QFRC_PCR_Msk 0x00000080UL /*!< Force position-compare ready interrupt */ +#define QEP_QFRC_PCM_Msk 0x00000100UL /*!< Force position-compare match interrupt */ +#define QEP_QFRC_SEL_Msk 0x00000200UL /*!< Force strobe event latch interrupt */ +#define QEP_QFRC_IEL_Msk 0x00000400UL /*!< Force index event latch interrupt */ +#define QEP_QFRC_UTO_Msk 0x00000800UL /*!< Force unit time out interrupt */ + +/*-- QEPSTS: Status register ---------------------------------------------------------------------------------*/ +typedef struct { + uint32_t PCEF :1; /*!< Position counter error flag */ + uint32_t FIMF :1; /*!< First index marker flag */ + uint32_t CDEF :1; /*!< Capture direction error flag */ + uint32_t COEF :1; /*!< Capture overflow error flag */ + uint32_t QDLF :1; /*!< QEP direction latch flag */ + uint32_t QDF :1; /*!< Quadrature direction flag */ + uint32_t FIDF :1; /*!< Direction on the first index marker */ + uint32_t UPEVNT :1; /*!< Unit position event flag */ + uint32_t DCF :1; /*!< Direction change flag */ +} _QEP_QEPSTS_bits; + +/* Bit field positions: */ +#define QEP_QEPSTS_PCEF_Pos 0 /*!< Position counter error flag */ +#define QEP_QEPSTS_FIMF_Pos 1 /*!< First index marker flag */ +#define QEP_QEPSTS_CDEF_Pos 2 /*!< Capture direction error flag */ +#define QEP_QEPSTS_COEF_Pos 3 /*!< Capture overflow error flag */ +#define QEP_QEPSTS_QDLF_Pos 4 /*!< QEP direction latch flag */ +#define QEP_QEPSTS_QDF_Pos 5 /*!< Quadrature direction flag */ +#define QEP_QEPSTS_FIDF_Pos 6 /*!< Direction on the first index marker */ +#define QEP_QEPSTS_UPEVNT_Pos 7 /*!< Unit position event flag */ +#define QEP_QEPSTS_DCF_Pos 8 /*!< Direction change flag */ + +/* Bit field masks: */ +#define QEP_QEPSTS_PCEF_Msk 0x00000001UL /*!< Position counter error flag */ +#define QEP_QEPSTS_FIMF_Msk 0x00000002UL /*!< First index marker flag */ +#define QEP_QEPSTS_CDEF_Msk 0x00000004UL /*!< Capture direction error flag */ +#define QEP_QEPSTS_COEF_Msk 0x00000008UL /*!< Capture overflow error flag */ +#define QEP_QEPSTS_QDLF_Msk 0x00000010UL /*!< QEP direction latch flag */ +#define QEP_QEPSTS_QDF_Msk 0x00000020UL /*!< Quadrature direction flag */ +#define QEP_QEPSTS_FIDF_Msk 0x00000040UL /*!< Direction on the first index marker */ +#define QEP_QEPSTS_UPEVNT_Msk 0x00000080UL /*!< Unit position event flag */ +#define QEP_QEPSTS_DCF_Msk 0x00000100UL /*!< Direction change flag */ + +/*-- QCTMR: Capture Timer register ---------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QCTMR_bits; + +/* Bit field positions: */ +#define QEP_QCTMR_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QCTMR_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QCPRD: Capture Period register --------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QCPRD_bits; + +/* Bit field positions: */ +#define QEP_QCPRD_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QCPRD_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QCTMRLAT: Capture Timer Latch register ------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QCTMRLAT_bits; + +/* Bit field positions: */ +#define QEP_QCTMRLAT_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QCTMRLAT_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- QCPRDLAT: Capture Period Latch register -----------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _QEP_QCPRDLAT_bits; + +/* Bit field positions: */ +#define QEP_QCPRDLAT_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define QEP_QCPRDLAT_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- DMAREQ: DMA request register ----------------------------------------------------------------------------*/ +typedef struct { + uint32_t DMAEN :1; /*!< DMA request enable */ +} _QEP_DMAREQ_bits; + +/* Bit field positions: */ +#define QEP_DMAREQ_DMAEN_Pos 0 /*!< DMA request enable */ + +/* Bit field masks: */ +#define QEP_DMAREQ_DMAEN_Msk 0x00000001UL /*!< DMA request enable */ + +/*-- INTCLR: Clear active interrupt register -----------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Active interrupt by read, write 1 to clear interrupt */ +} _QEP_INTCLR_bits; + +/* Bit field positions: */ +#define QEP_INTCLR_INT_Pos 0 /*!< Active interrupt by read, write 1 to clear interrupt */ + +/* Bit field masks: */ +#define QEP_INTCLR_INT_Msk 0x00000001UL /*!< Active interrupt by read, write 1 to clear interrupt */ + +typedef struct { + union { /*!< Position Counter register */ + __IO uint32_t QPOSCNT; /*!< QPOSCNT : type used for word access */ + __IO _QEP_QPOSCNT_bits QPOSCNT_bit; /*!< QPOSCNT_bit: structure used for bit access */ + }; + union { /*!< Position Counter Initialization register */ + __IO uint32_t QPOSINIT; /*!< QPOSINIT : type used for word access */ + __IO _QEP_QPOSINIT_bits QPOSINIT_bit; /*!< QPOSINIT_bit: structure used for bit access */ + }; + union { /*!< Maximum Position Count register */ + __IO uint32_t QPOSMAX; /*!< QPOSMAX : type used for word access */ + __IO _QEP_QPOSMAX_bits QPOSMAX_bit; /*!< QPOSMAX_bit: structure used for bit access */ + }; + union { /*!< Position-compare register */ + __IO uint32_t QPOSCMP; /*!< QPOSCMP : type used for word access */ + __IO _QEP_QPOSCMP_bits QPOSCMP_bit; /*!< QPOSCMP_bit: structure used for bit access */ + }; + union { /*!< Index Position Latch register */ + __I uint32_t QPOSILAT; /*!< QPOSILAT : type used for word access */ + __I _QEP_QPOSILAT_bits QPOSILAT_bit; /*!< QPOSILAT_bit: structure used for bit access */ + }; + union { /*!< Strobe Position Latch register */ + __I uint32_t QPOSSLAT; /*!< QPOSSLAT : type used for word access */ + __I _QEP_QPOSSLAT_bits QPOSSLAT_bit; /*!< QPOSSLAT_bit: structure used for bit access */ + }; + union { /*!< Position Counter Latch register */ + __I uint32_t QPOSLAT; /*!< QPOSLAT : type used for word access */ + __I _QEP_QPOSLAT_bits QPOSLAT_bit; /*!< QPOSLAT_bit: structure used for bit access */ + }; + union { /*!< Unit Timer register */ + __IO uint32_t QUTMR; /*!< QUTMR : type used for word access */ + __IO _QEP_QUTMR_bits QUTMR_bit; /*!< QUTMR_bit: structure used for bit access */ + }; + union { /*!< Unit Period register */ + __IO uint32_t QUPRD; /*!< QUPRD : type used for word access */ + __IO _QEP_QUPRD_bits QUPRD_bit; /*!< QUPRD_bit: structure used for bit access */ + }; + union { /*!< Watchdog Timer register */ + __IO uint32_t QWDTMR; /*!< QWDTMR : type used for word access */ + __IO _QEP_QWDTMR_bits QWDTMR_bit; /*!< QWDTMR_bit: structure used for bit access */ + }; + union { /*!< Watchdog Period register */ + __IO uint32_t QWDPRD; /*!< QWDPRD : type used for word access */ + __IO _QEP_QWDPRD_bits QWDPRD_bit; /*!< QWDPRD_bit: structure used for bit access */ + }; + union { /*!< Decoder Control register */ + __IO uint32_t QDECCTL; /*!< QDECCTL : type used for word access */ + __IO _QEP_QDECCTL_bits QDECCTL_bit; /*!< QDECCTL_bit: structure used for bit access */ + }; + union { /*!< Control register */ + __IO uint32_t QEPCTL; /*!< QEPCTL : type used for word access */ + __IO _QEP_QEPCTL_bits QEPCTL_bit; /*!< QEPCTL_bit: structure used for bit access */ + }; + union { /*!< Capture Control register */ + __IO uint32_t QCAPCTL; /*!< QCAPCTL : type used for word access */ + __IO _QEP_QCAPCTL_bits QCAPCTL_bit; /*!< QCAPCTL_bit: structure used for bit access */ + }; + union { /*!< Position-compare Control register */ + __IO uint32_t QPOSCTL; /*!< QPOSCTL : type used for word access */ + __IO _QEP_QPOSCTL_bits QPOSCTL_bit; /*!< QPOSCTL_bit: structure used for bit access */ + }; + union { /*!< Interrupt Enable register */ + __IO uint32_t QEINT; /*!< QEINT : type used for word access */ + __IO _QEP_QEINT_bits QEINT_bit; /*!< QEINT_bit: structure used for bit access */ + }; + union { /*!< Interrupt Flag register */ + __I uint32_t QFLG; /*!< QFLG : type used for word access */ + __I _QEP_QFLG_bits QFLG_bit; /*!< QFLG_bit: structure used for bit access */ + }; + union { /*!< Interrupt Clear register */ + __IO uint32_t QCLR; /*!< QCLR : type used for word access */ + __IO _QEP_QCLR_bits QCLR_bit; /*!< QCLR_bit: structure used for bit access */ + }; + union { /*!< Interrupt Force register */ + __IO uint32_t QFRC; /*!< QFRC : type used for word access */ + __IO _QEP_QFRC_bits QFRC_bit; /*!< QFRC_bit: structure used for bit access */ + }; + union { /*!< Status register */ + __IO uint32_t QEPSTS; /*!< QEPSTS : type used for word access */ + __IO _QEP_QEPSTS_bits QEPSTS_bit; /*!< QEPSTS_bit: structure used for bit access */ + }; + union { /*!< Capture Timer register */ + __IO uint32_t QCTMR; /*!< QCTMR : type used for word access */ + __IO _QEP_QCTMR_bits QCTMR_bit; /*!< QCTMR_bit: structure used for bit access */ + }; + union { /*!< Capture Period register */ + __IO uint32_t QCPRD; /*!< QCPRD : type used for word access */ + __IO _QEP_QCPRD_bits QCPRD_bit; /*!< QCPRD_bit: structure used for bit access */ + }; + union { /*!< Capture Timer Latch register */ + __I uint32_t QCTMRLAT; /*!< QCTMRLAT : type used for word access */ + __I _QEP_QCTMRLAT_bits QCTMRLAT_bit; /*!< QCTMRLAT_bit: structure used for bit access */ + }; + union { /*!< Capture Period Latch register */ + __I uint32_t QCPRDLAT; /*!< QCPRDLAT : type used for word access */ + __I _QEP_QCPRDLAT_bits QCPRDLAT_bit; /*!< QCPRDLAT_bit: structure used for bit access */ + }; + union { /*!< DMA request register */ + __IO uint32_t DMAREQ; /*!< DMAREQ : type used for word access */ + __IO _QEP_DMAREQ_bits DMAREQ_bit; /*!< DMAREQ_bit: structure used for bit access */ + }; + __IO uint32_t Reserved0[3]; + union { /*!< Clear active interrupt register */ + __IO uint32_t INTCLR; /*!< INTCLR : type used for word access */ + __IO _QEP_INTCLR_bits INTCLR_bit; /*!< INTCLR_bit: structure used for bit access */ + }; +} QEP_TypeDef; + + +/******************************************************************************/ +/* ECAP registers */ +/******************************************************************************/ + +/*-- TSCTR: Counter register ---------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Counter value */ +} _ECAP_TSCTR_bits; + +/* Bit field positions: */ +#define ECAP_TSCTR_VAL_Pos 0 /*!< Counter value */ + +/* Bit field masks: */ +#define ECAP_TSCTR_VAL_Msk 0xFFFFFFFFUL /*!< Counter value */ + +/*-- CTRPHS: Counter Phase Sync register ---------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< */ +} _ECAP_CTRPHS_bits; + +/* Bit field positions: */ +#define ECAP_CTRPHS_VAL_Pos 0 /*!< */ + +/* Bit field masks: */ +#define ECAP_CTRPHS_VAL_Msk 0xFFFFFFFFUL /*!< */ + +/*-- CAP0: Capture register 0 --------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Capture 0 value in CAP mode */ +} _ECAP_CAP0_bits; + +/* Bit field positions: */ +#define ECAP_CAP0_VAL_Pos 0 /*!< Capture 0 value in CAP mode */ + +/* Bit field masks: */ +#define ECAP_CAP0_VAL_Msk 0xFFFFFFFFUL /*!< Capture 0 value in CAP mode */ + +/*-- PRD: Period register ------------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Period value in APWM mode */ +} _ECAP_PRD_bits; + +/* Bit field positions: */ +#define ECAP_PRD_VAL_Pos 0 /*!< Period value in APWM mode */ + +/* Bit field masks: */ +#define ECAP_PRD_VAL_Msk 0xFFFFFFFFUL /*!< Period value in APWM mode */ + +/*-- CAP1: Capture register 1 --------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Capture 1 value in CAP mode */ +} _ECAP_CAP1_bits; + +/* Bit field positions: */ +#define ECAP_CAP1_VAL_Pos 0 /*!< Capture 1 value in CAP mode */ + +/* Bit field masks: */ +#define ECAP_CAP1_VAL_Msk 0xFFFFFFFFUL /*!< Capture 1 value in CAP mode */ + +/*-- CMP: Compare register -----------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Compare value in APWM mode */ +} _ECAP_CMP_bits; + +/* Bit field positions: */ +#define ECAP_CMP_VAL_Pos 0 /*!< Compare value in APWM mode */ + +/* Bit field masks: */ +#define ECAP_CMP_VAL_Msk 0xFFFFFFFFUL /*!< Compare value in APWM mode */ + +/*-- CAP2: Capture register 2 --------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Capture 2 value in CAP mode */ +} _ECAP_CAP2_bits; + +/* Bit field positions: */ +#define ECAP_CAP2_VAL_Pos 0 /*!< Capture 2 value in CAP mode */ + +/* Bit field masks: */ +#define ECAP_CAP2_VAL_Msk 0xFFFFFFFFUL /*!< Capture 2 value in CAP mode */ + +/*-- PRDSHDW: Period shadow register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Period shadow value in APWM mode */ +} _ECAP_PRDSHDW_bits; + +/* Bit field positions: */ +#define ECAP_PRDSHDW_VAL_Pos 0 /*!< Period shadow value in APWM mode */ + +/* Bit field masks: */ +#define ECAP_PRDSHDW_VAL_Msk 0xFFFFFFFFUL /*!< Period shadow value in APWM mode */ + +/*-- CAP3: Capture register 3 --------------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Capture 3 value in CAP mode */ +} _ECAP_CAP3_bits; + +/* Bit field positions: */ +#define ECAP_CAP3_VAL_Pos 0 /*!< Capture 3 value in CAP mode */ + +/* Bit field masks: */ +#define ECAP_CAP3_VAL_Msk 0xFFFFFFFFUL /*!< Capture 3 value in CAP mode */ + +/*-- CMPSHDW: Compare shadow register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :32; /*!< Compare shadow value in APWM mode */ +} _ECAP_CMPSHDW_bits; + +/* Bit field positions: */ +#define ECAP_CMPSHDW_VAL_Pos 0 /*!< Compare shadow value in APWM mode */ + +/* Bit field masks: */ +#define ECAP_CMPSHDW_VAL_Msk 0xFFFFFFFFUL /*!< Compare shadow value in APWM mode */ + +/*-- ECCTL0: Capture control register 0 ---------------------------------------------------------------------*/ +typedef struct { + uint32_t CAP0POL :1; /*!< Polarity select for capture 0 */ + uint32_t CTRRST0 :1; /*!< Reset counter after event 0 */ + uint32_t CAP1POL :1; /*!< Polarity select for capture 1 */ + uint32_t CTRRST1 :1; /*!< Reset counter after event 1 */ + uint32_t CAP2POL :1; /*!< Polarity select for capture 2 */ + uint32_t CTRRST2 :1; /*!< Reset counter after event 2 */ + uint32_t CAP3POL :1; /*!< Polarity select for capture 3 */ + uint32_t CTRRST3 :1; /*!< Reset counter after event 3 */ + uint32_t CAPLDEN :1; /*!< enable capture */ + uint32_t PRESCALE :5; /*!< Prescaler value */ + uint32_t FREESOFT :2; /*!< Emulation mode control */ +} _ECAP_ECCTL0_bits; + +/* Bit field positions: */ +#define ECAP_ECCTL0_CAP0POL_Pos 0 /*!< Polarity select for capture 0 */ +#define ECAP_ECCTL0_CTRRST0_Pos 1 /*!< Reset counter after event 0 */ +#define ECAP_ECCTL0_CAP1POL_Pos 2 /*!< Polarity select for capture 1 */ +#define ECAP_ECCTL0_CTRRST1_Pos 3 /*!< Reset counter after event 1 */ +#define ECAP_ECCTL0_CAP2POL_Pos 4 /*!< Polarity select for capture 2 */ +#define ECAP_ECCTL0_CTRRST2_Pos 5 /*!< Reset counter after event 2 */ +#define ECAP_ECCTL0_CAP3POL_Pos 6 /*!< Polarity select for capture 3 */ +#define ECAP_ECCTL0_CTRRST3_Pos 7 /*!< Reset counter after event 3 */ +#define ECAP_ECCTL0_CAPLDEN_Pos 8 /*!< enable capture */ +#define ECAP_ECCTL0_PRESCALE_Pos 9 /*!< Prescaler value */ +#define ECAP_ECCTL0_FREESOFT_Pos 14 /*!< Emulation mode control */ + +/* Bit field masks: */ +#define ECAP_ECCTL0_CAP0POL_Msk 0x00000001UL /*!< Polarity select for capture 0 */ +#define ECAP_ECCTL0_CTRRST0_Msk 0x00000002UL /*!< Reset counter after event 0 */ +#define ECAP_ECCTL0_CAP1POL_Msk 0x00000004UL /*!< Polarity select for capture 1 */ +#define ECAP_ECCTL0_CTRRST1_Msk 0x00000008UL /*!< Reset counter after event 1 */ +#define ECAP_ECCTL0_CAP2POL_Msk 0x00000010UL /*!< Polarity select for capture 2 */ +#define ECAP_ECCTL0_CTRRST2_Msk 0x00000020UL /*!< Reset counter after event 2 */ +#define ECAP_ECCTL0_CAP3POL_Msk 0x00000040UL /*!< Polarity select for capture 3 */ +#define ECAP_ECCTL0_CTRRST3_Msk 0x00000080UL /*!< Reset counter after event 3 */ +#define ECAP_ECCTL0_CAPLDEN_Msk 0x00000100UL /*!< enable capture */ +#define ECAP_ECCTL0_PRESCALE_Msk 0x00003E00UL /*!< Prescaler value */ +#define ECAP_ECCTL0_FREESOFT_Msk 0x0000C000UL /*!< Emulation mode control */ + +/* Bit field enums: */ +typedef enum { + ECAP_ECCTL0_FREESOFT_Stop = 0x0UL, /*!< stop timer immedeatelly */ + ECAP_ECCTL0_FREESOFT_StopAtZero = 0x1UL, /*!< stop timer when reach zero */ + ECAP_ECCTL0_FREESOFT_Free = 0x2UL, /*!< normal work */ +} ECAP_ECCTL0_FREESOFT_Enum; + +/*-- ECCTL1: Capture control register 1 ----------------------------------------------------------------------*/ +typedef struct { + uint32_t CONTOST :1; /*!< Capture mode */ + uint32_t STOPWRAP :2; /*!< Stop compare value */ + uint32_t REARM :1; /*!< Reset and enable controller, capture reg load */ + uint32_t TSCTRSTOP :1; /*!< Enable Timer */ + uint32_t SYNCIEN :1; /*!< Sync in enable */ + uint32_t SYNCOSEL :2; /*!< SYNCO source selection */ + uint32_t SWSYNC :1; /*!< Software timers sync */ + uint32_t CAPAPWM :1; /*!< Capture mode or APWM mode */ + uint32_t APWMPOL :1; /*!< High/low level APWM */ +} _ECAP_ECCTL1_bits; + +/* Bit field positions: */ +#define ECAP_ECCTL1_CONTOST_Pos 0 /*!< Capture mode */ +#define ECAP_ECCTL1_STOPWRAP_Pos 1 /*!< Stop compare value */ +#define ECAP_ECCTL1_REARM_Pos 3 /*!< Reset and enable controller, capture reg load */ +#define ECAP_ECCTL1_TSCTRSTOP_Pos 4 /*!< Enable Timer */ +#define ECAP_ECCTL1_SYNCIEN_Pos 5 /*!< Sync in enable */ +#define ECAP_ECCTL1_SYNCOSEL_Pos 6 /*!< SYNCO source selection */ +#define ECAP_ECCTL1_SWSYNC_Pos 8 /*!< Software timers sync */ +#define ECAP_ECCTL1_CAPAPWM_Pos 9 /*!< Capture mode or APWM mode */ +#define ECAP_ECCTL1_APWMPOL_Pos 10 /*!< High/low level APWM */ + +/* Bit field masks: */ +#define ECAP_ECCTL1_CONTOST_Msk 0x00000001UL /*!< Capture mode */ +#define ECAP_ECCTL1_STOPWRAP_Msk 0x00000006UL /*!< Stop compare value */ +#define ECAP_ECCTL1_REARM_Msk 0x00000008UL /*!< Reset and enable controller, capture reg load */ +#define ECAP_ECCTL1_TSCTRSTOP_Msk 0x00000010UL /*!< Enable Timer */ +#define ECAP_ECCTL1_SYNCIEN_Msk 0x00000020UL /*!< Sync in enable */ +#define ECAP_ECCTL1_SYNCOSEL_Msk 0x000000C0UL /*!< SYNCO source selection */ +#define ECAP_ECCTL1_SWSYNC_Msk 0x00000100UL /*!< Software timers sync */ +#define ECAP_ECCTL1_CAPAPWM_Msk 0x00000200UL /*!< Capture mode or APWM mode */ +#define ECAP_ECCTL1_APWMPOL_Msk 0x00000400UL /*!< High/low level APWM */ + +/* Bit field enums: */ +typedef enum { + ECAP_ECCTL1_SYNCOSEL_Bypass = 0x0UL, /*!< sync in connected with sync out */ + ECAP_ECCTL1_SYNCOSEL_CTREqPrd = 0x1UL, /*!< sync out generated when CTR = PRD */ + ECAP_ECCTL1_SYNCOSEL_Disable = 0x2UL, /*!< sync out generate disabled */ +} ECAP_ECCTL1_SYNCOSEL_Enum; + +/*-- ECEINT: Interrupt mask register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t :1; /*!< RESERVED */ + uint32_t CEVT0 :1; /*!< enable int CEVT0 */ + uint32_t CEVT1 :1; /*!< enable int CEVT1 */ + uint32_t CEVT2 :1; /*!< enable int CEVT2 */ + uint32_t CEVT3 :1; /*!< enable int CEVT3 */ + uint32_t CTROVF :1; /*!< enable int CTR_OVF */ + uint32_t CTRPRD :1; /*!< enable int CTR=PRD */ + uint32_t CTRCMP :1; /*!< enable int CTR=CMP */ +} _ECAP_ECEINT_bits; + +/* Bit field positions: */ +#define ECAP_ECEINT_CEVT0_Pos 1 /*!< enable int CEVT0 */ +#define ECAP_ECEINT_CEVT1_Pos 2 /*!< enable int CEVT1 */ +#define ECAP_ECEINT_CEVT2_Pos 3 /*!< enable int CEVT2 */ +#define ECAP_ECEINT_CEVT3_Pos 4 /*!< enable int CEVT3 */ +#define ECAP_ECEINT_CTROVF_Pos 5 /*!< enable int CTR_OVF */ +#define ECAP_ECEINT_CTRPRD_Pos 6 /*!< enable int CTR=PRD */ +#define ECAP_ECEINT_CTRCMP_Pos 7 /*!< enable int CTR=CMP */ + +/* Bit field masks: */ +#define ECAP_ECEINT_CEVT0_Msk 0x00000002UL /*!< enable int CEVT0 */ +#define ECAP_ECEINT_CEVT1_Msk 0x00000004UL /*!< enable int CEVT1 */ +#define ECAP_ECEINT_CEVT2_Msk 0x00000008UL /*!< enable int CEVT2 */ +#define ECAP_ECEINT_CEVT3_Msk 0x00000010UL /*!< enable int CEVT3 */ +#define ECAP_ECEINT_CTROVF_Msk 0x00000020UL /*!< enable int CTR_OVF */ +#define ECAP_ECEINT_CTRPRD_Msk 0x00000040UL /*!< enable int CTR=PRD */ +#define ECAP_ECEINT_CTRCMP_Msk 0x00000080UL /*!< enable int CTR=CMP */ + +/*-- ECFLG: Interrupt status register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< indicate global interrupt */ + uint32_t CEVT0 :1; /*!< Hap interrupt CEVT0 */ + uint32_t CEVT1 :1; /*!< Hap interrupt CEVT1 */ + uint32_t CEVT2 :1; /*!< Hap interrupt CEVT2 */ + uint32_t CEVT3 :1; /*!< Hap interrupt CEVT3 */ + uint32_t CTROVF :1; /*!< Hap interrupt CTROVF */ + uint32_t CTRPRD :1; /*!< Hap interrupt CTR=PRD */ + uint32_t CTRCMP :1; /*!< Hap interrupt CTR=CMP */ +} _ECAP_ECFLG_bits; + +/* Bit field positions: */ +#define ECAP_ECFLG_INT_Pos 0 /*!< indicate global interrupt */ +#define ECAP_ECFLG_CEVT0_Pos 1 /*!< Hap interrupt CEVT0 */ +#define ECAP_ECFLG_CEVT1_Pos 2 /*!< Hap interrupt CEVT1 */ +#define ECAP_ECFLG_CEVT2_Pos 3 /*!< Hap interrupt CEVT2 */ +#define ECAP_ECFLG_CEVT3_Pos 4 /*!< Hap interrupt CEVT3 */ +#define ECAP_ECFLG_CTROVF_Pos 5 /*!< Hap interrupt CTROVF */ +#define ECAP_ECFLG_CTRPRD_Pos 6 /*!< Hap interrupt CTR=PRD */ +#define ECAP_ECFLG_CTRCMP_Pos 7 /*!< Hap interrupt CTR=CMP */ + +/* Bit field masks: */ +#define ECAP_ECFLG_INT_Msk 0x00000001UL /*!< indicate global interrupt */ +#define ECAP_ECFLG_CEVT0_Msk 0x00000002UL /*!< Hap interrupt CEVT0 */ +#define ECAP_ECFLG_CEVT1_Msk 0x00000004UL /*!< Hap interrupt CEVT1 */ +#define ECAP_ECFLG_CEVT2_Msk 0x00000008UL /*!< Hap interrupt CEVT2 */ +#define ECAP_ECFLG_CEVT3_Msk 0x00000010UL /*!< Hap interrupt CEVT3 */ +#define ECAP_ECFLG_CTROVF_Msk 0x00000020UL /*!< Hap interrupt CTROVF */ +#define ECAP_ECFLG_CTRPRD_Msk 0x00000040UL /*!< Hap interrupt CTR=PRD */ +#define ECAP_ECFLG_CTRCMP_Msk 0x00000080UL /*!< Hap interrupt CTR=CMP */ + +/*-- ECCLR: Clear interrupt register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< reset global interrupt */ + uint32_t CEVT0 :1; /*!< reset intstatus */ + uint32_t CEVT1 :1; /*!< reset intstatus */ + uint32_t CEVT2 :1; /*!< reset intstatus */ + uint32_t CEVT3 :1; /*!< reset intstatus */ + uint32_t CTROVF :1; /*!< reset intstatus */ + uint32_t CTRPRD :1; /*!< reset intstatus */ + uint32_t CTRCMP :1; /*!< reset intstatus */ +} _ECAP_ECCLR_bits; + +/* Bit field positions: */ +#define ECAP_ECCLR_INT_Pos 0 /*!< reset global interrupt */ +#define ECAP_ECCLR_CEVT0_Pos 1 /*!< reset intstatus */ +#define ECAP_ECCLR_CEVT1_Pos 2 /*!< reset intstatus */ +#define ECAP_ECCLR_CEVT2_Pos 3 /*!< reset intstatus */ +#define ECAP_ECCLR_CEVT3_Pos 4 /*!< reset intstatus */ +#define ECAP_ECCLR_CTROVF_Pos 5 /*!< reset intstatus */ +#define ECAP_ECCLR_CTRPRD_Pos 6 /*!< reset intstatus */ +#define ECAP_ECCLR_CTRCMP_Pos 7 /*!< reset intstatus */ + +/* Bit field masks: */ +#define ECAP_ECCLR_INT_Msk 0x00000001UL /*!< reset global interrupt */ +#define ECAP_ECCLR_CEVT0_Msk 0x00000002UL /*!< reset intstatus */ +#define ECAP_ECCLR_CEVT1_Msk 0x00000004UL /*!< reset intstatus */ +#define ECAP_ECCLR_CEVT2_Msk 0x00000008UL /*!< reset intstatus */ +#define ECAP_ECCLR_CEVT3_Msk 0x00000010UL /*!< reset intstatus */ +#define ECAP_ECCLR_CTROVF_Msk 0x00000020UL /*!< reset intstatus */ +#define ECAP_ECCLR_CTRPRD_Msk 0x00000040UL /*!< reset intstatus */ +#define ECAP_ECCLR_CTRCMP_Msk 0x00000080UL /*!< reset intstatus */ + +/*-- ECFRC: Force interrupt register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t :1; /*!< RESERVED */ + uint32_t CEVT0 :1; /*!< gen test interrupt */ + uint32_t CEVT1 :1; /*!< gen test interrupt */ + uint32_t CEVT2 :1; /*!< gen test interrupt */ + uint32_t CEVT3 :1; /*!< gen test interrupt */ + uint32_t CTROVF :1; /*!< gen test interrupt */ + uint32_t CTRPRD :1; /*!< gen test interrupt */ + uint32_t CTRCMP :1; /*!< gen test interrupt */ +} _ECAP_ECFRC_bits; + +/* Bit field positions: */ +#define ECAP_ECFRC_CEVT0_Pos 1 /*!< gen test interrupt */ +#define ECAP_ECFRC_CEVT1_Pos 2 /*!< gen test interrupt */ +#define ECAP_ECFRC_CEVT2_Pos 3 /*!< gen test interrupt */ +#define ECAP_ECFRC_CEVT3_Pos 4 /*!< gen test interrupt */ +#define ECAP_ECFRC_CTROVF_Pos 5 /*!< gen test interrupt */ +#define ECAP_ECFRC_CTRPRD_Pos 6 /*!< gen test interrupt */ +#define ECAP_ECFRC_CTRCMP_Pos 7 /*!< gen test interrupt */ + +/* Bit field masks: */ +#define ECAP_ECFRC_CEVT0_Msk 0x00000002UL /*!< gen test interrupt */ +#define ECAP_ECFRC_CEVT1_Msk 0x00000004UL /*!< gen test interrupt */ +#define ECAP_ECFRC_CEVT2_Msk 0x00000008UL /*!< gen test interrupt */ +#define ECAP_ECFRC_CEVT3_Msk 0x00000010UL /*!< gen test interrupt */ +#define ECAP_ECFRC_CTROVF_Msk 0x00000020UL /*!< gen test interrupt */ +#define ECAP_ECFRC_CTRPRD_Msk 0x00000040UL /*!< gen test interrupt */ +#define ECAP_ECFRC_CTRCMP_Msk 0x00000080UL /*!< gen test interrupt */ + +/*-- PEINT: Active interrupt status register -----------------------------------------------------------------*/ +typedef struct { + uint32_t PEINT :1; /*!< active interrupt flag */ +} _ECAP_PEINT_bits; + +/* Bit field positions: */ +#define ECAP_PEINT_PEINT_Pos 0 /*!< active interrupt flag */ + +/* Bit field masks: */ +#define ECAP_PEINT_PEINT_Msk 0x00000001UL /*!< active interrupt flag */ + +typedef struct { + union { /*!< Counter register */ + __IO uint32_t TSCTR; /*!< TSCTR : type used for word access */ + __IO _ECAP_TSCTR_bits TSCTR_bit; /*!< TSCTR_bit: structure used for bit access */ + }; + union { /*!< Counter Phase Sync register */ + __IO uint32_t CTRPHS; /*!< CTRPHS : type used for word access */ + __IO _ECAP_CTRPHS_bits CTRPHS_bit; /*!< CTRPHS_bit: structure used for bit access */ + }; + union { + union { /*!< Capture register 0 */ + __IO uint32_t CAP0; /*!< CAP0 : type used for word access */ + __IO _ECAP_CAP0_bits CAP0_bit; /*!< CAP0_bit: structure used for bit access */ + }; + struct { + union { /*!< Period register */ + __IO uint32_t PRD; /*!< PRD : type used for word access */ + __IO _ECAP_PRD_bits PRD_bit; /*!< PRD_bit: structure used for bit access */ + }; + }; + }; + union { + union { /*!< Capture register 1 */ + __IO uint32_t CAP1; /*!< CAP1 : type used for word access */ + __IO _ECAP_CAP1_bits CAP1_bit; /*!< CAP1_bit: structure used for bit access */ + }; + struct { + union { /*!< Compare register */ + __IO uint32_t CMP; /*!< CMP : type used for word access */ + __IO _ECAP_CMP_bits CMP_bit; /*!< CMP_bit: structure used for bit access */ + }; + }; + }; + union { + union { /*!< Capture register 2 */ + __IO uint32_t CAP2; /*!< CAP2 : type used for word access */ + __IO _ECAP_CAP2_bits CAP2_bit; /*!< CAP2_bit: structure used for bit access */ + }; + struct { + union { /*!< Period shadow register */ + __IO uint32_t PRDSHDW; /*!< PRDSHDW : type used for word access */ + __IO _ECAP_PRDSHDW_bits PRDSHDW_bit; /*!< PRDSHDW_bit: structure used for bit access */ + }; + }; + }; + union { + union { /*!< Capture register 3 */ + __IO uint32_t CAP3; /*!< CAP3 : type used for word access */ + __IO _ECAP_CAP3_bits CAP3_bit; /*!< CAP3_bit: structure used for bit access */ + }; + struct { + union { /*!< Compare shadow register */ + __IO uint32_t CMPSHDW; /*!< CMPSHDW : type used for word access */ + __IO _ECAP_CMPSHDW_bits CMPSHDW_bit; /*!< CMPSHDW_bit: structure used for bit access */ + }; + }; + }; + __IO uint32_t Reserved0[4]; + union { /*!< Capture control register 0 */ + __IO uint32_t ECCTL0; /*!< ECCTL0 : type used for word access */ + __IO _ECAP_ECCTL0_bits ECCTL0_bit; /*!< ECCTL0_bit: structure used for bit access */ + }; + union { /*!< Capture control register 1 */ + __IO uint32_t ECCTL1; /*!< ECCTL1 : type used for word access */ + __IO _ECAP_ECCTL1_bits ECCTL1_bit; /*!< ECCTL1_bit: structure used for bit access */ + }; + union { /*!< Interrupt mask register */ + __IO uint32_t ECEINT; /*!< ECEINT : type used for word access */ + __IO _ECAP_ECEINT_bits ECEINT_bit; /*!< ECEINT_bit: structure used for bit access */ + }; + union { /*!< Interrupt status register */ + __I uint32_t ECFLG; /*!< ECFLG : type used for word access */ + __I _ECAP_ECFLG_bits ECFLG_bit; /*!< ECFLG_bit: structure used for bit access */ + }; + union { /*!< Clear interrupt register */ + __IO uint32_t ECCLR; /*!< ECCLR : type used for word access */ + __IO _ECAP_ECCLR_bits ECCLR_bit; /*!< ECCLR_bit: structure used for bit access */ + }; + union { /*!< Force interrupt register */ + __IO uint32_t ECFRC; /*!< ECFRC : type used for word access */ + __IO _ECAP_ECFRC_bits ECFRC_bit; /*!< ECFRC_bit: structure used for bit access */ + }; + union { /*!< Active interrupt status register */ + __IO uint32_t PEINT; /*!< PEINT : type used for word access */ + __IO _ECAP_PEINT_bits PEINT_bit; /*!< PEINT_bit: structure used for bit access */ + }; +} ECAP_TypeDef; + + +/******************************************************************************/ +/* PWM registers */ +/******************************************************************************/ + +/*-- TBCTL: Time-Base Control Register -----------------------------------------------------------------------*/ +typedef struct { + uint32_t CTRMODE :2; /*!< Counter mode */ + uint32_t PHSEN :1; /*!< Counter register load from phase register enable */ + uint32_t PRDLD :1; /*!< Active period register load from shadow register select */ + uint32_t SYNCOSEL :2; /*!< Synchronization Output Select. These bits select the source of the PWM_SYNCO signal. */ + uint32_t SWFSYNC :1; /*!< Software forced synchronization pulse */ + uint32_t HSPCLKDIV :3; /*!< High speed time-base clock prescale bits */ + uint32_t CLKDIV :3; /*!< Time-base clock prescale bits */ + uint32_t PHSDIR :1; /*!< Phase direction bit */ + uint32_t FREESOFT :2; /*!< Emulation mode bits - select the behavior of the time-base counter during emulation events */ + uint32_t SHDWGLOB :1; /*!< Global enable for all shadow loads */ +} _PWM_TBCTL_bits; + +/* Bit field positions: */ +#define PWM_TBCTL_CTRMODE_Pos 0 /*!< Counter mode */ +#define PWM_TBCTL_PHSEN_Pos 2 /*!< Counter register load from phase register enable */ +#define PWM_TBCTL_PRDLD_Pos 3 /*!< Active period register load from shadow register select */ +#define PWM_TBCTL_SYNCOSEL_Pos 4 /*!< Synchronization Output Select. These bits select the source of the PWM_SYNCO signal. */ +#define PWM_TBCTL_SWFSYNC_Pos 6 /*!< Software forced synchronization pulse */ +#define PWM_TBCTL_HSPCLKDIV_Pos 7 /*!< High speed time-base clock prescale bits */ +#define PWM_TBCTL_CLKDIV_Pos 10 /*!< Time-base clock prescale bits */ +#define PWM_TBCTL_PHSDIR_Pos 13 /*!< Phase direction bit */ +#define PWM_TBCTL_FREESOFT_Pos 14 /*!< Emulation mode bits - select the behavior of the time-base counter during emulation events */ +#define PWM_TBCTL_SHDWGLOB_Pos 16 /*!< Global enable for all shadow loads */ + +/* Bit field masks: */ +#define PWM_TBCTL_CTRMODE_Msk 0x00000003UL /*!< Counter mode */ +#define PWM_TBCTL_PHSEN_Msk 0x00000004UL /*!< Counter register load from phase register enable */ +#define PWM_TBCTL_PRDLD_Msk 0x00000008UL /*!< Active period register load from shadow register select */ +#define PWM_TBCTL_SYNCOSEL_Msk 0x00000030UL /*!< Synchronization Output Select. These bits select the source of the PWM_SYNCO signal. */ +#define PWM_TBCTL_SWFSYNC_Msk 0x00000040UL /*!< Software forced synchronization pulse */ +#define PWM_TBCTL_HSPCLKDIV_Msk 0x00000380UL /*!< High speed time-base clock prescale bits */ +#define PWM_TBCTL_CLKDIV_Msk 0x00001C00UL /*!< Time-base clock prescale bits */ +#define PWM_TBCTL_PHSDIR_Msk 0x00002000UL /*!< Phase direction bit */ +#define PWM_TBCTL_FREESOFT_Msk 0x0000C000UL /*!< Emulation mode bits - select the behavior of the time-base counter during emulation events */ +#define PWM_TBCTL_SHDWGLOB_Msk 0x00010000UL /*!< Global enable for all shadow loads */ + +/* Bit field enums: */ +typedef enum { + PWM_TBCTL_CTRMODE_Up = 0x0UL, /*!< count direction up */ + PWM_TBCTL_CTRMODE_Down = 0x1UL, /*!< count direction down */ + PWM_TBCTL_CTRMODE_UpDown = 0x2UL, /*!< count direction up-down */ + PWM_TBCTL_CTRMODE_Stop = 0x3UL, /*!< counter stopped */ +} PWM_TBCTL_CTRMODE_Enum; + +typedef enum { + PWM_TBCTL_SYNCOSEL_SYNCI = 0x0UL, /*!< PWM_SYNCI is source for PWM_SYNCO */ + PWM_TBCTL_SYNCOSEL_CTREqZero = 0x1UL, /*!< CTR = 0000h is source for PWM_SYNCO */ + PWM_TBCTL_SYNCOSEL_CTREqCMPB = 0x2UL, /*!< CTR = CMPB is source for PWM_SYNCO */ + PWM_TBCTL_SYNCOSEL_Disable = 0x3UL, /*!< PWM_SYNCO generation disabled */ +} PWM_TBCTL_SYNCOSEL_Enum; + +typedef enum { + PWM_TBCTL_HSPCLKDIV_Div1 = 0x0UL, /*!< clock not divided */ + PWM_TBCTL_HSPCLKDIV_Div2 = 0x1UL, /*!< clock divided by 2 */ + PWM_TBCTL_HSPCLKDIV_Div4 = 0x2UL, /*!< clock divided by 4 */ + PWM_TBCTL_HSPCLKDIV_Div6 = 0x3UL, /*!< clock divided by 6 */ + PWM_TBCTL_HSPCLKDIV_Div8 = 0x4UL, /*!< clock divided by 8 */ + PWM_TBCTL_HSPCLKDIV_Div10 = 0x5UL, /*!< clock divided by 10 */ + PWM_TBCTL_HSPCLKDIV_Div12 = 0x6UL, /*!< clock divided by 12 */ + PWM_TBCTL_HSPCLKDIV_Div14 = 0x7UL, /*!< clock divided by 14 */ +} PWM_TBCTL_HSPCLKDIV_Enum; + +typedef enum { + PWM_TBCTL_CLKDIV_Div1 = 0x0UL, /*!< clock not divided */ + PWM_TBCTL_CLKDIV_Div2 = 0x1UL, /*!< clock divided by 2 */ + PWM_TBCTL_CLKDIV_Div4 = 0x2UL, /*!< clock divided by 4 */ + PWM_TBCTL_CLKDIV_Div8 = 0x3UL, /*!< clock divided by 8 */ + PWM_TBCTL_CLKDIV_Div16 = 0x4UL, /*!< clock divided by 16 */ + PWM_TBCTL_CLKDIV_Div32 = 0x5UL, /*!< clock divided by 32 */ + PWM_TBCTL_CLKDIV_Div64 = 0x6UL, /*!< clock divided by 64 */ + PWM_TBCTL_CLKDIV_Div128 = 0x7UL, /*!< clock divided by 128 */ +} PWM_TBCTL_CLKDIV_Enum; + +typedef enum { + PWM_TBCTL_FREESOFT_StopAtTBCLK = 0x0UL, /*!< stop timer at next TBCLK tact */ + PWM_TBCTL_FREESOFT_StopAtPeriod = 0x1UL, /*!< stop timer when period ends */ + PWM_TBCTL_FREESOFT_FreeRun = 0x2UL, /*!< free run mode */ +} PWM_TBCTL_FREESOFT_Enum; + +/*-- TBSTS: Time-Base Status Register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t CTRDIR :1; /*!< Time-Base counter direction status bit */ + uint32_t SYNCI :1; /*!< Input synchronization latched status bit */ + uint32_t CTRMAX :1; /*!< Time-Base counter max latched status bit */ +} _PWM_TBSTS_bits; + +/* Bit field positions: */ +#define PWM_TBSTS_CTRDIR_Pos 0 /*!< Time-Base counter direction status bit */ +#define PWM_TBSTS_SYNCI_Pos 1 /*!< Input synchronization latched status bit */ +#define PWM_TBSTS_CTRMAX_Pos 2 /*!< Time-Base counter max latched status bit */ + +/* Bit field masks: */ +#define PWM_TBSTS_CTRDIR_Msk 0x00000001UL /*!< Time-Base counter direction status bit */ +#define PWM_TBSTS_SYNCI_Msk 0x00000002UL /*!< Input synchronization latched status bit */ +#define PWM_TBSTS_CTRMAX_Msk 0x00000004UL /*!< Time-Base counter max latched status bit */ + +/*-- TBPHS: Time-Base Phase Register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t :16; /*!< RESERVED */ + uint32_t TBPHS :16; /*!< Time-base counter phase */ +} _PWM_TBPHS_bits; + +/* Bit field positions: */ +#define PWM_TBPHS_TBPHS_Pos 16 /*!< Time-base counter phase */ + +/* Bit field masks: */ +#define PWM_TBPHS_TBPHS_Msk 0xFFFF0000UL /*!< Time-base counter phase */ + +/*-- TBCTR: Time-Base Counter Register -----------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :16; /*!< Current time-base counter value */ +} _PWM_TBCTR_bits; + +/* Bit field positions: */ +#define PWM_TBCTR_VAL_Pos 0 /*!< Current time-base counter value */ + +/* Bit field masks: */ +#define PWM_TBCTR_VAL_Msk 0x0000FFFFUL /*!< Current time-base counter value */ + +/*-- TBPRD: Time-Base Period Register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :16; /*!< Period of the time-base counter */ +} _PWM_TBPRD_bits; + +/* Bit field positions: */ +#define PWM_TBPRD_VAL_Pos 0 /*!< Period of the time-base counter */ + +/* Bit field masks: */ +#define PWM_TBPRD_VAL_Msk 0x0000FFFFUL /*!< Period of the time-base counter */ + +/*-- CMPCTL: Counter-Compare Control Register ----------------------------------------------------------------*/ +typedef struct { + uint32_t LOADAMODE :2; /*!< Active CMPA load from shadow select mode */ + uint32_t LOADBMODE :2; /*!< Active CMPB load from shadow select mode */ + uint32_t SHDWAMODE :1; /*!< CMPA register operating mode */ + uint32_t :1; /*!< RESERVED */ + uint32_t SHDWBMODE :1; /*!< CMPB register operating mode */ + uint32_t :1; /*!< RESERVED */ + uint32_t SHDWAFULL :1; /*!< CMPA shadow register full status flag */ + uint32_t SHDWBFULL :1; /*!< CMPB shadow register full status flag */ +} _PWM_CMPCTL_bits; + +/* Bit field positions: */ +#define PWM_CMPCTL_LOADAMODE_Pos 0 /*!< Active CMPA load from shadow select mode */ +#define PWM_CMPCTL_LOADBMODE_Pos 2 /*!< Active CMPB load from shadow select mode */ +#define PWM_CMPCTL_SHDWAMODE_Pos 4 /*!< CMPA register operating mode */ +#define PWM_CMPCTL_SHDWBMODE_Pos 6 /*!< CMPB register operating mode */ +#define PWM_CMPCTL_SHDWAFULL_Pos 8 /*!< CMPA shadow register full status flag */ +#define PWM_CMPCTL_SHDWBFULL_Pos 9 /*!< CMPB shadow register full status flag */ + +/* Bit field masks: */ +#define PWM_CMPCTL_LOADAMODE_Msk 0x00000003UL /*!< Active CMPA load from shadow select mode */ +#define PWM_CMPCTL_LOADBMODE_Msk 0x0000000CUL /*!< Active CMPB load from shadow select mode */ +#define PWM_CMPCTL_SHDWAMODE_Msk 0x00000010UL /*!< CMPA register operating mode */ +#define PWM_CMPCTL_SHDWBMODE_Msk 0x00000040UL /*!< CMPB register operating mode */ +#define PWM_CMPCTL_SHDWAFULL_Msk 0x00000100UL /*!< CMPA shadow register full status flag */ +#define PWM_CMPCTL_SHDWBFULL_Msk 0x00000200UL /*!< CMPB shadow register full status flag */ + +/* Bit field enums: */ +typedef enum { + PWM_CMPCTL_LOADAMODE_CTREqZero = 0x0UL, /*!< shadow load for CMPx (x=A,B) when CTR = 0 */ + PWM_CMPCTL_LOADAMODE_CTREqPRD = 0x1UL, /*!< shadow load for CMPx (x=A,B) when CTR = PRD */ + PWM_CMPCTL_LOADAMODE_CTREqZeroPRD = 0x2UL, /*!< shadow load for CMPx (x=A,B) when CTR = 0 or CTR = PRD */ + PWM_CMPCTL_LOADAMODE_Disable = 0x3UL, /*!< shadow load for CMPx (x=A,B) disabled */ +} PWM_CMPCTL_LOADAMODE_Enum; + +typedef enum { + PWM_CMPCTL_LOADBMODE_CTREqZero = 0x0UL, /*!< shadow load for CMPx (x=A,B) when CTR = 0 */ + PWM_CMPCTL_LOADBMODE_CTREqPRD = 0x1UL, /*!< shadow load for CMPx (x=A,B) when CTR = PRD */ + PWM_CMPCTL_LOADBMODE_CTREqZeroPRD = 0x2UL, /*!< shadow load for CMPx (x=A,B) when CTR = 0 or CTR = PRD */ + PWM_CMPCTL_LOADBMODE_Disable = 0x3UL, /*!< shadow load for CMPx (x=A,B) disabled */ +} PWM_CMPCTL_LOADBMODE_Enum; + +/*-- CMPA: Counter-Compare A Register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t :8; /*!< RESERVED */ + uint32_t CMPAHR :8; /*!< The value compared to the time-base counter (TBCTR) in High-Resolution mode */ + uint32_t CMPA :16; /*!< The value compared to the time-base counter (TBCTR) */ +} _PWM_CMPA_bits; + +/* Bit field positions: */ +#define PWM_CMPA_CMPAHR_Pos 8 /*!< The value compared to the time-base counter (TBCTR) in High-Resolution mode */ +#define PWM_CMPA_CMPA_Pos 16 /*!< The value compared to the time-base counter (TBCTR) */ + +/* Bit field masks: */ +#define PWM_CMPA_CMPAHR_Msk 0x0000FF00UL /*!< The value compared to the time-base counter (TBCTR) in High-Resolution mode */ +#define PWM_CMPA_CMPA_Msk 0xFFFF0000UL /*!< The value compared to the time-base counter (TBCTR) */ + +/*-- CMPB: Counter-Compare B Register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t :16; /*!< RESERVED */ + uint32_t CMPB :16; /*!< The value compared to the time-base counter (TBCTR) */ +} _PWM_CMPB_bits; + +/* Bit field positions: */ +#define PWM_CMPB_CMPB_Pos 16 /*!< The value compared to the time-base counter (TBCTR) */ + +/* Bit field masks: */ +#define PWM_CMPB_CMPB_Msk 0xFFFF0000UL /*!< The value compared to the time-base counter (TBCTR) */ + +/*-- AQCTLA: Action-Qualifier Output A Control Register ------------------------------------------------------*/ +typedef struct { + uint32_t ZRO :2; /*!< Action when counter equals zero */ + uint32_t PRD :2; /*!< Action when the counter equals the period */ + uint32_t CAU :2; /*!< Action when the counter equals the active CMPA register and the counter is incrementing */ + uint32_t CAD :2; /*!< Action when the counter equals the active CMPA register and the counter is decrementing */ + uint32_t CBU :2; /*!< Action when the counter equals the active CMPB register and the counter is incrementing */ + uint32_t CBD :2; /*!< Action when the time-base counter equals the active CMPB register and the counter is decrementing + */ +} _PWM_AQCTLA_bits; + +/* Bit field positions: */ +#define PWM_AQCTLA_ZRO_Pos 0 /*!< Action when counter equals zero */ +#define PWM_AQCTLA_PRD_Pos 2 /*!< Action when the counter equals the period */ +#define PWM_AQCTLA_CAU_Pos 4 /*!< Action when the counter equals the active CMPA register and the counter is incrementing */ +#define PWM_AQCTLA_CAD_Pos 6 /*!< Action when the counter equals the active CMPA register and the counter is decrementing */ +#define PWM_AQCTLA_CBU_Pos 8 /*!< Action when the counter equals the active CMPB register and the counter is incrementing */ +#define PWM_AQCTLA_CBD_Pos 10 /*!< Action when the time-base counter equals the active CMPB register and the counter is decrementing + */ + +/* Bit field masks: */ +#define PWM_AQCTLA_ZRO_Msk 0x00000003UL /*!< Action when counter equals zero */ +#define PWM_AQCTLA_PRD_Msk 0x0000000CUL /*!< Action when the counter equals the period */ +#define PWM_AQCTLA_CAU_Msk 0x00000030UL /*!< Action when the counter equals the active CMPA register and the counter is incrementing */ +#define PWM_AQCTLA_CAD_Msk 0x000000C0UL /*!< Action when the counter equals the active CMPA register and the counter is decrementing */ +#define PWM_AQCTLA_CBU_Msk 0x00000300UL /*!< Action when the counter equals the active CMPB register and the counter is incrementing */ +#define PWM_AQCTLA_CBD_Msk 0x00000C00UL /*!< Action when the time-base counter equals the active CMPB register and the counter is decrementing + */ + +/* Bit field enums: */ +typedef enum { + PWM_AQCTLA_ZRO_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLA_ZRO_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLA_ZRO_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLA_ZRO_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLA_ZRO_Enum; + +typedef enum { + PWM_AQCTLA_PRD_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLA_PRD_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLA_PRD_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLA_PRD_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLA_PRD_Enum; + +typedef enum { + PWM_AQCTLA_CAU_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLA_CAU_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLA_CAU_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLA_CAU_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLA_CAU_Enum; + +typedef enum { + PWM_AQCTLA_CAD_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLA_CAD_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLA_CAD_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLA_CAD_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLA_CAD_Enum; + +typedef enum { + PWM_AQCTLA_CBU_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLA_CBU_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLA_CBU_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLA_CBU_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLA_CBU_Enum; + +typedef enum { + PWM_AQCTLA_CBD_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLA_CBD_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLA_CBD_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLA_CBD_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLA_CBD_Enum; + +/*-- AQCTLB: Action-Qualifier Output B Control Register ------------------------------------------------------*/ +typedef struct { + uint32_t ZRO :2; /*!< Action when counter equals zero */ + uint32_t PRD :2; /*!< Action when the counter equals the period */ + uint32_t CAU :2; /*!< Action when the counter equals the active CMPA register and the counter is incrementing */ + uint32_t CAD :2; /*!< Action when the counter equals the active CMPA register and the counter is decrementing */ + uint32_t CBU :2; /*!< Action when the counter equals the active CMPB register and the counter is incrementing */ + uint32_t CBD :2; /*!< Action when the time-base counter equals the active CMPB register and the counter is decrementing + */ +} _PWM_AQCTLB_bits; + +/* Bit field positions: */ +#define PWM_AQCTLB_ZRO_Pos 0 /*!< Action when counter equals zero */ +#define PWM_AQCTLB_PRD_Pos 2 /*!< Action when the counter equals the period */ +#define PWM_AQCTLB_CAU_Pos 4 /*!< Action when the counter equals the active CMPA register and the counter is incrementing */ +#define PWM_AQCTLB_CAD_Pos 6 /*!< Action when the counter equals the active CMPA register and the counter is decrementing */ +#define PWM_AQCTLB_CBU_Pos 8 /*!< Action when the counter equals the active CMPB register and the counter is incrementing */ +#define PWM_AQCTLB_CBD_Pos 10 /*!< Action when the time-base counter equals the active CMPB register and the counter is decrementing + */ + +/* Bit field masks: */ +#define PWM_AQCTLB_ZRO_Msk 0x00000003UL /*!< Action when counter equals zero */ +#define PWM_AQCTLB_PRD_Msk 0x0000000CUL /*!< Action when the counter equals the period */ +#define PWM_AQCTLB_CAU_Msk 0x00000030UL /*!< Action when the counter equals the active CMPA register and the counter is incrementing */ +#define PWM_AQCTLB_CAD_Msk 0x000000C0UL /*!< Action when the counter equals the active CMPA register and the counter is decrementing */ +#define PWM_AQCTLB_CBU_Msk 0x00000300UL /*!< Action when the counter equals the active CMPB register and the counter is incrementing */ +#define PWM_AQCTLB_CBD_Msk 0x00000C00UL /*!< Action when the time-base counter equals the active CMPB register and the counter is decrementing + */ + +/* Bit field enums: */ +typedef enum { + PWM_AQCTLB_ZRO_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLB_ZRO_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLB_ZRO_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLB_ZRO_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLB_ZRO_Enum; + +typedef enum { + PWM_AQCTLB_PRD_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLB_PRD_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLB_PRD_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLB_PRD_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLB_PRD_Enum; + +typedef enum { + PWM_AQCTLB_CAU_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLB_CAU_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLB_CAU_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLB_CAU_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLB_CAU_Enum; + +typedef enum { + PWM_AQCTLB_CAD_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLB_CAD_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLB_CAD_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLB_CAD_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLB_CAD_Enum; + +typedef enum { + PWM_AQCTLB_CBU_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLB_CBU_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLB_CBU_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLB_CBU_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLB_CBU_Enum; + +typedef enum { + PWM_AQCTLB_CBD_NoAction = 0x0UL, /*!< no action */ + PWM_AQCTLB_CBD_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCTLB_CBD_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQCTLB_CBD_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQCTLB_CBD_Enum; + +/*-- AQSFRC: Action-Qualifier Software Force Register --------------------------------------------------------*/ +typedef struct { + uint32_t ACTSFA :2; /*!< Action when one-time software force A is invoked */ + uint32_t OTSFA :1; /*!< One-time software forced event on output A */ + uint32_t ACTSFB :2; /*!< Action when one-time software force B is invoked */ + uint32_t OTSFB :1; /*!< One-time software forced event on output B */ + uint32_t RLDCSF :2; /*!< AQCSFRC active register reload from shadow options */ +} _PWM_AQSFRC_bits; + +/* Bit field positions: */ +#define PWM_AQSFRC_ACTSFA_Pos 0 /*!< Action when one-time software force A is invoked */ +#define PWM_AQSFRC_OTSFA_Pos 2 /*!< One-time software forced event on output A */ +#define PWM_AQSFRC_ACTSFB_Pos 3 /*!< Action when one-time software force B is invoked */ +#define PWM_AQSFRC_OTSFB_Pos 5 /*!< One-time software forced event on output B */ +#define PWM_AQSFRC_RLDCSF_Pos 6 /*!< AQCSFRC active register reload from shadow options */ + +/* Bit field masks: */ +#define PWM_AQSFRC_ACTSFA_Msk 0x00000003UL /*!< Action when one-time software force A is invoked */ +#define PWM_AQSFRC_OTSFA_Msk 0x00000004UL /*!< One-time software forced event on output A */ +#define PWM_AQSFRC_ACTSFB_Msk 0x00000018UL /*!< Action when one-time software force B is invoked */ +#define PWM_AQSFRC_OTSFB_Msk 0x00000020UL /*!< One-time software forced event on output B */ +#define PWM_AQSFRC_RLDCSF_Msk 0x000000C0UL /*!< AQCSFRC active register reload from shadow options */ + +/* Bit field enums: */ +typedef enum { + PWM_AQSFRC_ACTSFA_NoAction = 0x0UL, /*!< no action */ + PWM_AQSFRC_ACTSFA_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQSFRC_ACTSFA_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQSFRC_ACTSFA_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQSFRC_ACTSFA_Enum; + +typedef enum { + PWM_AQSFRC_ACTSFB_NoAction = 0x0UL, /*!< no action */ + PWM_AQSFRC_ACTSFB_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQSFRC_ACTSFB_Set = 0x2UL, /*!< set PWMA/PWMB */ + PWM_AQSFRC_ACTSFB_Toggle = 0x3UL, /*!< inverse PWMA/PWMB */ +} PWM_AQSFRC_ACTSFB_Enum; + +typedef enum { + PWM_AQSFRC_RLDCSF_CTREqZero = 0x0UL, /*!< load when CTR = 0 */ + PWM_AQSFRC_RLDCSF_CTREqPRD = 0x1UL, /*!< load when CTR = PRD */ + PWM_AQSFRC_RLDCSF_CTREqZeroPRD = 0x2UL, /*!< load when CTR = 0 or CTR = PRD */ + PWM_AQSFRC_RLDCSF_NoShadow = 0x3UL, /*!< load immediatelly */ +} PWM_AQSFRC_RLDCSF_Enum; + +/*-- AQCSFRC: Action-Qualifier Continuous Software Force Register --------------------------------------------*/ +typedef struct { + uint32_t CSFA :2; /*!< Continuous software force on output A */ + uint32_t CSFB :2; /*!< Continuous software force on output B */ +} _PWM_AQCSFRC_bits; + +/* Bit field positions: */ +#define PWM_AQCSFRC_CSFA_Pos 0 /*!< Continuous software force on output A */ +#define PWM_AQCSFRC_CSFB_Pos 2 /*!< Continuous software force on output B */ + +/* Bit field masks: */ +#define PWM_AQCSFRC_CSFA_Msk 0x00000003UL /*!< Continuous software force on output A */ +#define PWM_AQCSFRC_CSFB_Msk 0x0000000CUL /*!< Continuous software force on output B */ + +/* Bit field enums: */ +typedef enum { + PWM_AQCSFRC_CSFA_NoAction = 0x0UL, /*!< no action */ + PWM_AQCSFRC_CSFA_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCSFRC_CSFA_Set = 0x2UL, /*!< set PWMA/PWMB */ +} PWM_AQCSFRC_CSFA_Enum; + +typedef enum { + PWM_AQCSFRC_CSFB_NoAction = 0x0UL, /*!< no action */ + PWM_AQCSFRC_CSFB_Clear = 0x1UL, /*!< clear PWMA/PWMB */ + PWM_AQCSFRC_CSFB_Set = 0x2UL, /*!< set PWMA/PWMB */ +} PWM_AQCSFRC_CSFB_Enum; + +/*-- DBCTL: Dead-Band Generator Control Register -------------------------------------------------------------*/ +typedef struct { + uint32_t OUTMODE :2; /*!< Dead-band output mode control */ + uint32_t POLSEL :2; /*!< Polarity select control */ + uint32_t INMODE :2; /*!< Dead band input mode control */ +} _PWM_DBCTL_bits; + +/* Bit field positions: */ +#define PWM_DBCTL_OUTMODE_Pos 0 /*!< Dead-band output mode control */ +#define PWM_DBCTL_POLSEL_Pos 2 /*!< Polarity select control */ +#define PWM_DBCTL_INMODE_Pos 4 /*!< Dead band input mode control */ + +/* Bit field masks: */ +#define PWM_DBCTL_OUTMODE_Msk 0x00000003UL /*!< Dead-band output mode control */ +#define PWM_DBCTL_POLSEL_Msk 0x0000000CUL /*!< Polarity select control */ +#define PWM_DBCTL_INMODE_Msk 0x00000030UL /*!< Dead band input mode control */ + +/* Bit field enums: */ +typedef enum { + PWM_DBCTL_OUTMODE_NoSpec = 0x0UL, /*!< edge for deadtime is no specified */ + PWM_DBCTL_OUTMODE_BNeg = 0x1UL, /*!< deadtime on PWMB negedge */ + PWM_DBCTL_OUTMODE_APos = 0x2UL, /*!< deadtime on PWMA posedge */ + PWM_DBCTL_OUTMODE_Apos_BNeg = 0x3UL, /*!< deadtime on PWMA posedge and PWMB negedge */ +} PWM_DBCTL_OUTMODE_Enum; + +typedef enum { + PWM_DBCTL_POLSEL_InvDisable = 0x0UL, /*!< inverse disabled */ + PWM_DBCTL_POLSEL_InvA = 0x1UL, /*!< inverse on PWMA */ + PWM_DBCTL_POLSEL_InvB = 0x2UL, /*!< inverse on PWMB */ + PWM_DBCTL_POLSEL_InvAB = 0x3UL, /*!< inverse on PWMA and PWMB */ +} PWM_DBCTL_POLSEL_Enum; + +typedef enum { + PWM_DBCTL_INMODE_APosNeg = 0x0UL, /*!< PWMA is used for posedge and negedge control */ + PWM_DBCTL_INMODE_ANeg_BPos = 0x1UL, /*!< PWMA is used for negedge and PWMB is used for posedge control */ + PWM_DBCTL_INMODE_APos_BNeg = 0x2UL, /*!< PWMA is used for posedge and PWMB is used for negedge control */ + PWM_DBCTL_INMODE_BPosNeg = 0x3UL, /*!< PWMB is used for posedge and negedge control */ +} PWM_DBCTL_INMODE_Enum; + +/*-- DBRED: Dead-Band Generator Rising Edge Delay Register ---------------------------------------------------*/ +typedef struct { + uint32_t DEL :10; /*!< Rising edge delay count */ +} _PWM_DBRED_bits; + +/* Bit field positions: */ +#define PWM_DBRED_DEL_Pos 0 /*!< Rising edge delay count */ + +/* Bit field masks: */ +#define PWM_DBRED_DEL_Msk 0x000003FFUL /*!< Rising edge delay count */ + +/*-- DBFED: Dead-Band Generator Falling Edge Delay Register --------------------------------------------------*/ +typedef struct { + uint32_t DEL :10; /*!< Falling edge delay count */ +} _PWM_DBFED_bits; + +/* Bit field positions: */ +#define PWM_DBFED_DEL_Pos 0 /*!< Falling edge delay count */ + +/* Bit field masks: */ +#define PWM_DBFED_DEL_Msk 0x000003FFUL /*!< Falling edge delay count */ + +/*-- TZSEL: Trip-Zone Select Register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t CBC :1; /*!< Cycle-by-Cycle trip-zone 0 enable + */ + uint32_t :7; /*!< RESERVED */ + uint32_t OST :1; /*!< One-Shot trip-zone 0 enable */ +} _PWM_TZSEL_bits; + +/* Bit field positions: */ +#define PWM_TZSEL_CBC_Pos 0 /*!< Cycle-by-Cycle trip-zone 0 enable + */ +#define PWM_TZSEL_OST_Pos 8 /*!< One-Shot trip-zone 0 enable */ + +/* Bit field masks: */ +#define PWM_TZSEL_CBC_Msk 0x00000001UL /*!< Cycle-by-Cycle trip-zone 0 enable + */ +#define PWM_TZSEL_OST_Msk 0x00000100UL /*!< One-Shot trip-zone 0 enable */ + +/*-- TZCTL: Trip-Zone Control Register -----------------------------------------------------------------------*/ +typedef struct { + uint32_t TZA :2; /*!< When a trip event occurs the following action is taken on output A */ + uint32_t TZB :2; /*!< When a trip event occurs the following action is taken on output B */ +} _PWM_TZCTL_bits; + +/* Bit field positions: */ +#define PWM_TZCTL_TZA_Pos 0 /*!< When a trip event occurs the following action is taken on output A */ +#define PWM_TZCTL_TZB_Pos 2 /*!< When a trip event occurs the following action is taken on output B */ + +/* Bit field masks: */ +#define PWM_TZCTL_TZA_Msk 0x00000003UL /*!< When a trip event occurs the following action is taken on output A */ +#define PWM_TZCTL_TZB_Msk 0x0000000CUL /*!< When a trip event occurs the following action is taken on output B */ + +/* Bit field enums: */ +typedef enum { + PWM_TZCTL_TZA_Z = 0x0UL, /*!< PWMA/PWMB go to Z on failture */ + PWM_TZCTL_TZA_Set = 0x1UL, /*!< PWMA/PWMB go to 1 on failture */ + PWM_TZCTL_TZA_Clear = 0x2UL, /*!< PWMA/PWMB go to 0 on failture */ + PWM_TZCTL_TZA_NoAction = 0x3UL, /*!< no action on failture */ +} PWM_TZCTL_TZA_Enum; + +typedef enum { + PWM_TZCTL_TZB_Z = 0x0UL, /*!< PWMA/PWMB go to Z on failture */ + PWM_TZCTL_TZB_Set = 0x1UL, /*!< PWMA/PWMB go to 1 on failture */ + PWM_TZCTL_TZB_Clear = 0x2UL, /*!< PWMA/PWMB go to 0 on failture */ + PWM_TZCTL_TZB_NoAction = 0x3UL, /*!< no action on failture */ +} PWM_TZCTL_TZB_Enum; + +/*-- TZEINT: Trip-Zone Enable Interrupt Register -------------------------------------------------------------*/ +typedef struct { + uint32_t :1; /*!< RESERVED */ + uint32_t CBC :1; /*!< Trip-zone Cycle-by-Cycle interrupt enable */ + uint32_t OST :1; /*!< Trip-zone One-Shot interrupt enable */ +} _PWM_TZEINT_bits; + +/* Bit field positions: */ +#define PWM_TZEINT_CBC_Pos 1 /*!< Trip-zone Cycle-by-Cycle interrupt enable */ +#define PWM_TZEINT_OST_Pos 2 /*!< Trip-zone One-Shot interrupt enable */ + +/* Bit field masks: */ +#define PWM_TZEINT_CBC_Msk 0x00000002UL /*!< Trip-zone Cycle-by-Cycle interrupt enable */ +#define PWM_TZEINT_OST_Msk 0x00000004UL /*!< Trip-zone One-Shot interrupt enable */ + +/*-- TZFLG: Trip-Zone Flag Register --------------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Latched trip interrupt status flag */ + uint32_t CBC :1; /*!< Latched status flag for Cycle-By-Cycle trip event */ + uint32_t OST :1; /*!< Latched status flag for a One-Shot trip event */ +} _PWM_TZFLG_bits; + +/* Bit field positions: */ +#define PWM_TZFLG_INT_Pos 0 /*!< Latched trip interrupt status flag */ +#define PWM_TZFLG_CBC_Pos 1 /*!< Latched status flag for Cycle-By-Cycle trip event */ +#define PWM_TZFLG_OST_Pos 2 /*!< Latched status flag for a One-Shot trip event */ + +/* Bit field masks: */ +#define PWM_TZFLG_INT_Msk 0x00000001UL /*!< Latched trip interrupt status flag */ +#define PWM_TZFLG_CBC_Msk 0x00000002UL /*!< Latched status flag for Cycle-By-Cycle trip event */ +#define PWM_TZFLG_OST_Msk 0x00000004UL /*!< Latched status flag for a One-Shot trip event */ + +/*-- TZCLR: Trip-Zone Clear Register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Clear trip-zone interrupt flag */ + uint32_t CBC :1; /*!< Clear flag for Cycle-By-Cycle trip latch + */ + uint32_t OST :1; /*!< Clear flag for One-Shot trip latch */ +} _PWM_TZCLR_bits; + +/* Bit field positions: */ +#define PWM_TZCLR_INT_Pos 0 /*!< Clear trip-zone interrupt flag */ +#define PWM_TZCLR_CBC_Pos 1 /*!< Clear flag for Cycle-By-Cycle trip latch + */ +#define PWM_TZCLR_OST_Pos 2 /*!< Clear flag for One-Shot trip latch */ + +/* Bit field masks: */ +#define PWM_TZCLR_INT_Msk 0x00000001UL /*!< Clear trip-zone interrupt flag */ +#define PWM_TZCLR_CBC_Msk 0x00000002UL /*!< Clear flag for Cycle-By-Cycle trip latch + */ +#define PWM_TZCLR_OST_Msk 0x00000004UL /*!< Clear flag for One-Shot trip latch */ + +/*-- TZFRC: Trip-Zone Force Register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t :1; /*!< RESERVED */ + uint32_t CBC :1; /*!< Force a Cycle-by-Cycle trip event via software */ + uint32_t OST :1; /*!< Force a One-Shot trip event via software */ +} _PWM_TZFRC_bits; + +/* Bit field positions: */ +#define PWM_TZFRC_CBC_Pos 1 /*!< Force a Cycle-by-Cycle trip event via software */ +#define PWM_TZFRC_OST_Pos 2 /*!< Force a One-Shot trip event via software */ + +/* Bit field masks: */ +#define PWM_TZFRC_CBC_Msk 0x00000002UL /*!< Force a Cycle-by-Cycle trip event via software */ +#define PWM_TZFRC_OST_Msk 0x00000004UL /*!< Force a One-Shot trip event via software */ + +/*-- ETSEL: Event-Trigger Selection Register -----------------------------------------------------------------*/ +typedef struct { + uint32_t INTSEL :3; /*!< PWM_INT interrupt selection options */ + uint32_t INTEN :1; /*!< Enable PWM_INT interrupt generation */ + uint32_t :4; /*!< RESERVED */ + uint32_t SOCASEL :3; /*!< PWM_SOCA selection Options */ + uint32_t SOCAEN :1; /*!< Enable the ADC start of conversion A PWM_SOCA pulse */ + uint32_t SOCBSEL :3; /*!< PWM_SOCB selection Options */ + uint32_t SOCBEN :1; /*!< Enable the ADC start of conversion B PWM_SOCB pulse */ + uint32_t DRQASEL :3; /*!< PWM A DMA request event selection */ + uint32_t DRQAEN :1; /*!< Enable the DMA request from PWM A */ + uint32_t DRQBSEL :3; /*!< PWM B DMA request event selection */ + uint32_t DRQBEN :1; /*!< Enable the DMA request from PWM B */ +} _PWM_ETSEL_bits; + +/* Bit field positions: */ +#define PWM_ETSEL_INTSEL_Pos 0 /*!< PWM_INT interrupt selection options */ +#define PWM_ETSEL_INTEN_Pos 3 /*!< Enable PWM_INT interrupt generation */ +#define PWM_ETSEL_SOCASEL_Pos 8 /*!< PWM_SOCA selection Options */ +#define PWM_ETSEL_SOCAEN_Pos 11 /*!< Enable the ADC start of conversion A PWM_SOCA pulse */ +#define PWM_ETSEL_SOCBSEL_Pos 12 /*!< PWM_SOCB selection Options */ +#define PWM_ETSEL_SOCBEN_Pos 15 /*!< Enable the ADC start of conversion B PWM_SOCB pulse */ +#define PWM_ETSEL_DRQASEL_Pos 16 /*!< PWM A DMA request event selection */ +#define PWM_ETSEL_DRQAEN_Pos 19 /*!< Enable the DMA request from PWM A */ +#define PWM_ETSEL_DRQBSEL_Pos 20 /*!< PWM B DMA request event selection */ +#define PWM_ETSEL_DRQBEN_Pos 23 /*!< Enable the DMA request from PWM B */ + +/* Bit field masks: */ +#define PWM_ETSEL_INTSEL_Msk 0x00000007UL /*!< PWM_INT interrupt selection options */ +#define PWM_ETSEL_INTEN_Msk 0x00000008UL /*!< Enable PWM_INT interrupt generation */ +#define PWM_ETSEL_SOCASEL_Msk 0x00000700UL /*!< PWM_SOCA selection Options */ +#define PWM_ETSEL_SOCAEN_Msk 0x00000800UL /*!< Enable the ADC start of conversion A PWM_SOCA pulse */ +#define PWM_ETSEL_SOCBSEL_Msk 0x00007000UL /*!< PWM_SOCB selection Options */ +#define PWM_ETSEL_SOCBEN_Msk 0x00008000UL /*!< Enable the ADC start of conversion B PWM_SOCB pulse */ +#define PWM_ETSEL_DRQASEL_Msk 0x00070000UL /*!< PWM A DMA request event selection */ +#define PWM_ETSEL_DRQAEN_Msk 0x00080000UL /*!< Enable the DMA request from PWM A */ +#define PWM_ETSEL_DRQBSEL_Msk 0x00700000UL /*!< PWM B DMA request event selection */ +#define PWM_ETSEL_DRQBEN_Msk 0x00800000UL /*!< Enable the DMA request from PWM B */ + +/* Bit field enums: */ +typedef enum { + PWM_ETSEL_INTSEL_CTREqZero = 0x1UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = 0 */ + PWM_ETSEL_INTSEL_CTREqPRD = 0x2UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = PRD */ + PWM_ETSEL_INTSEL_CTREqCMPA_OnUp = 0x4UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPA when count up */ + PWM_ETSEL_INTSEL_CTREqCMPA_OnDown = 0x5UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPA when count down */ + PWM_ETSEL_INTSEL_CTREqCMPB_OnUp = 0x6UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPB when count up */ + PWM_ETSEL_INTSEL_CTREqCMPB_OnDown = 0x7UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPB when count down */ +} PWM_ETSEL_INTSEL_Enum; + +typedef enum { + PWM_ETSEL_SOCASEL_CTREqZero = 0x1UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = 0 */ + PWM_ETSEL_SOCASEL_CTREqPRD = 0x2UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = PRD */ + PWM_ETSEL_SOCASEL_CTREqCMPA_OnUp = 0x4UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPA when count up */ + PWM_ETSEL_SOCASEL_CTREqCMPA_OnDown = 0x5UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPA when count down */ + PWM_ETSEL_SOCASEL_CTREqCMPB_OnUp = 0x6UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPB when count up */ + PWM_ETSEL_SOCASEL_CTREqCMPB_OnDown = 0x7UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPB when count down */ +} PWM_ETSEL_SOCASEL_Enum; + +typedef enum { + PWM_ETSEL_SOCBSEL_CTREqZero = 0x1UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = 0 */ + PWM_ETSEL_SOCBSEL_CTREqPRD = 0x2UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = PRD */ + PWM_ETSEL_SOCBSEL_CTREqCMPA_OnUp = 0x4UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPA when count up */ + PWM_ETSEL_SOCBSEL_CTREqCMPA_OnDown = 0x5UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPA when count down */ + PWM_ETSEL_SOCBSEL_CTREqCMPB_OnUp = 0x6UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPB when count up */ + PWM_ETSEL_SOCBSEL_CTREqCMPB_OnDown = 0x7UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPB when count down */ +} PWM_ETSEL_SOCBSEL_Enum; + +typedef enum { + PWM_ETSEL_DRQASEL_CTREqZero = 0x1UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = 0 */ + PWM_ETSEL_DRQASEL_CTREqPRD = 0x2UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = PRD */ + PWM_ETSEL_DRQASEL_CTREqCMPA_OnUp = 0x4UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPA when count up */ + PWM_ETSEL_DRQASEL_CTREqCMPA_OnDown = 0x5UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPA when count down */ + PWM_ETSEL_DRQASEL_CTREqCMPB_OnUp = 0x6UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPB when count up */ + PWM_ETSEL_DRQASEL_CTREqCMPB_OnDown = 0x7UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPB when count down */ +} PWM_ETSEL_DRQASEL_Enum; + +typedef enum { + PWM_ETSEL_DRQBSEL_CTREqZero = 0x1UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = 0 */ + PWM_ETSEL_DRQBSEL_CTREqPRD = 0x2UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = PRD */ + PWM_ETSEL_DRQBSEL_CTREqCMPA_OnUp = 0x4UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPA when count up */ + PWM_ETSEL_DRQBSEL_CTREqCMPA_OnDown = 0x5UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPA when count down */ + PWM_ETSEL_DRQBSEL_CTREqCMPB_OnUp = 0x6UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPB when count up */ + PWM_ETSEL_DRQBSEL_CTREqCMPB_OnDown = 0x7UL, /*!< generate PWM_SOCA/PWM_SOCB/PWN_INT impulse on CTR = CMPB when count down */ +} PWM_ETSEL_DRQBSEL_Enum; + +/*-- ETPS: Event-Trigger Prescale Register -------------------------------------------------------------------*/ +typedef struct { + uint32_t INTPRD :2; /*!< PWM interrupt (PWM_INT) period select */ + uint32_t INTCNT :2; /*!< PWM interrupt event (PWM_INT) counter register */ + uint32_t :4; /*!< RESERVED */ + uint32_t SOCAPRD :2; /*!< PWM ADC Start-of-Conversion A event (PWM_SOCA) period select */ + uint32_t SOCACNT :2; /*!< PWM ADC Start-of-Conversion A event (PWM_SOCA) counter register */ + uint32_t SOCBPRD :2; /*!< PWM ADC Start-of-Conversion B event (PWM_SOCB) period select */ + uint32_t SOCBCNT :2; /*!< PWM ADC Start-of-Conversion B event (PWM_SOCB) counter register */ + uint32_t DRQAPRD :2; /*!< PWM DMA request A period select */ + uint32_t DRQACNT :2; /*!< PWM DMA request event A counter */ + uint32_t DRQBPRD :2; /*!< PWM DMA request B period select */ + uint32_t DRQBCNT :2; /*!< PWM DMA request event B counter */ +} _PWM_ETPS_bits; + +/* Bit field positions: */ +#define PWM_ETPS_INTPRD_Pos 0 /*!< PWM interrupt (PWM_INT) period select */ +#define PWM_ETPS_INTCNT_Pos 2 /*!< PWM interrupt event (PWM_INT) counter register */ +#define PWM_ETPS_SOCAPRD_Pos 8 /*!< PWM ADC Start-of-Conversion A event (PWM_SOCA) period select */ +#define PWM_ETPS_SOCACNT_Pos 10 /*!< PWM ADC Start-of-Conversion A event (PWM_SOCA) counter register */ +#define PWM_ETPS_SOCBPRD_Pos 12 /*!< PWM ADC Start-of-Conversion B event (PWM_SOCB) period select */ +#define PWM_ETPS_SOCBCNT_Pos 14 /*!< PWM ADC Start-of-Conversion B event (PWM_SOCB) counter register */ +#define PWM_ETPS_DRQAPRD_Pos 16 /*!< PWM DMA request A period select */ +#define PWM_ETPS_DRQACNT_Pos 18 /*!< PWM DMA request event A counter */ +#define PWM_ETPS_DRQBPRD_Pos 20 /*!< PWM DMA request B period select */ +#define PWM_ETPS_DRQBCNT_Pos 22 /*!< PWM DMA request event B counter */ + +/* Bit field masks: */ +#define PWM_ETPS_INTPRD_Msk 0x00000003UL /*!< PWM interrupt (PWM_INT) period select */ +#define PWM_ETPS_INTCNT_Msk 0x0000000CUL /*!< PWM interrupt event (PWM_INT) counter register */ +#define PWM_ETPS_SOCAPRD_Msk 0x00000300UL /*!< PWM ADC Start-of-Conversion A event (PWM_SOCA) period select */ +#define PWM_ETPS_SOCACNT_Msk 0x00000C00UL /*!< PWM ADC Start-of-Conversion A event (PWM_SOCA) counter register */ +#define PWM_ETPS_SOCBPRD_Msk 0x00003000UL /*!< PWM ADC Start-of-Conversion B event (PWM_SOCB) period select */ +#define PWM_ETPS_SOCBCNT_Msk 0x0000C000UL /*!< PWM ADC Start-of-Conversion B event (PWM_SOCB) counter register */ +#define PWM_ETPS_DRQAPRD_Msk 0x00030000UL /*!< PWM DMA request A period select */ +#define PWM_ETPS_DRQACNT_Msk 0x000C0000UL /*!< PWM DMA request event A counter */ +#define PWM_ETPS_DRQBPRD_Msk 0x00300000UL /*!< PWM DMA request B period select */ +#define PWM_ETPS_DRQBCNT_Msk 0x00C00000UL /*!< PWM DMA request event B counter */ + +/*-- ETFLG: Event-Trigger Flag Register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Latched PWM Interrupt (PWM_INT) status flag */ + uint32_t :1; /*!< RESERVED */ + uint32_t SOCA :1; /*!< Latched PWM ADC Start-of-Conversion A (PWM_SOCA) status flag */ + uint32_t SOCB :1; /*!< Latched PWM ADC Start-of-Conversion B (PWM_SOCB) status flag */ + uint32_t DRQA :1; /*!< Latched PWM DMA request A status flag */ + uint32_t DRQB :1; /*!< Latched PWM DMA request B status flag */ +} _PWM_ETFLG_bits; + +/* Bit field positions: */ +#define PWM_ETFLG_INT_Pos 0 /*!< Latched PWM Interrupt (PWM_INT) status flag */ +#define PWM_ETFLG_SOCA_Pos 2 /*!< Latched PWM ADC Start-of-Conversion A (PWM_SOCA) status flag */ +#define PWM_ETFLG_SOCB_Pos 3 /*!< Latched PWM ADC Start-of-Conversion B (PWM_SOCB) status flag */ +#define PWM_ETFLG_DRQA_Pos 4 /*!< Latched PWM DMA request A status flag */ +#define PWM_ETFLG_DRQB_Pos 5 /*!< Latched PWM DMA request B status flag */ + +/* Bit field masks: */ +#define PWM_ETFLG_INT_Msk 0x00000001UL /*!< Latched PWM Interrupt (PWM_INT) status flag */ +#define PWM_ETFLG_SOCA_Msk 0x00000004UL /*!< Latched PWM ADC Start-of-Conversion A (PWM_SOCA) status flag */ +#define PWM_ETFLG_SOCB_Msk 0x00000008UL /*!< Latched PWM ADC Start-of-Conversion B (PWM_SOCB) status flag */ +#define PWM_ETFLG_DRQA_Msk 0x00000010UL /*!< Latched PWM DMA request A status flag */ +#define PWM_ETFLG_DRQB_Msk 0x00000020UL /*!< Latched PWM DMA request B status flag */ + +/*-- ETCLR: Event-Trigger Clear Register ---------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Latched PWM Interrupt (PWM_INT) flag clear bit */ + uint32_t :1; /*!< RESERVED */ + uint32_t SOCA :1; /*!< Latched PWM ADC Start-of-Conversion A (PWM_SOCA) flag clear bit */ + uint32_t SOCB :1; /*!< Latched PWM ADC Start-of-Conversion B (PWM_SOCB) flag clear bit */ + uint32_t DRQA :1; /*!< Latched PWM DMA request A flag clear bit */ + uint32_t DRQB :1; /*!< Latched PWM DMA request B flag clear bit */ +} _PWM_ETCLR_bits; + +/* Bit field positions: */ +#define PWM_ETCLR_INT_Pos 0 /*!< Latched PWM Interrupt (PWM_INT) flag clear bit */ +#define PWM_ETCLR_SOCA_Pos 2 /*!< Latched PWM ADC Start-of-Conversion A (PWM_SOCA) flag clear bit */ +#define PWM_ETCLR_SOCB_Pos 3 /*!< Latched PWM ADC Start-of-Conversion B (PWM_SOCB) flag clear bit */ +#define PWM_ETCLR_DRQA_Pos 4 /*!< Latched PWM DMA request A flag clear bit */ +#define PWM_ETCLR_DRQB_Pos 5 /*!< Latched PWM DMA request B flag clear bit */ + +/* Bit field masks: */ +#define PWM_ETCLR_INT_Msk 0x00000001UL /*!< Latched PWM Interrupt (PWM_INT) flag clear bit */ +#define PWM_ETCLR_SOCA_Msk 0x00000004UL /*!< Latched PWM ADC Start-of-Conversion A (PWM_SOCA) flag clear bit */ +#define PWM_ETCLR_SOCB_Msk 0x00000008UL /*!< Latched PWM ADC Start-of-Conversion B (PWM_SOCB) flag clear bit */ +#define PWM_ETCLR_DRQA_Msk 0x00000010UL /*!< Latched PWM DMA request A flag clear bit */ +#define PWM_ETCLR_DRQB_Msk 0x00000020UL /*!< Latched PWM DMA request B flag clear bit */ + +/*-- ETFRC: Event-Trigger Force Register ---------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< PWM_INT force bit. */ + uint32_t :1; /*!< RESERVED */ + uint32_t SOCA :1; /*!< PWM_SOCA force bit */ + uint32_t SOCB :1; /*!< PWM_SOCB force bit */ + uint32_t DRQA :1; /*!< PWM DMA request A force bit */ + uint32_t DRQB :1; /*!< PWM DMA request B force bit */ +} _PWM_ETFRC_bits; + +/* Bit field positions: */ +#define PWM_ETFRC_INT_Pos 0 /*!< PWM_INT force bit. */ +#define PWM_ETFRC_SOCA_Pos 2 /*!< PWM_SOCA force bit */ +#define PWM_ETFRC_SOCB_Pos 3 /*!< PWM_SOCB force bit */ +#define PWM_ETFRC_DRQA_Pos 4 /*!< PWM DMA request A force bit */ +#define PWM_ETFRC_DRQB_Pos 5 /*!< PWM DMA request B force bit */ + +/* Bit field masks: */ +#define PWM_ETFRC_INT_Msk 0x00000001UL /*!< PWM_INT force bit. */ +#define PWM_ETFRC_SOCA_Msk 0x00000004UL /*!< PWM_SOCA force bit */ +#define PWM_ETFRC_SOCB_Msk 0x00000008UL /*!< PWM_SOCB force bit */ +#define PWM_ETFRC_DRQA_Msk 0x00000010UL /*!< PWM DMA request A force bit */ +#define PWM_ETFRC_DRQB_Msk 0x00000020UL /*!< PWM DMA request B force bit */ + +/*-- PCCTL: PWM-Chopper Control Register ---------------------------------------------------------------------*/ +typedef struct { + uint32_t CHPEN :1; /*!< PWM-chopping enable */ + uint32_t OSTWTH :4; /*!< One-Shot pulse width */ + uint32_t SHRFREQ :3; /*!< Chopping clock frequency */ + uint32_t CHPDUTY :3; /*!< Chopping clock duty cycle */ +} _PWM_PCCTL_bits; + +/* Bit field positions: */ +#define PWM_PCCTL_CHPEN_Pos 0 /*!< PWM-chopping enable */ +#define PWM_PCCTL_OSTWTH_Pos 1 /*!< One-Shot pulse width */ +#define PWM_PCCTL_SHRFREQ_Pos 5 /*!< Chopping clock frequency */ +#define PWM_PCCTL_CHPDUTY_Pos 8 /*!< Chopping clock duty cycle */ + +/* Bit field masks: */ +#define PWM_PCCTL_CHPEN_Msk 0x00000001UL /*!< PWM-chopping enable */ +#define PWM_PCCTL_OSTWTH_Msk 0x0000001EUL /*!< One-Shot pulse width */ +#define PWM_PCCTL_SHRFREQ_Msk 0x000000E0UL /*!< Chopping clock frequency */ +#define PWM_PCCTL_CHPDUTY_Msk 0x00000700UL /*!< Chopping clock duty cycle */ + +/* Bit field enums: */ +typedef enum { + PWM_PCCTL_SHRFREQ_Div1 = 0x0UL, /*!< sync frequency divide by 1 */ + PWM_PCCTL_SHRFREQ_Div2 = 0x1UL, /*!< sync frequency divide by 2 */ + PWM_PCCTL_SHRFREQ_Div3 = 0x2UL, /*!< sync frequency divide by 3 */ + PWM_PCCTL_SHRFREQ_Div4 = 0x3UL, /*!< sync frequency divide by 4 */ + PWM_PCCTL_SHRFREQ_Div5 = 0x4UL, /*!< sync frequency divide by 5 */ + PWM_PCCTL_SHRFREQ_Div6 = 0x5UL, /*!< sync frequency divide by 6 */ + PWM_PCCTL_SHRFREQ_Div7 = 0x6UL, /*!< sync frequency divide by 7 */ + PWM_PCCTL_SHRFREQ_Div8 = 0x7UL, /*!< sync frequency divide by 8 */ +} PWM_PCCTL_SHRFREQ_Enum; + +typedef enum { + PWM_PCCTL_CHPDUTY_Duty_1_8 = 0x0UL, /*!< duty 1/8 */ + PWM_PCCTL_CHPDUTY_Duty_2_8 = 0x1UL, /*!< duty 2/8 */ + PWM_PCCTL_CHPDUTY_Duty_3_8 = 0x2UL, /*!< duty 3/8 */ + PWM_PCCTL_CHPDUTY_Duty_4_8 = 0x3UL, /*!< duty 4/8 */ + PWM_PCCTL_CHPDUTY_Duty_5_8 = 0x4UL, /*!< duty 5/8 */ + PWM_PCCTL_CHPDUTY_Duty_6_8 = 0x5UL, /*!< duty 6/8 */ + PWM_PCCTL_CHPDUTY_Duty_7_8 = 0x6UL, /*!< duty 7/8 */ +} PWM_PCCTL_CHPDUTY_Enum; + +/*-- FWDTH: Filter Width select Register ---------------------------------------------------------------------*/ +typedef struct { + uint32_t VAL :8; /*!< Pulse filter width selection */ +} _PWM_FWDTH_bits; + +/* Bit field positions: */ +#define PWM_FWDTH_VAL_Pos 0 /*!< Pulse filter width selection */ + +/* Bit field masks: */ +#define PWM_FWDTH_VAL_Msk 0x000000FFUL /*!< Pulse filter width selection */ + +/*-- HDSEL: Hold Detector event Select Register --------------------------------------------------------------*/ +typedef struct { + uint32_t ADCDC0 :1; /*!< Hold detector event by ADC Digital Comparator 0 enable */ + uint32_t ADCDC1 :1; /*!< Hold detector event by ADC Digital Comparator 1 enable */ + uint32_t ADCDC2 :1; /*!< Hold detector event by ADC Digital Comparator 2 enable */ + uint32_t ADCDC3 :1; /*!< Hold detector event by ADC Digital Comparator 3 enable */ + uint32_t :24; /*!< RESERVED */ + uint32_t CBC :1; /*!< Cycle-by-Cycle hold detector enable */ + uint32_t :2; /*!< RESERVED */ + uint32_t OST :1; /*!< One-Shot hold detector enable */ +} _PWM_HDSEL_bits; + +/* Bit field positions: */ +#define PWM_HDSEL_ADCDC0_Pos 0 /*!< Hold detector event by ADC Digital Comparator 0 enable */ +#define PWM_HDSEL_ADCDC1_Pos 1 /*!< Hold detector event by ADC Digital Comparator 1 enable */ +#define PWM_HDSEL_ADCDC2_Pos 2 /*!< Hold detector event by ADC Digital Comparator 2 enable */ +#define PWM_HDSEL_ADCDC3_Pos 3 /*!< Hold detector event by ADC Digital Comparator 3 enable */ +#define PWM_HDSEL_CBC_Pos 28 /*!< Cycle-by-Cycle hold detector enable */ +#define PWM_HDSEL_OST_Pos 31 /*!< One-Shot hold detector enable */ + +/* Bit field masks: */ +#define PWM_HDSEL_ADCDC0_Msk 0x00000001UL /*!< Hold detector event by ADC Digital Comparator 0 enable */ +#define PWM_HDSEL_ADCDC1_Msk 0x00000002UL /*!< Hold detector event by ADC Digital Comparator 1 enable */ +#define PWM_HDSEL_ADCDC2_Msk 0x00000004UL /*!< Hold detector event by ADC Digital Comparator 2 enable */ +#define PWM_HDSEL_ADCDC3_Msk 0x00000008UL /*!< Hold detector event by ADC Digital Comparator 3 enable */ +#define PWM_HDSEL_CBC_Msk 0x10000000UL /*!< Cycle-by-Cycle hold detector enable */ +#define PWM_HDSEL_OST_Msk 0x80000000UL /*!< One-Shot hold detector enable */ + +/*-- HDCTL: Hold Detector Control register -------------------------------------------------------------------*/ +typedef struct { + uint32_t HDA :2; /*!< Action when hold detection A is invoked */ + uint32_t HDB :2; /*!< Action when hold detection B is invoked */ +} _PWM_HDCTL_bits; + +/* Bit field positions: */ +#define PWM_HDCTL_HDA_Pos 0 /*!< Action when hold detection A is invoked */ +#define PWM_HDCTL_HDB_Pos 2 /*!< Action when hold detection B is invoked */ + +/* Bit field masks: */ +#define PWM_HDCTL_HDA_Msk 0x00000003UL /*!< Action when hold detection A is invoked */ +#define PWM_HDCTL_HDB_Msk 0x0000000CUL /*!< Action when hold detection B is invoked */ + +/* Bit field enums: */ +typedef enum { + PWM_HDCTL_HDA_Set = 0x1UL, /*!< PWMA/PWMB go to 1 on failture */ + PWM_HDCTL_HDA_Clear = 0x2UL, /*!< PWMA/PWMB go to 0 on failture */ + PWM_HDCTL_HDA_NoAction = 0x3UL, /*!< no action on failture */ +} PWM_HDCTL_HDA_Enum; + +typedef enum { + PWM_HDCTL_HDB_Set = 0x1UL, /*!< PWMA/PWMB go to 1 on failture */ + PWM_HDCTL_HDB_Clear = 0x2UL, /*!< PWMA/PWMB go to 0 on failture */ + PWM_HDCTL_HDB_NoAction = 0x3UL, /*!< no action on failture */ +} PWM_HDCTL_HDB_Enum; + +/*-- HDEINT: Hold Detector Enable Interrupt Register ---------------------------------------------------------*/ +typedef struct { + uint32_t :1; /*!< RESERVED */ + uint32_t CBC :1; /*!< Hold detector Cycle-by-Cycle interrupt enable */ + uint32_t OST :1; /*!< Hold detector One-Shot interrupt enable */ +} _PWM_HDEINT_bits; + +/* Bit field positions: */ +#define PWM_HDEINT_CBC_Pos 1 /*!< Hold detector Cycle-by-Cycle interrupt enable */ +#define PWM_HDEINT_OST_Pos 2 /*!< Hold detector One-Shot interrupt enable */ + +/* Bit field masks: */ +#define PWM_HDEINT_CBC_Msk 0x00000002UL /*!< Hold detector Cycle-by-Cycle interrupt enable */ +#define PWM_HDEINT_OST_Msk 0x00000004UL /*!< Hold detector One-Shot interrupt enable */ + +/*-- HDFLG: Hold Detector Flag Register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Latched hold detector interrupt status flag */ + uint32_t CBC :1; /*!< Latched status flag for hold detector Cycle-by-Cycle event */ + uint32_t OST :1; /*!< Latched status flag for hold detector One-Shot event */ +} _PWM_HDFLG_bits; + +/* Bit field positions: */ +#define PWM_HDFLG_INT_Pos 0 /*!< Latched hold detector interrupt status flag */ +#define PWM_HDFLG_CBC_Pos 1 /*!< Latched status flag for hold detector Cycle-by-Cycle event */ +#define PWM_HDFLG_OST_Pos 2 /*!< Latched status flag for hold detector One-Shot event */ + +/* Bit field masks: */ +#define PWM_HDFLG_INT_Msk 0x00000001UL /*!< Latched hold detector interrupt status flag */ +#define PWM_HDFLG_CBC_Msk 0x00000002UL /*!< Latched status flag for hold detector Cycle-by-Cycle event */ +#define PWM_HDFLG_OST_Msk 0x00000004UL /*!< Latched status flag for hold detector One-Shot event */ + +/*-- HDCLR: Register clear HD flag ---------------------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Clear hold detector interrupt flag */ + uint32_t CBC :1; /*!< Clear flag for Cycle-By-Cycle hold detector latch + */ + uint32_t OST :1; /*!< Clear flag for One-Shot hold detector latch */ +} _PWM_HDCLR_bits; + +/* Bit field positions: */ +#define PWM_HDCLR_INT_Pos 0 /*!< Clear hold detector interrupt flag */ +#define PWM_HDCLR_CBC_Pos 1 /*!< Clear flag for Cycle-By-Cycle hold detector latch + */ +#define PWM_HDCLR_OST_Pos 2 /*!< Clear flag for One-Shot hold detector latch */ + +/* Bit field masks: */ +#define PWM_HDCLR_INT_Msk 0x00000001UL /*!< Clear hold detector interrupt flag */ +#define PWM_HDCLR_CBC_Msk 0x00000002UL /*!< Clear flag for Cycle-By-Cycle hold detector latch + */ +#define PWM_HDCLR_OST_Msk 0x00000004UL /*!< Clear flag for One-Shot hold detector latch */ + +/*-- HDFRC: Hold Detector Force Register ---------------------------------------------------------------------*/ +typedef struct { + uint32_t :1; /*!< RESERVED */ + uint32_t CBC :1; /*!< Force a Cycle-by-Cycle hold detector event via software */ + uint32_t OST :1; /*!< Force a One-Shot hold detector event via software */ +} _PWM_HDFRC_bits; + +/* Bit field positions: */ +#define PWM_HDFRC_CBC_Pos 1 /*!< Force a Cycle-by-Cycle hold detector event via software */ +#define PWM_HDFRC_OST_Pos 2 /*!< Force a One-Shot hold detector event via software */ + +/* Bit field masks: */ +#define PWM_HDFRC_CBC_Msk 0x00000002UL /*!< Force a Cycle-by-Cycle hold detector event via software */ +#define PWM_HDFRC_OST_Msk 0x00000004UL /*!< Force a One-Shot hold detector event via software */ + +/*-- HDINTCLR: Hold Detector Interrupt pending Clear Register ------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Clear HD interrupt pending */ +} _PWM_HDINTCLR_bits; + +/* Bit field positions: */ +#define PWM_HDINTCLR_INT_Pos 0 /*!< Clear HD interrupt pending */ + +/* Bit field masks: */ +#define PWM_HDINTCLR_INT_Msk 0x00000001UL /*!< Clear HD interrupt pending */ + +/*-- TZINTCLR: Trip-Zone Interrupt pending Clear Register ----------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Clear TZ interrupt pending */ +} _PWM_TZINTCLR_bits; + +/* Bit field positions: */ +#define PWM_TZINTCLR_INT_Pos 0 /*!< Clear TZ interrupt pending */ + +/* Bit field masks: */ +#define PWM_TZINTCLR_INT_Msk 0x00000001UL /*!< Clear TZ interrupt pending */ + +/*-- INTCLR: PWM Interrupt pending Clear Register ------------------------------------------------------------*/ +typedef struct { + uint32_t INT :1; /*!< Clear interrupt pending */ +} _PWM_INTCLR_bits; + +/* Bit field positions: */ +#define PWM_INTCLR_INT_Pos 0 /*!< Clear interrupt pending */ + +/* Bit field masks: */ +#define PWM_INTCLR_INT_Msk 0x00000001UL /*!< Clear interrupt pending */ + +typedef struct { + union { /*!< Time-Base Control Register */ + __IO uint32_t TBCTL; /*!< TBCTL : type used for word access */ + __IO _PWM_TBCTL_bits TBCTL_bit; /*!< TBCTL_bit: structure used for bit access */ + }; + union { /*!< Time-Base Status Register */ + __IO uint32_t TBSTS; /*!< TBSTS : type used for word access */ + __IO _PWM_TBSTS_bits TBSTS_bit; /*!< TBSTS_bit: structure used for bit access */ + }; + union { /*!< Time-Base Phase Register */ + __IO uint32_t TBPHS; /*!< TBPHS : type used for word access */ + __IO _PWM_TBPHS_bits TBPHS_bit; /*!< TBPHS_bit: structure used for bit access */ + }; + union { /*!< Time-Base Counter Register */ + __IO uint32_t TBCTR; /*!< TBCTR : type used for word access */ + __IO _PWM_TBCTR_bits TBCTR_bit; /*!< TBCTR_bit: structure used for bit access */ + }; + union { /*!< Time-Base Period Register */ + __IO uint32_t TBPRD; /*!< TBPRD : type used for word access */ + __IO _PWM_TBPRD_bits TBPRD_bit; /*!< TBPRD_bit: structure used for bit access */ + }; + union { /*!< Counter-Compare Control Register */ + __IO uint32_t CMPCTL; /*!< CMPCTL : type used for word access */ + __IO _PWM_CMPCTL_bits CMPCTL_bit; /*!< CMPCTL_bit: structure used for bit access */ + }; + union { /*!< Counter-Compare A Register */ + __IO uint32_t CMPA; /*!< CMPA : type used for word access */ + __IO _PWM_CMPA_bits CMPA_bit; /*!< CMPA_bit: structure used for bit access */ + }; + union { /*!< Counter-Compare B Register */ + __IO uint32_t CMPB; /*!< CMPB : type used for word access */ + __IO _PWM_CMPB_bits CMPB_bit; /*!< CMPB_bit: structure used for bit access */ + }; + union { /*!< Action-Qualifier Output A Control Register */ + __IO uint32_t AQCTLA; /*!< AQCTLA : type used for word access */ + __IO _PWM_AQCTLA_bits AQCTLA_bit; /*!< AQCTLA_bit: structure used for bit access */ + }; + union { /*!< Action-Qualifier Output B Control Register */ + __IO uint32_t AQCTLB; /*!< AQCTLB : type used for word access */ + __IO _PWM_AQCTLB_bits AQCTLB_bit; /*!< AQCTLB_bit: structure used for bit access */ + }; + union { /*!< Action-Qualifier Software Force Register */ + __IO uint32_t AQSFRC; /*!< AQSFRC : type used for word access */ + __IO _PWM_AQSFRC_bits AQSFRC_bit; /*!< AQSFRC_bit: structure used for bit access */ + }; + union { /*!< Action-Qualifier Continuous Software Force Register */ + __IO uint32_t AQCSFRC; /*!< AQCSFRC : type used for word access */ + __IO _PWM_AQCSFRC_bits AQCSFRC_bit; /*!< AQCSFRC_bit: structure used for bit access */ + }; + union { /*!< Dead-Band Generator Control Register */ + __IO uint32_t DBCTL; /*!< DBCTL : type used for word access */ + __IO _PWM_DBCTL_bits DBCTL_bit; /*!< DBCTL_bit: structure used for bit access */ + }; + union { /*!< Dead-Band Generator Rising Edge Delay Register */ + __IO uint32_t DBRED; /*!< DBRED : type used for word access */ + __IO _PWM_DBRED_bits DBRED_bit; /*!< DBRED_bit: structure used for bit access */ + }; + union { /*!< Dead-Band Generator Falling Edge Delay Register */ + __IO uint32_t DBFED; /*!< DBFED : type used for word access */ + __IO _PWM_DBFED_bits DBFED_bit; /*!< DBFED_bit: structure used for bit access */ + }; + union { /*!< Trip-Zone Select Register */ + __IO uint32_t TZSEL; /*!< TZSEL : type used for word access */ + __IO _PWM_TZSEL_bits TZSEL_bit; /*!< TZSEL_bit: structure used for bit access */ + }; + union { /*!< Trip-Zone Control Register */ + __IO uint32_t TZCTL; /*!< TZCTL : type used for word access */ + __IO _PWM_TZCTL_bits TZCTL_bit; /*!< TZCTL_bit: structure used for bit access */ + }; + union { /*!< Trip-Zone Enable Interrupt Register */ + __IO uint32_t TZEINT; /*!< TZEINT : type used for word access */ + __IO _PWM_TZEINT_bits TZEINT_bit; /*!< TZEINT_bit: structure used for bit access */ + }; + union { /*!< Trip-Zone Flag Register */ + __I uint32_t TZFLG; /*!< TZFLG : type used for word access */ + __I _PWM_TZFLG_bits TZFLG_bit; /*!< TZFLG_bit: structure used for bit access */ + }; + union { /*!< Trip-Zone Clear Register */ + __IO uint32_t TZCLR; /*!< TZCLR : type used for word access */ + __IO _PWM_TZCLR_bits TZCLR_bit; /*!< TZCLR_bit: structure used for bit access */ + }; + union { /*!< Trip-Zone Force Register */ + __IO uint32_t TZFRC; /*!< TZFRC : type used for word access */ + __IO _PWM_TZFRC_bits TZFRC_bit; /*!< TZFRC_bit: structure used for bit access */ + }; + union { /*!< Event-Trigger Selection Register */ + __IO uint32_t ETSEL; /*!< ETSEL : type used for word access */ + __IO _PWM_ETSEL_bits ETSEL_bit; /*!< ETSEL_bit: structure used for bit access */ + }; + union { /*!< Event-Trigger Prescale Register */ + __IO uint32_t ETPS; /*!< ETPS : type used for word access */ + __IO _PWM_ETPS_bits ETPS_bit; /*!< ETPS_bit: structure used for bit access */ + }; + union { /*!< Event-Trigger Flag Register */ + __I uint32_t ETFLG; /*!< ETFLG : type used for word access */ + __I _PWM_ETFLG_bits ETFLG_bit; /*!< ETFLG_bit: structure used for bit access */ + }; + union { /*!< Event-Trigger Clear Register */ + __IO uint32_t ETCLR; /*!< ETCLR : type used for word access */ + __IO _PWM_ETCLR_bits ETCLR_bit; /*!< ETCLR_bit: structure used for bit access */ + }; + union { /*!< Event-Trigger Force Register */ + __IO uint32_t ETFRC; /*!< ETFRC : type used for word access */ + __IO _PWM_ETFRC_bits ETFRC_bit; /*!< ETFRC_bit: structure used for bit access */ + }; + union { /*!< PWM-Chopper Control Register */ + __IO uint32_t PCCTL; /*!< PCCTL : type used for word access */ + __IO _PWM_PCCTL_bits PCCTL_bit; /*!< PCCTL_bit: structure used for bit access */ + }; + __IO uint32_t Reserved0; + union { /*!< Filter Width select Register */ + __IO uint32_t FWDTH; /*!< FWDTH : type used for word access */ + __IO _PWM_FWDTH_bits FWDTH_bit; /*!< FWDTH_bit: structure used for bit access */ + }; + __IO uint32_t Reserved1[5]; + union { /*!< Hold Detector event Select Register */ + __IO uint32_t HDSEL; /*!< HDSEL : type used for word access */ + __IO _PWM_HDSEL_bits HDSEL_bit; /*!< HDSEL_bit: structure used for bit access */ + }; + union { /*!< Hold Detector Control register */ + __IO uint32_t HDCTL; /*!< HDCTL : type used for word access */ + __IO _PWM_HDCTL_bits HDCTL_bit; /*!< HDCTL_bit: structure used for bit access */ + }; + union { /*!< Hold Detector Enable Interrupt Register */ + __IO uint32_t HDEINT; /*!< HDEINT : type used for word access */ + __IO _PWM_HDEINT_bits HDEINT_bit; /*!< HDEINT_bit: structure used for bit access */ + }; + union { /*!< Hold Detector Flag Register */ + __I uint32_t HDFLG; /*!< HDFLG : type used for word access */ + __I _PWM_HDFLG_bits HDFLG_bit; /*!< HDFLG_bit: structure used for bit access */ + }; + union { /*!< Register clear HD flag */ + __IO uint32_t HDCLR; /*!< HDCLR : type used for word access */ + __IO _PWM_HDCLR_bits HDCLR_bit; /*!< HDCLR_bit: structure used for bit access */ + }; + union { /*!< Hold Detector Force Register */ + __IO uint32_t HDFRC; /*!< HDFRC : type used for word access */ + __IO _PWM_HDFRC_bits HDFRC_bit; /*!< HDFRC_bit: structure used for bit access */ + }; + union { /*!< Hold Detector Interrupt pending Clear Register */ + __O uint32_t HDINTCLR; /*!< HDINTCLR : type used for word access */ + __O _PWM_HDINTCLR_bits HDINTCLR_bit; /*!< HDINTCLR_bit: structure used for bit access */ + }; + union { /*!< Trip-Zone Interrupt pending Clear Register */ + __O uint32_t TZINTCLR; /*!< TZINTCLR : type used for word access */ + __O _PWM_TZINTCLR_bits TZINTCLR_bit; /*!< TZINTCLR_bit: structure used for bit access */ + }; + union { /*!< PWM Interrupt pending Clear Register */ + __O uint32_t INTCLR; /*!< INTCLR : type used for word access */ + __O _PWM_INTCLR_bits INTCLR_bit; /*!< INTCLR_bit: structure used for bit access */ + }; +} PWM_TypeDef; + + +/******************************************************************************/ +/* SPI registers */ +/******************************************************************************/ + +/*-- CR0: Control register 0 ---------------------------------------------------------------------------------*/ +typedef struct { + uint32_t DSS :4; /*!< Size of data */ + uint32_t FRF :2; /*!< Select protocol */ + uint32_t SPO :1; /*!< Polarity SSPCLKOUT */ + uint32_t SPH :1; /*!< Phase SSPCLKOUT */ + uint32_t SCR :8; /*!< Value divider */ +} _SPI_CR0_bits; + +/* Bit field positions: */ +#define SPI_CR0_DSS_Pos 0 /*!< Size of data */ +#define SPI_CR0_FRF_Pos 4 /*!< Select protocol */ +#define SPI_CR0_SPO_Pos 6 /*!< Polarity SSPCLKOUT */ +#define SPI_CR0_SPH_Pos 7 /*!< Phase SSPCLKOUT */ +#define SPI_CR0_SCR_Pos 8 /*!< Value divider */ + +/* Bit field masks: */ +#define SPI_CR0_DSS_Msk 0x0000000FUL /*!< Size of data */ +#define SPI_CR0_FRF_Msk 0x00000030UL /*!< Select protocol */ +#define SPI_CR0_SPO_Msk 0x00000040UL /*!< Polarity SSPCLKOUT */ +#define SPI_CR0_SPH_Msk 0x00000080UL /*!< Phase SSPCLKOUT */ +#define SPI_CR0_SCR_Msk 0x0000FF00UL /*!< Value divider */ + +/* Bit field enums: */ +typedef enum { + SPI_CR0_DSS_4bit = 0x3UL, /*!< data size 4 bit */ + SPI_CR0_DSS_5bit = 0x4UL, /*!< data size 5 bit */ + SPI_CR0_DSS_6bit = 0x5UL, /*!< data size 6 bit */ + SPI_CR0_DSS_7bit = 0x6UL, /*!< data size 7 bit */ + SPI_CR0_DSS_8bit = 0x7UL, /*!< data size 8 bit */ + SPI_CR0_DSS_9bit = 0x8UL, /*!< data size 9 bit */ + SPI_CR0_DSS_10bit = 0x9UL, /*!< data size 10 bit */ + SPI_CR0_DSS_11bit = 0xAUL, /*!< data size 11 bit */ + SPI_CR0_DSS_12bit = 0xBUL, /*!< data size 12 bit */ + SPI_CR0_DSS_13bit = 0xCUL, /*!< data size 13 bit */ + SPI_CR0_DSS_14bit = 0xDUL, /*!< data size 14 bit */ + SPI_CR0_DSS_15bit = 0xEUL, /*!< data size 15 bit */ + SPI_CR0_DSS_16bit = 0xFUL, /*!< data size 16 bit */ +} SPI_CR0_DSS_Enum; + +typedef enum { + SPI_CR0_FRF_SPI = 0x0UL, /*!< SPI of Motorola */ + SPI_CR0_FRF_SSI = 0x1UL, /*!< SSI of Texas Instruments */ + SPI_CR0_FRF_Microwire = 0x2UL, /*!< Microwire of National Semiconductor */ +} SPI_CR0_FRF_Enum; + +/*-- CR1: Control register 1 ---------------------------------------------------------------------------------*/ +typedef struct { + uint32_t :1; /*!< RESERVED */ + uint32_t SSE :1; /*!< Enable transceiver */ + uint32_t MS :1; /*!< Select mode */ + uint32_t SOD :1; /*!< Disable bit data */ + uint32_t :4; /*!< RESERVED */ + uint32_t RXIFLSEL :4; /*!< Receive interrupt FIFO level select */ + uint32_t TXIFLSEL :4; /*!< Transmit interrupt FIFO level select */ +} _SPI_CR1_bits; + +/* Bit field positions: */ +#define SPI_CR1_SSE_Pos 1 /*!< Enable transceiver */ +#define SPI_CR1_MS_Pos 2 /*!< Select mode */ +#define SPI_CR1_SOD_Pos 3 /*!< Disable bit data */ +#define SPI_CR1_RXIFLSEL_Pos 8 /*!< Receive interrupt FIFO level select */ +#define SPI_CR1_TXIFLSEL_Pos 12 /*!< Transmit interrupt FIFO level select */ + +/* Bit field masks: */ +#define SPI_CR1_SSE_Msk 0x00000002UL /*!< Enable transceiver */ +#define SPI_CR1_MS_Msk 0x00000004UL /*!< Select mode */ +#define SPI_CR1_SOD_Msk 0x00000008UL /*!< Disable bit data */ +#define SPI_CR1_RXIFLSEL_Msk 0x00000F00UL /*!< Receive interrupt FIFO level select */ +#define SPI_CR1_TXIFLSEL_Msk 0x0000F000UL /*!< Transmit interrupt FIFO level select */ + +/*-- DR: Data register ---------------------------------------------------------------------------------------*/ +typedef struct { + uint32_t DATA :16; /*!< */ +} _SPI_DR_bits; + +/* Bit field positions: */ +#define SPI_DR_DATA_Pos 0 /*!< */ + +/* Bit field masks: */ +#define SPI_DR_DATA_Msk 0x0000FFFFUL /*!< */ + +/*-- SR: State register --------------------------------------------------------------------------------------*/ +typedef struct { + uint32_t TFE :1; /*!< FIFO buffer empty flag transmitter */ + uint32_t TNF :1; /*!< Indicator the transmitter FIFO buffer is not full */ + uint32_t RNE :1; /*!< Indicate not empty receive buffer */ + uint32_t RFF :1; /*!< Indicate full receive buffer */ + uint32_t BSY :1; /*!< Activity flag */ +} _SPI_SR_bits; + +/* Bit field positions: */ +#define SPI_SR_TFE_Pos 0 /*!< FIFO buffer empty flag transmitter */ +#define SPI_SR_TNF_Pos 1 /*!< Indicator the transmitter FIFO buffer is not full */ +#define SPI_SR_RNE_Pos 2 /*!< Indicate not empty receive buffer */ +#define SPI_SR_RFF_Pos 3 /*!< Indicate full receive buffer */ +#define SPI_SR_BSY_Pos 4 /*!< Activity flag */ + +/* Bit field masks: */ +#define SPI_SR_TFE_Msk 0x00000001UL /*!< FIFO buffer empty flag transmitter */ +#define SPI_SR_TNF_Msk 0x00000002UL /*!< Indicator the transmitter FIFO buffer is not full */ +#define SPI_SR_RNE_Msk 0x00000004UL /*!< Indicate not empty receive buffer */ +#define SPI_SR_RFF_Msk 0x00000008UL /*!< Indicate full receive buffer */ +#define SPI_SR_BSY_Msk 0x00000010UL /*!< Activity flag */ + +/*-- CPSR: Clock division factor register --------------------------------------------------------------------*/ +typedef struct { + uint32_t CPSDVSR :8; /*!< Clock division factor. Bit0 always 0 */ +} _SPI_CPSR_bits; + +/* Bit field positions: */ +#define SPI_CPSR_CPSDVSR_Pos 0 /*!< Clock division factor. Bit0 always 0 */ + +/* Bit field masks: */ +#define SPI_CPSR_CPSDVSR_Msk 0x000000FFUL /*!< Clock division factor. Bit0 always 0 */ + +/*-- IMSC: Mask interrupt register ---------------------------------------------------------------------------*/ +typedef struct { + uint32_t RORIM :1; /*!< Interrupt mask bit SSPRORINTR buffer overflow receiver */ + uint32_t RTIM :1; /*!< Interrupt mask bit SSPRTINTR timeout receiver */ + uint32_t RXIM :1; /*!< SSPRXINTR interrupt mask bit to fill 50% or less of the receiver FIFO buffer */ + uint32_t TXIM :1; /*!< SSPTXINTR interrupt mask bit to fill 50% or less of the FIFO buffer of the transmitter */ +} _SPI_IMSC_bits; + +/* Bit field positions: */ +#define SPI_IMSC_RORIM_Pos 0 /*!< Interrupt mask bit SSPRORINTR buffer overflow receiver */ +#define SPI_IMSC_RTIM_Pos 1 /*!< Interrupt mask bit SSPRTINTR timeout receiver */ +#define SPI_IMSC_RXIM_Pos 2 /*!< SSPRXINTR interrupt mask bit to fill 50% or less of the receiver FIFO buffer */ +#define SPI_IMSC_TXIM_Pos 3 /*!< SSPTXINTR interrupt mask bit to fill 50% or less of the FIFO buffer of the transmitter */ + +/* Bit field masks: */ +#define SPI_IMSC_RORIM_Msk 0x00000001UL /*!< Interrupt mask bit SSPRORINTR buffer overflow receiver */ +#define SPI_IMSC_RTIM_Msk 0x00000002UL /*!< Interrupt mask bit SSPRTINTR timeout receiver */ +#define SPI_IMSC_RXIM_Msk 0x00000004UL /*!< SSPRXINTR interrupt mask bit to fill 50% or less of the receiver FIFO buffer */ +#define SPI_IMSC_TXIM_Msk 0x00000008UL /*!< SSPTXINTR interrupt mask bit to fill 50% or less of the FIFO buffer of the transmitter */ + +/*-- RIS: Status register interrupt without mask -------------------------------------------------------------*/ +typedef struct { + uint32_t RORRIS :1; /*!< Interrupt status before masking SSPRORINTR */ + uint32_t RTRIS :1; /*!< Interrupt status before masking SSPRTINTR */ + uint32_t RXRIS :1; /*!< Interrupt status before masking SSPRXINTR */ + uint32_t TXRIS :1; /*!< Interrupt status before masking SSPTXINTR */ +} _SPI_RIS_bits; + +/* Bit field positions: */ +#define SPI_RIS_RORRIS_Pos 0 /*!< Interrupt status before masking SSPRORINTR */ +#define SPI_RIS_RTRIS_Pos 1 /*!< Interrupt status before masking SSPRTINTR */ +#define SPI_RIS_RXRIS_Pos 2 /*!< Interrupt status before masking SSPRXINTR */ +#define SPI_RIS_TXRIS_Pos 3 /*!< Interrupt status before masking SSPTXINTR */ + +/* Bit field masks: */ +#define SPI_RIS_RORRIS_Msk 0x00000001UL /*!< Interrupt status before masking SSPRORINTR */ +#define SPI_RIS_RTRIS_Msk 0x00000002UL /*!< Interrupt status before masking SSPRTINTR */ +#define SPI_RIS_RXRIS_Msk 0x00000004UL /*!< Interrupt status before masking SSPRXINTR */ +#define SPI_RIS_TXRIS_Msk 0x00000008UL /*!< Interrupt status before masking SSPTXINTR */ + +/*-- MIS: Status register interrupt masking account ----------------------------------------------------------*/ +typedef struct { + uint32_t RORRIS :1; /*!< Masked interrupt status SSPRORINTR */ + uint32_t RTRIS :1; /*!< Masked interrupt status SSPRTINTR */ + uint32_t RXRIS :1; /*!< Masked interrupt status SSPRXINTR */ + uint32_t TXRIS :1; /*!< Masked interrupt status SSPTXINTR */ +} _SPI_MIS_bits; + +/* Bit field positions: */ +#define SPI_MIS_RORRIS_Pos 0 /*!< Masked interrupt status SSPRORINTR */ +#define SPI_MIS_RTRIS_Pos 1 /*!< Masked interrupt status SSPRTINTR */ +#define SPI_MIS_RXRIS_Pos 2 /*!< Masked interrupt status SSPRXINTR */ +#define SPI_MIS_TXRIS_Pos 3 /*!< Masked interrupt status SSPTXINTR */ + +/* Bit field masks: */ +#define SPI_MIS_RORRIS_Msk 0x00000001UL /*!< Masked interrupt status SSPRORINTR */ +#define SPI_MIS_RTRIS_Msk 0x00000002UL /*!< Masked interrupt status SSPRTINTR */ +#define SPI_MIS_RXRIS_Msk 0x00000004UL /*!< Masked interrupt status SSPRXINTR */ +#define SPI_MIS_TXRIS_Msk 0x00000008UL /*!< Masked interrupt status SSPTXINTR */ + +/*-- ICR: Register reset interrupt ---------------------------------------------------------------------------*/ +typedef struct { + uint32_t RORIC :1; /*!< Reset interrupt SSPRORINTR */ + uint32_t RTIC :1; /*!< Reset interrupt SSPRTINTR */ +} _SPI_ICR_bits; + +/* Bit field positions: */ +#define SPI_ICR_RORIC_Pos 0 /*!< Reset interrupt SSPRORINTR */ +#define SPI_ICR_RTIC_Pos 1 /*!< Reset interrupt SSPRTINTR */ + +/* Bit field masks: */ +#define SPI_ICR_RORIC_Msk 0x00000001UL /*!< Reset interrupt SSPRORINTR */ +#define SPI_ICR_RTIC_Msk 0x00000002UL /*!< Reset interrupt SSPRTINTR */ + +/*-- DMACR: Control register DMA -----------------------------------------------------------------------------*/ +typedef struct { + uint32_t RXDMAE :1; /*!< DMA enable bit at reception */ + uint32_t TXDMAE :1; /*!< DMA enable bit transmission */ +} _SPI_DMACR_bits; + +/* Bit field positions: */ +#define SPI_DMACR_RXDMAE_Pos 0 /*!< DMA enable bit at reception */ +#define SPI_DMACR_TXDMAE_Pos 1 /*!< DMA enable bit transmission */ + +/* Bit field masks: */ +#define SPI_DMACR_RXDMAE_Msk 0x00000001UL /*!< DMA enable bit at reception */ +#define SPI_DMACR_TXDMAE_Msk 0x00000002UL /*!< DMA enable bit transmission */ + +typedef struct { + union { /*!< Control register 0 */ + __IO uint32_t CR0; /*!< CR0 : type used for word access */ + __IO _SPI_CR0_bits CR0_bit; /*!< CR0_bit: structure used for bit access */ + }; + union { /*!< Control register 1 */ + __IO uint32_t CR1; /*!< CR1 : type used for word access */ + __IO _SPI_CR1_bits CR1_bit; /*!< CR1_bit: structure used for bit access */ + }; + union { /*!< Data register */ + __IO uint32_t DR; /*!< DR : type used for word access */ + __IO _SPI_DR_bits DR_bit; /*!< DR_bit: structure used for bit access */ + }; + union { /*!< State register */ + __I uint32_t SR; /*!< SR : type used for word access */ + __I _SPI_SR_bits SR_bit; /*!< SR_bit: structure used for bit access */ + }; + union { /*!< Clock division factor register */ + __IO uint32_t CPSR; /*!< CPSR : type used for word access */ + __IO _SPI_CPSR_bits CPSR_bit; /*!< CPSR_bit: structure used for bit access */ + }; + union { /*!< Mask interrupt register */ + __IO uint32_t IMSC; /*!< IMSC : type used for word access */ + __IO _SPI_IMSC_bits IMSC_bit; /*!< IMSC_bit: structure used for bit access */ + }; + union { /*!< Status register interrupt without mask */ + __I uint32_t RIS; /*!< RIS : type used for word access */ + __I _SPI_RIS_bits RIS_bit; /*!< RIS_bit: structure used for bit access */ + }; + union { /*!< Status register interrupt masking account */ + __I uint32_t MIS; /*!< MIS : type used for word access */ + __I _SPI_MIS_bits MIS_bit; /*!< MIS_bit: structure used for bit access */ + }; + union { /*!< Register reset interrupt */ + __O uint32_t ICR; /*!< ICR : type used for word access */ + __O _SPI_ICR_bits ICR_bit; /*!< ICR_bit: structure used for bit access */ + }; + union { /*!< Control register DMA */ + __IO uint32_t DMACR; /*!< DMACR : type used for word access */ + __IO _SPI_DMACR_bits DMACR_bit; /*!< DMACR_bit: structure used for bit access */ + }; +} SPI_TypeDef; + + +/******************************************************************************/ +/* I2C registers */ +/******************************************************************************/ + +/*-- SDA: Data register --------------------------------------------------------------------------------------*/ +typedef struct { + uint32_t DATA :8; /*!< Data field */ +} _I2C_SDA_bits; + +/* Bit field positions: */ +#define I2C_SDA_DATA_Pos 0 /*!< Data field */ + +/* Bit field masks: */ +#define I2C_SDA_DATA_Msk 0x000000FFUL /*!< Data field */ + +/*-- ST: Status register -------------------------------------------------------------------------------------*/ +typedef struct { + uint32_t MODE :6; /*!< Status code */ + uint32_t :1; /*!< RESERVED */ + uint32_t INT :1; /*!< Interrupt flag */ +} _I2C_ST_bits; + +/* Bit field positions: */ +#define I2C_ST_MODE_Pos 0 /*!< Status code */ +#define I2C_ST_INT_Pos 7 /*!< Interrupt flag */ + +/* Bit field masks: */ +#define I2C_ST_MODE_Msk 0x0000003FUL /*!< Status code */ +#define I2C_ST_INT_Msk 0x00000080UL /*!< Interrupt flag */ + +/* Bit field enums: */ +typedef enum { + I2C_ST_MODE_IDLE = 0x0UL, /*!< General - Idle, no valid status information available */ + I2C_ST_MODE_STDONE = 0x1UL, /*!< FS master - Start condition generated */ + I2C_ST_MODE_RSDONE = 0x2UL, /*!< FS master - Repeated start condition generated */ + I2C_ST_MODE_IDLARL = 0x3UL, /*!< FS master - Arbitration lost, unaddressed slave mode entered */ + I2C_ST_MODE_MTADPA = 0x4UL, /*!< FS master transmit - Slave address sent, positive ACK */ + I2C_ST_MODE_MTADNA = 0x5UL, /*!< FS master transmit - Slave address sent, negative ACK */ + I2C_ST_MODE_MTDAPA = 0x6UL, /*!< FS master transmit - Data byte sent, positive ACK */ + I2C_ST_MODE_MTDANA = 0x7UL, /*!< FS master transmit - Data byte sent, negative ACK */ + I2C_ST_MODE_MRADPA = 0x8UL, /*!< FS master receive - Slave addres sent, positive ACK */ + I2C_ST_MODE_MRADNA = 0x9UL, /*!< FS master receive - Slave addres sent, negative ACK */ + I2C_ST_MODE_MRDAPA = 0xAUL, /*!< FS master receive - Data byte received, positive ACK */ + I2C_ST_MODE_MRDANA = 0xBUL, /*!< FS master receive - Data byte received, negative ACK */ + I2C_ST_MODE_MTMCER = 0xCUL, /*!< FS master - Mastercode transmitted, error detected (positive ACK) */ + I2C_ST_MODE_SRADPA = 0x10UL, /*!< FS slave receive - Slave address received, positive ACK */ + I2C_ST_MODE_SRAAPA = 0x11UL, /*!< FS slave receive - Slave address received after arbitration loss, positive ACK */ + I2C_ST_MODE_SRDAPA = 0x12UL, /*!< FS slave receive - Data byte received, positive ACK */ + I2C_ST_MODE_SRDANA = 0x13UL, /*!< FS slave receive - Data byte received, negative ACK */ + I2C_ST_MODE_STADPA = 0x14UL, /*!< FS slave transmit - Slave address received, positive ACK */ + I2C_ST_MODE_STAAPA = 0x15UL, /*!< FS slave transmit - Slave address received, negative ACK */ + I2C_ST_MODE_STDAPA = 0x16UL, /*!< FS slave transmit - Data byte sent, positive ACK */ + I2C_ST_MODE_STDANA = 0x17UL, /*!< FS slave transmit - Data byte sent, negative ACK */ + I2C_ST_MODE_SATADP = 0x18UL, /*!< FS slave transmit alert response - Alert response address received, positive ACK */ + I2C_ST_MODE_SATAAP = 0x19UL, /*!< FS slave transmit alert response - Alert response address received after arbitration loss, positive ACK */ + I2C_ST_MODE_SATDAP = 0x1AUL, /*!< FS slave transmit alert response - Alert response data byte sent, positive ACK */ + I2C_ST_MODE_SATDAN = 0x1BUL, /*!< FS slave transmit alert response - Alert response data byte sent, negative ACK */ + I2C_ST_MODE_SSTOP = 0x1CUL, /*!< FS slave - Slave mode stop condition detected */ + I2C_ST_MODE_SGADPA = 0x1DUL, /*!< FS slave - Global call address received, positive ACK */ + I2C_ST_MODE_SDAAPA = 0x1EUL, /*!< FS slave - Global call address received after arbitration loss, positive ACK */ + I2C_ST_MODE_BERROR = 0x1FUL, /*!< General - Bus error detected (invalid start or stop condition */ + I2C_ST_MODE_HMTMCOK = 0x21UL, /*!< HS master - Master code transmitted OK - switched to HS mode */ + I2C_ST_MODE_HRSDONE = 0x22UL, /*!< HS master - Repeated start condition generated */ + I2C_ST_MODE_HIDLARL = 0x23UL, /*!< HS master - Arbitration lost, HS unaddressed slave mode entered */ + I2C_ST_MODE_HMTADPA = 0x24UL, /*!< HS master transmit - Slave address sent, positive ACK */ + I2C_ST_MODE_HMTADNA = 0x25UL, /*!< HS master transmit - Slave address sent, negative ACK */ + I2C_ST_MODE_HMTDAPA = 0x26UL, /*!< HS master transmit - Data byte sent, positive ACK */ + I2C_ST_MODE_HMTDANA = 0x27UL, /*!< HS master transmit - Data byte sent, negative ACK */ + I2C_ST_MODE_HMRADPA = 0x28UL, /*!< HS master receive - Slave address sent, positive ACK */ + I2C_ST_MODE_HMRADNA = 0x29UL, /*!< HS master receive - Slave address sent, negative ACK */ + I2C_ST_MODE_HMRDAPA = 0x2AUL, /*!< HS master receive - Data byte received, positive ACK */ + I2C_ST_MODE_HMRDANA = 0x2BUL, /*!< HS master receive - Data byte received, negative ACK */ + I2C_ST_MODE_HSRADPA = 0x30UL, /*!< HS slave receive - Slave address received, positive ACK */ + I2C_ST_MODE_HSRDAPA = 0x32UL, /*!< HS slave receive - Data byte received, positive ACK */ + I2C_ST_MODE_HSRDANA = 0x33UL, /*!< HS slave receive - Data byte received, negative ACK */ + I2C_ST_MODE_HSTADPA = 0x34UL, /*!< HS slave transmit - Slave address received, positive ACK */ + I2C_ST_MODE_HSTDAPA = 0x36UL, /*!< HS slave transmit - Data byte sent, positive ACK */ + I2C_ST_MODE_HSTDANA = 0x37UL, /*!< HS slave transmit - Data byte sent, negative ACK */ +} I2C_ST_MODE_Enum; + +/*-- CST: Status and control register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t BB :1; /*!< Bus Busy */ + uint32_t TOCDIV :2; /*!< SMBus Timeout Divider */ + uint32_t TOERR :1; /*!< SMBus Timeout Error */ + uint32_t TSDA :1; /*!< Bit test SDA */ + uint32_t TGSCL :1; /*!< Toggle SCL */ + uint32_t PECNEXT :1; /*!< PEC Next */ + uint32_t PECFAULT :1; /*!< Packet Error Fault */ +} _I2C_CST_bits; + +/* Bit field positions: */ +#define I2C_CST_BB_Pos 0 /*!< Bus Busy */ +#define I2C_CST_TOCDIV_Pos 1 /*!< SMBus Timeout Divider */ +#define I2C_CST_TOERR_Pos 3 /*!< SMBus Timeout Error */ +#define I2C_CST_TSDA_Pos 4 /*!< Bit test SDA */ +#define I2C_CST_TGSCL_Pos 5 /*!< Toggle SCL */ +#define I2C_CST_PECNEXT_Pos 6 /*!< PEC Next */ +#define I2C_CST_PECFAULT_Pos 7 /*!< Packet Error Fault */ + +/* Bit field masks: */ +#define I2C_CST_BB_Msk 0x00000001UL /*!< Bus Busy */ +#define I2C_CST_TOCDIV_Msk 0x00000006UL /*!< SMBus Timeout Divider */ +#define I2C_CST_TOERR_Msk 0x00000008UL /*!< SMBus Timeout Error */ +#define I2C_CST_TSDA_Msk 0x00000010UL /*!< Bit test SDA */ +#define I2C_CST_TGSCL_Msk 0x00000020UL /*!< Toggle SCL */ +#define I2C_CST_PECNEXT_Msk 0x00000040UL /*!< PEC Next */ +#define I2C_CST_PECFAULT_Msk 0x00000080UL /*!< Packet Error Fault */ + +/* Bit field enums: */ +typedef enum { + I2C_CST_TOCDIV_Disable = 0x0UL, /*!< disable clock */ + I2C_CST_TOCDIV_Div4 = 0x1UL, /*!< clock divided by 4 */ + I2C_CST_TOCDIV_Div8 = 0x2UL, /*!< clock divided by 8 */ + I2C_CST_TOCDIV_Div16 = 0x3UL, /*!< clock divided by 16 */ +} I2C_CST_TOCDIV_Enum; + +/*-- CTL0: Control register 0 --------------------------------------------------------------------------------*/ +typedef struct { + uint32_t START :1; /*!< Start bit */ + uint32_t STOP :1; /*!< Stop bit */ + uint32_t INTEN :1; /*!< Interrupt enable bit */ + uint32_t :1; /*!< RESERVED */ + uint32_t ACK :1; /*!< Acknowledge bit */ + uint32_t GCMEN :1; /*!< Global call match enable */ + uint32_t SMBARE :1; /*!< SMBus Alert Response Match Enable */ + uint32_t CLRST :1; /*!< Clear interrupt status */ +} _I2C_CTL0_bits; + +/* Bit field positions: */ +#define I2C_CTL0_START_Pos 0 /*!< Start bit */ +#define I2C_CTL0_STOP_Pos 1 /*!< Stop bit */ +#define I2C_CTL0_INTEN_Pos 2 /*!< Interrupt enable bit */ +#define I2C_CTL0_ACK_Pos 4 /*!< Acknowledge bit */ +#define I2C_CTL0_GCMEN_Pos 5 /*!< Global call match enable */ +#define I2C_CTL0_SMBARE_Pos 6 /*!< SMBus Alert Response Match Enable */ +#define I2C_CTL0_CLRST_Pos 7 /*!< Clear interrupt status */ + +/* Bit field masks: */ +#define I2C_CTL0_START_Msk 0x00000001UL /*!< Start bit */ +#define I2C_CTL0_STOP_Msk 0x00000002UL /*!< Stop bit */ +#define I2C_CTL0_INTEN_Msk 0x00000004UL /*!< Interrupt enable bit */ +#define I2C_CTL0_ACK_Msk 0x00000010UL /*!< Acknowledge bit */ +#define I2C_CTL0_GCMEN_Msk 0x00000020UL /*!< Global call match enable */ +#define I2C_CTL0_SMBARE_Msk 0x00000040UL /*!< SMBus Alert Response Match Enable */ +#define I2C_CTL0_CLRST_Msk 0x00000080UL /*!< Clear interrupt status */ + +/*-- ADDR: Register own address ------------------------------------------------------------------------------*/ +typedef struct { + uint32_t ADDR :7; /*!< Own 7-bit address */ + uint32_t SAEN :1; /*!< Enable address recognition */ +} _I2C_ADDR_bits; + +/* Bit field positions: */ +#define I2C_ADDR_ADDR_Pos 0 /*!< Own 7-bit address */ +#define I2C_ADDR_SAEN_Pos 7 /*!< Enable address recognition */ + +/* Bit field masks: */ +#define I2C_ADDR_ADDR_Msk 0x0000007FUL /*!< Own 7-bit address */ +#define I2C_ADDR_SAEN_Msk 0x00000080UL /*!< Enable address recognition */ + +/*-- CTL1: Control register 1 --------------------------------------------------------------------------------*/ +typedef struct { + uint32_t ENABLE :1; /*!< Enable I2C */ + uint32_t SCLFRQ :7; /*!< SCL frequency (bits [6:0]) */ +} _I2C_CTL1_bits; + +/* Bit field positions: */ +#define I2C_CTL1_ENABLE_Pos 0 /*!< Enable I2C */ +#define I2C_CTL1_SCLFRQ_Pos 1 /*!< SCL frequency (bits [6:0]) */ + +/* Bit field masks: */ +#define I2C_CTL1_ENABLE_Msk 0x00000001UL /*!< Enable I2C */ +#define I2C_CTL1_SCLFRQ_Msk 0x000000FEUL /*!< SCL frequency (bits [6:0]) */ + +/*-- TOPR: Prescaler load register ---------------------------------------------------------------------------*/ +typedef struct { + uint32_t SMBTOPR :8; /*!< Prescaler reload value */ +} _I2C_TOPR_bits; + +/* Bit field positions: */ +#define I2C_TOPR_SMBTOPR_Pos 0 /*!< Prescaler reload value */ + +/* Bit field masks: */ +#define I2C_TOPR_SMBTOPR_Msk 0x000000FFUL /*!< Prescaler reload value */ + +/*-- CTL2: Control register 2 --------------------------------------------------------------------------------*/ +typedef struct { + uint32_t S10ADR :3; /*!< Upper bits of 10-bit slave address */ + uint32_t S10EN :1; /*!< Enabled 10-bit slave address */ + uint32_t HSDIV :4; /*!< SCL frequency select in HS master mode (bits [3:0]) */ +} _I2C_CTL2_bits; + +/* Bit field positions: */ +#define I2C_CTL2_S10ADR_Pos 0 /*!< Upper bits of 10-bit slave address */ +#define I2C_CTL2_S10EN_Pos 3 /*!< Enabled 10-bit slave address */ +#define I2C_CTL2_HSDIV_Pos 4 /*!< SCL frequency select in HS master mode (bits [3:0]) */ + +/* Bit field masks: */ +#define I2C_CTL2_S10ADR_Msk 0x00000007UL /*!< Upper bits of 10-bit slave address */ +#define I2C_CTL2_S10EN_Msk 0x00000008UL /*!< Enabled 10-bit slave address */ +#define I2C_CTL2_HSDIV_Msk 0x000000F0UL /*!< SCL frequency select in HS master mode (bits [3:0]) */ + +/*-- CTL3: Control register 3 --------------------------------------------------------------------------------*/ +typedef struct { + uint32_t SCLFRQ :8; /*!< SCL frequency (bits [14:7]) */ +} _I2C_CTL3_bits; + +/* Bit field positions: */ +#define I2C_CTL3_SCLFRQ_Pos 0 /*!< SCL frequency (bits [14:7]) */ + +/* Bit field masks: */ +#define I2C_CTL3_SCLFRQ_Msk 0x000000FFUL /*!< SCL frequency (bits [14:7]) */ + +/*-- CTL4: Control Register 4 --------------------------------------------------------------------------------*/ +typedef struct { + uint32_t HSDIV :8; /*!< SCL frequency select in HS master mode (bits [11:4]) */ +} _I2C_CTL4_bits; + +/* Bit field positions: */ +#define I2C_CTL4_HSDIV_Pos 0 /*!< SCL frequency select in HS master mode (bits [11:4]) */ + +/* Bit field masks: */ +#define I2C_CTL4_HSDIV_Msk 0x000000FFUL /*!< SCL frequency select in HS master mode (bits [11:4]) */ + +typedef struct { + union { /*!< Data register */ + __IO uint32_t SDA; /*!< SDA : type used for word access */ + __IO _I2C_SDA_bits SDA_bit; /*!< SDA_bit: structure used for bit access */ + }; + union { /*!< Status register */ + __I uint32_t ST; /*!< ST : type used for word access */ + __I _I2C_ST_bits ST_bit; /*!< ST_bit: structure used for bit access */ + }; + union { /*!< Status and control register */ + __IO uint32_t CST; /*!< CST : type used for word access */ + __IO _I2C_CST_bits CST_bit; /*!< CST_bit: structure used for bit access */ + }; + union { /*!< Control register 0 */ + __IO uint32_t CTL0; /*!< CTL0 : type used for word access */ + __IO _I2C_CTL0_bits CTL0_bit; /*!< CTL0_bit: structure used for bit access */ + }; + union { /*!< Register own address */ + __IO uint32_t ADDR; /*!< ADDR : type used for word access */ + __IO _I2C_ADDR_bits ADDR_bit; /*!< ADDR_bit: structure used for bit access */ + }; + union { /*!< Control register 1 */ + __IO uint32_t CTL1; /*!< CTL1 : type used for word access */ + __IO _I2C_CTL1_bits CTL1_bit; /*!< CTL1_bit: structure used for bit access */ + }; + union { /*!< Prescaler load register */ + __IO uint32_t TOPR; /*!< TOPR : type used for word access */ + __IO _I2C_TOPR_bits TOPR_bit; /*!< TOPR_bit: structure used for bit access */ + }; + union { /*!< Control register 2 */ + __IO uint32_t CTL2; /*!< CTL2 : type used for word access */ + __IO _I2C_CTL2_bits CTL2_bit; /*!< CTL2_bit: structure used for bit access */ + }; + union { /*!< Control register 3 */ + __IO uint32_t CTL3; /*!< CTL3 : type used for word access */ + __IO _I2C_CTL3_bits CTL3_bit; /*!< CTL3_bit: structure used for bit access */ + }; + union { /*!< Control Register 4 */ + __IO uint32_t CTL4; /*!< CTL4 : type used for word access */ + __IO _I2C_CTL4_bits CTL4_bit; /*!< CTL4_bit: structure used for bit access */ + }; +} I2C_TypeDef; + + +/******************************************************************************/ +/* CAN registers */ +/******************************************************************************/ + +/*-- CLC: CAN Clock Control Register -------------------------------------------------------------------------*/ +typedef struct { + uint32_t DISR :1; /*!< Module Disable Request bit */ + uint32_t DISS :1; /*!< Module Disable Status Bit */ + uint32_t SPEN :1; /*!< Module Suspend Enable for debug */ + uint32_t :1; /*!< RESERVED */ + uint32_t SBWE :1; /*!< Module Suspend Bit Write Enable */ + uint32_t FSOE :1; /*!< Fast Shut-off Enable */ +} _CAN_CLC_bits; + +/* Bit field positions: */ +#define CAN_CLC_DISR_Pos 0 /*!< Module Disable Request bit */ +#define CAN_CLC_DISS_Pos 1 /*!< Module Disable Status Bit */ +#define CAN_CLC_SPEN_Pos 2 /*!< Module Suspend Enable for debug */ +#define CAN_CLC_SBWE_Pos 4 /*!< Module Suspend Bit Write Enable */ +#define CAN_CLC_FSOE_Pos 5 /*!< Fast Shut-off Enable */ + +/* Bit field masks: */ +#define CAN_CLC_DISR_Msk 0x00000001UL /*!< Module Disable Request bit */ +#define CAN_CLC_DISS_Msk 0x00000002UL /*!< Module Disable Status Bit */ +#define CAN_CLC_SPEN_Msk 0x00000004UL /*!< Module Suspend Enable for debug */ +#define CAN_CLC_SBWE_Msk 0x00000010UL /*!< Module Suspend Bit Write Enable */ +#define CAN_CLC_FSOE_Msk 0x00000020UL /*!< Fast Shut-off Enable */ + +/*-- ID: Module Identification Register ----------------------------------------------------------------------*/ +typedef struct { + uint32_t MODREV :8; /*!< Module Revision Number */ + uint32_t MODTYPE :8; /*!< Module type */ + uint32_t MODNUM :16; /*!< Module Number Value */ +} _CAN_ID_bits; + +/* Bit field positions: */ +#define CAN_ID_MODREV_Pos 0 /*!< Module Revision Number */ +#define CAN_ID_MODTYPE_Pos 8 /*!< Module type */ +#define CAN_ID_MODNUM_Pos 16 /*!< Module Number Value */ + +/* Bit field masks: */ +#define CAN_ID_MODREV_Msk 0x000000FFUL /*!< Module Revision Number */ +#define CAN_ID_MODTYPE_Msk 0x0000FF00UL /*!< Module type */ +#define CAN_ID_MODNUM_Msk 0xFFFF0000UL /*!< Module Number Value */ + +/*-- FDR: Fractional Divider Register ------------------------------------------------------------------------*/ +typedef struct { + uint32_t STEP :10; /*!< Step Value */ + uint32_t :1; /*!< RESERVED */ + uint32_t SM :1; /*!< Suspend Mode */ + uint32_t SC :2; /*!< Suspend Control */ + uint32_t DM :2; /*!< Divider Mode */ + uint32_t RESULT :10; /*!< Result Value */ + uint32_t :2; /*!< RESERVED */ + uint32_t SUSACK :1; /*!< Suspend Mode Acknowledge */ + uint32_t SUSREQ :1; /*!< Suspend Mode Request */ + uint32_t ENHW :1; /*!< Enable Hardware Clock Control */ + uint32_t DISCLK :1; /*!< Disable Clock */ +} _CAN_FDR_bits; + +/* Bit field positions: */ +#define CAN_FDR_STEP_Pos 0 /*!< Step Value */ +#define CAN_FDR_SM_Pos 11 /*!< Suspend Mode */ +#define CAN_FDR_SC_Pos 12 /*!< Suspend Control */ +#define CAN_FDR_DM_Pos 14 /*!< Divider Mode */ +#define CAN_FDR_RESULT_Pos 16 /*!< Result Value */ +#define CAN_FDR_SUSACK_Pos 28 /*!< Suspend Mode Acknowledge */ +#define CAN_FDR_SUSREQ_Pos 29 /*!< Suspend Mode Request */ +#define CAN_FDR_ENHW_Pos 30 /*!< Enable Hardware Clock Control */ +#define CAN_FDR_DISCLK_Pos 31 /*!< Disable Clock */ + +/* Bit field masks: */ +#define CAN_FDR_STEP_Msk 0x000003FFUL /*!< Step Value */ +#define CAN_FDR_SM_Msk 0x00000800UL /*!< Suspend Mode */ +#define CAN_FDR_SC_Msk 0x00003000UL /*!< Suspend Control */ +#define CAN_FDR_DM_Msk 0x0000C000UL /*!< Divider Mode */ +#define CAN_FDR_RESULT_Msk 0x03FF0000UL /*!< Result Value */ +#define CAN_FDR_SUSACK_Msk 0x10000000UL /*!< Suspend Mode Acknowledge */ +#define CAN_FDR_SUSREQ_Msk 0x20000000UL /*!< Suspend Mode Request */ +#define CAN_FDR_ENHW_Msk 0x40000000UL /*!< Enable Hardware Clock Control */ +#define CAN_FDR_DISCLK_Msk 0x80000000UL /*!< Disable Clock */ + +/* Bit field enums: */ +typedef enum { + CAN_FDR_DM_Disable = 0x0UL, /*!< counter disabled */ + CAN_FDR_DM_NormalMode = 0x1UL, /*!< normal operation mode */ + CAN_FDR_DM_DividerMode = 0x2UL, /*!< divider operation mode */ +} CAN_FDR_DM_Enum; + +/*-- LIST: LIST: List Register0 -------------------------------------------------------------------------------*/ +typedef struct { + uint32_t BEGIN :8; /*!< List Begin */ + uint32_t END :8; /*!< List End */ + uint32_t SIZE :8; /*!< List Size */ + uint32_t EMPTY :1; /*!< List Empty Indication */ +} _CAN_LIST_LIST_bits; + +/* Bit field positions: */ +#define CAN_LIST_LIST_BEGIN_Pos 0 /*!< List Begin */ +#define CAN_LIST_LIST_END_Pos 8 /*!< List End */ +#define CAN_LIST_LIST_SIZE_Pos 16 /*!< List Size */ +#define CAN_LIST_LIST_EMPTY_Pos 24 /*!< List Empty Indication */ + +/* Bit field masks: */ +#define CAN_LIST_LIST_BEGIN_Msk 0x000000FFUL /*!< List Begin */ +#define CAN_LIST_LIST_END_Msk 0x0000FF00UL /*!< List End */ +#define CAN_LIST_LIST_SIZE_Msk 0x00FF0000UL /*!< List Size */ +#define CAN_LIST_LIST_EMPTY_Msk 0x01000000UL /*!< List Empty Indication */ + +/*-- MSPND: MSPND: Message Pending Register0 ------------------------------------------------------------------*/ +typedef struct { + uint32_t PND :32; /*!< Message Pending */ +} _CAN_MSPND_MSPND_bits; + +/* Bit field positions: */ +#define CAN_MSPND_MSPND_PND_Pos 0 /*!< Message Pending */ + +/* Bit field masks: */ +#define CAN_MSPND_MSPND_PND_Msk 0xFFFFFFFFUL /*!< Message Pending */ + +/*-- MSID: MSID: Message Index Register0 ----------------------------------------------------------------------*/ +typedef struct { + uint32_t INDEX :8; /*!< Message Pending Index */ +} _CAN_MSID_MSID_bits; + +/* Bit field positions: */ +#define CAN_MSID_MSID_INDEX_Pos 0 /*!< Message Pending Index */ + +/* Bit field masks: */ +#define CAN_MSID_MSID_INDEX_Msk 0x000000FFUL /*!< Message Pending Index */ + +/*-- MSIMASK: Message Index Mask Register --------------------------------------------------------------------*/ +typedef struct { + uint32_t IM :32; /*!< Message Index Mask */ +} _CAN_MSIMASK_bits; + +/* Bit field positions: */ +#define CAN_MSIMASK_IM_Pos 0 /*!< Message Index Mask */ + +/* Bit field masks: */ +#define CAN_MSIMASK_IM_Msk 0xFFFFFFFFUL /*!< Message Index Mask */ + +/*-- PANCTR: Panel Control Register --------------------------------------------------------------------------*/ +typedef struct { + uint32_t PANCMD :8; /*!< Panel Command */ + uint32_t BUSY :1; /*!< Panel Busy Flag */ + uint32_t RBUSY :1; /*!< Result Busy Flag */ + uint32_t :6; /*!< RESERVED */ + uint32_t PANAR1 :8; /*!< Panel argument 1 */ + uint32_t PANAR2 :8; /*!< Panel argument 2 */ +} _CAN_PANCTR_bits; + +/* Bit field positions: */ +#define CAN_PANCTR_PANCMD_Pos 0 /*!< Panel Command */ +#define CAN_PANCTR_BUSY_Pos 8 /*!< Panel Busy Flag */ +#define CAN_PANCTR_RBUSY_Pos 9 /*!< Result Busy Flag */ +#define CAN_PANCTR_PANAR1_Pos 16 /*!< Panel argument 1 */ +#define CAN_PANCTR_PANAR2_Pos 24 /*!< Panel argument 2 */ + +/* Bit field masks: */ +#define CAN_PANCTR_PANCMD_Msk 0x000000FFUL /*!< Panel Command */ +#define CAN_PANCTR_BUSY_Msk 0x00000100UL /*!< Panel Busy Flag */ +#define CAN_PANCTR_RBUSY_Msk 0x00000200UL /*!< Result Busy Flag */ +#define CAN_PANCTR_PANAR1_Msk 0x00FF0000UL /*!< Panel argument 1 */ +#define CAN_PANCTR_PANAR2_Msk 0xFF000000UL /*!< Panel argument 2 */ + +/*-- MCR: ---------------------------------------------------------------------------------------------------*/ +typedef struct { + uint32_t :12; /*!< RESERVED */ + uint32_t MPSEL :4; /*!< Message Pending Selector */ +} _CAN_MCR_bits; + +/* Bit field positions: */ +#define CAN_MCR_MPSEL_Pos 12 /*!< Message Pending Selector */ + +/* Bit field masks: */ +#define CAN_MCR_MPSEL_Msk 0x0000F000UL /*!< Message Pending Selector */ + +/*-- MITR: Module Interrupt Trigger Register -----------------------------------------------------------------*/ +typedef struct { + uint32_t IT :16; /*!< Interrupt Trigger */ +} _CAN_MITR_bits; + +/* Bit field positions: */ +#define CAN_MITR_IT_Pos 0 /*!< Interrupt Trigger */ + +/* Bit field masks: */ +#define CAN_MITR_IT_Msk 0x0000FFFFUL /*!< Interrupt Trigger */ + +/*-- Node: NCR: Node control register0 ------------------------------------------------------------------------*/ +typedef struct { + uint32_t INIT :1; /*!< Node Initialization */ + uint32_t TRIE :1; /*!< Transfer Interrupt Enable */ + uint32_t LECIE :1; /*!< LEC Indicated Error Interrupt Enable */ + uint32_t ALIE :1; /*!< Alert Interrupt Enable */ + uint32_t CANDIS :1; /*!< CAN Disable */ + uint32_t :1; /*!< RESERVED */ + uint32_t CCE :1; /*!< Configuration Change Enable */ + uint32_t CALM :1; /*!< CAN Analyzer Mode */ + uint32_t SUSEN :1; /*!< Suspend Enable */ +} _CAN_Node_NCR_bits; + +/* Bit field positions: */ +#define CAN_Node_NCR_INIT_Pos 0 /*!< Node Initialization */ +#define CAN_Node_NCR_TRIE_Pos 1 /*!< Transfer Interrupt Enable */ +#define CAN_Node_NCR_LECIE_Pos 2 /*!< LEC Indicated Error Interrupt Enable */ +#define CAN_Node_NCR_ALIE_Pos 3 /*!< Alert Interrupt Enable */ +#define CAN_Node_NCR_CANDIS_Pos 4 /*!< CAN Disable */ +#define CAN_Node_NCR_CCE_Pos 6 /*!< Configuration Change Enable */ +#define CAN_Node_NCR_CALM_Pos 7 /*!< CAN Analyzer Mode */ +#define CAN_Node_NCR_SUSEN_Pos 8 /*!< Suspend Enable */ + +/* Bit field masks: */ +#define CAN_Node_NCR_INIT_Msk 0x00000001UL /*!< Node Initialization */ +#define CAN_Node_NCR_TRIE_Msk 0x00000002UL /*!< Transfer Interrupt Enable */ +#define CAN_Node_NCR_LECIE_Msk 0x00000004UL /*!< LEC Indicated Error Interrupt Enable */ +#define CAN_Node_NCR_ALIE_Msk 0x00000008UL /*!< Alert Interrupt Enable */ +#define CAN_Node_NCR_CANDIS_Msk 0x00000010UL /*!< CAN Disable */ +#define CAN_Node_NCR_CCE_Msk 0x00000040UL /*!< Configuration Change Enable */ +#define CAN_Node_NCR_CALM_Msk 0x00000080UL /*!< CAN Analyzer Mode */ +#define CAN_Node_NCR_SUSEN_Msk 0x00000100UL /*!< Suspend Enable */ + +/*-- Node: NSR: Node Status Register0 -------------------------------------------------------------------------*/ +typedef struct { + uint32_t LEC :3; /*!< Last Error Code */ + uint32_t TXOK :1; /*!< Message Transmitted Successfully */ + uint32_t RXOK :1; /*!< Message Received Successfully */ + uint32_t ALERT :1; /*!< Alert Warning */ + uint32_t EWRN :1; /*!< Error Warning Status */ + uint32_t BOFF :1; /*!< Bus-Off Status */ + uint32_t LLE :1; /*!< List Length Error */ + uint32_t LOE :1; /*!< List Object Error */ + uint32_t SUSACK :1; /*!< Suspend Acknowledge */ +} _CAN_Node_NSR_bits; + +/* Bit field positions: */ +#define CAN_Node_NSR_LEC_Pos 0 /*!< Last Error Code */ +#define CAN_Node_NSR_TXOK_Pos 3 /*!< Message Transmitted Successfully */ +#define CAN_Node_NSR_RXOK_Pos 4 /*!< Message Received Successfully */ +#define CAN_Node_NSR_ALERT_Pos 5 /*!< Alert Warning */ +#define CAN_Node_NSR_EWRN_Pos 6 /*!< Error Warning Status */ +#define CAN_Node_NSR_BOFF_Pos 7 /*!< Bus-Off Status */ +#define CAN_Node_NSR_LLE_Pos 8 /*!< List Length Error */ +#define CAN_Node_NSR_LOE_Pos 9 /*!< List Object Error */ +#define CAN_Node_NSR_SUSACK_Pos 10 /*!< Suspend Acknowledge */ + +/* Bit field masks: */ +#define CAN_Node_NSR_LEC_Msk 0x00000007UL /*!< Last Error Code */ +#define CAN_Node_NSR_TXOK_Msk 0x00000008UL /*!< Message Transmitted Successfully */ +#define CAN_Node_NSR_RXOK_Msk 0x00000010UL /*!< Message Received Successfully */ +#define CAN_Node_NSR_ALERT_Msk 0x00000020UL /*!< Alert Warning */ +#define CAN_Node_NSR_EWRN_Msk 0x00000040UL /*!< Error Warning Status */ +#define CAN_Node_NSR_BOFF_Msk 0x00000080UL /*!< Bus-Off Status */ +#define CAN_Node_NSR_LLE_Msk 0x00000100UL /*!< List Length Error */ +#define CAN_Node_NSR_LOE_Msk 0x00000200UL /*!< List Object Error */ +#define CAN_Node_NSR_SUSACK_Msk 0x00000400UL /*!< Suspend Acknowledge */ + +/* Bit field enums: */ +typedef enum { + CAN_Node_NSR_LEC_NoErr = 0x0UL, /*!< no error */ + CAN_Node_NSR_LEC_StuffErr = 0x1UL, /*!< stuff error */ + CAN_Node_NSR_LEC_FormErr = 0x2UL, /*!< form error */ + CAN_Node_NSR_LEC_AckErr = 0x3UL, /*!< acknowlegment error */ + CAN_Node_NSR_LEC_Bit1Err = 0x4UL, /*!< bit 1 error */ + CAN_Node_NSR_LEC_Bit0Err = 0x5UL, /*!< bit 0 error */ + CAN_Node_NSR_LEC_CRCErr = 0x6UL, /*!< CRC error */ + CAN_Node_NSR_LEC_WriteEn = 0x7UL, /*!< enable hardware write */ +} CAN_Node_NSR_LEC_Enum; + +/*-- Node: NIPR: Node Interrupt Pointer Register0 -------------------------------------------------------------*/ +typedef struct { + uint32_t ALINP :4; /*!< Alert Interrupt Node Pointer */ + uint32_t LECINP :4; /*!< Last Error Code Interrupt Node Pointer */ + uint32_t TRINP :4; /*!< Transfer OK Interrupt Node Pointer */ + uint32_t CFCINP :4; /*!< Frame Counter Interrupt Node Pointer */ +} _CAN_Node_NIPR_bits; + +/* Bit field positions: */ +#define CAN_Node_NIPR_ALINP_Pos 0 /*!< Alert Interrupt Node Pointer */ +#define CAN_Node_NIPR_LECINP_Pos 4 /*!< Last Error Code Interrupt Node Pointer */ +#define CAN_Node_NIPR_TRINP_Pos 8 /*!< Transfer OK Interrupt Node Pointer */ +#define CAN_Node_NIPR_CFCINP_Pos 12 /*!< Frame Counter Interrupt Node Pointer */ + +/* Bit field masks: */ +#define CAN_Node_NIPR_ALINP_Msk 0x0000000FUL /*!< Alert Interrupt Node Pointer */ +#define CAN_Node_NIPR_LECINP_Msk 0x000000F0UL /*!< Last Error Code Interrupt Node Pointer */ +#define CAN_Node_NIPR_TRINP_Msk 0x00000F00UL /*!< Transfer OK Interrupt Node Pointer */ +#define CAN_Node_NIPR_CFCINP_Msk 0x0000F000UL /*!< Frame Counter Interrupt Node Pointer */ + +/*-- Node: NPCR: Node Port Control Register0 ------------------------------------------------------------------*/ +typedef struct { + uint32_t RXSEL :3; /*!< Receive Select */ + uint32_t :5; /*!< RESERVED */ + uint32_t LBM :1; /*!< Loop-Back Mode */ +} _CAN_Node_NPCR_bits; + +/* Bit field positions: */ +#define CAN_Node_NPCR_RXSEL_Pos 0 /*!< Receive Select */ +#define CAN_Node_NPCR_LBM_Pos 8 /*!< Loop-Back Mode */ + +/* Bit field masks: */ +#define CAN_Node_NPCR_RXSEL_Msk 0x00000007UL /*!< Receive Select */ +#define CAN_Node_NPCR_LBM_Msk 0x00000100UL /*!< Loop-Back Mode */ + +/*-- Node: NBTR: Node Bit Timing Register0 --------------------------------------------------------------------*/ +typedef struct { + uint32_t BRP :6; /*!< Baud Rate Prescaler */ + uint32_t SJW :2; /*!< Synchronization Jump Width */ + uint32_t TSEG1 :4; /*!< Time Segment Before Sample Point */ + uint32_t TSEG2 :3; /*!< Time Segment After Sample Point */ + uint32_t DIV8 :1; /*!< Divide Prescaler Clock by 8 */ +} _CAN_Node_NBTR_bits; + +/* Bit field positions: */ +#define CAN_Node_NBTR_BRP_Pos 0 /*!< Baud Rate Prescaler */ +#define CAN_Node_NBTR_SJW_Pos 6 /*!< Synchronization Jump Width */ +#define CAN_Node_NBTR_TSEG1_Pos 8 /*!< Time Segment Before Sample Point */ +#define CAN_Node_NBTR_TSEG2_Pos 12 /*!< Time Segment After Sample Point */ +#define CAN_Node_NBTR_DIV8_Pos 15 /*!< Divide Prescaler Clock by 8 */ + +/* Bit field masks: */ +#define CAN_Node_NBTR_BRP_Msk 0x0000003FUL /*!< Baud Rate Prescaler */ +#define CAN_Node_NBTR_SJW_Msk 0x000000C0UL /*!< Synchronization Jump Width */ +#define CAN_Node_NBTR_TSEG1_Msk 0x00000F00UL /*!< Time Segment Before Sample Point */ +#define CAN_Node_NBTR_TSEG2_Msk 0x00007000UL /*!< Time Segment After Sample Point */ +#define CAN_Node_NBTR_DIV8_Msk 0x00008000UL /*!< Divide Prescaler Clock by 8 */ + +/*-- Node: NECNT: Node Error Counter Register0 ----------------------------------------------------------------*/ +typedef struct { + uint32_t REC :8; /*!< Receive Error Counter */ + uint32_t TEC :8; /*!< Transmit Error Counter */ + uint32_t EWRNLVL :8; /*!< Error Warning Level */ + uint32_t LETD :1; /*!< Last Error Transfer Direction */ + uint32_t LEINC :1; /*!< Last Error Increment */ +} _CAN_Node_NECNT_bits; + +/* Bit field positions: */ +#define CAN_Node_NECNT_REC_Pos 0 /*!< Receive Error Counter */ +#define CAN_Node_NECNT_TEC_Pos 8 /*!< Transmit Error Counter */ +#define CAN_Node_NECNT_EWRNLVL_Pos 16 /*!< Error Warning Level */ +#define CAN_Node_NECNT_LETD_Pos 24 /*!< Last Error Transfer Direction */ +#define CAN_Node_NECNT_LEINC_Pos 25 /*!< Last Error Increment */ + +/* Bit field masks: */ +#define CAN_Node_NECNT_REC_Msk 0x000000FFUL /*!< Receive Error Counter */ +#define CAN_Node_NECNT_TEC_Msk 0x0000FF00UL /*!< Transmit Error Counter */ +#define CAN_Node_NECNT_EWRNLVL_Msk 0x00FF0000UL /*!< Error Warning Level */ +#define CAN_Node_NECNT_LETD_Msk 0x01000000UL /*!< Last Error Transfer Direction */ +#define CAN_Node_NECNT_LEINC_Msk 0x02000000UL /*!< Last Error Increment */ + +/*-- Node: NFCR: Node Frame Counter Register0 -----------------------------------------------------------------*/ +typedef struct { + uint32_t CFC :16; /*!< CAN Frame Counter */ + uint32_t CFSEL :3; /*!< CAN Frame Count Selection */ + uint32_t CFMOD :2; /*!< CAN Frame Counter Mode */ + uint32_t :1; /*!< RESERVED */ + uint32_t CFCIE :1; /*!< CAN Frame Counter Interrupt Enable */ + uint32_t CFCOV :1; /*!< CAN Frame Counter Overflow Flag */ +} _CAN_Node_NFCR_bits; + +/* Bit field positions: */ +#define CAN_Node_NFCR_CFC_Pos 0 /*!< CAN Frame Counter */ +#define CAN_Node_NFCR_CFSEL_Pos 16 /*!< CAN Frame Count Selection */ +#define CAN_Node_NFCR_CFMOD_Pos 19 /*!< CAN Frame Counter Mode */ +#define CAN_Node_NFCR_CFCIE_Pos 22 /*!< CAN Frame Counter Interrupt Enable */ +#define CAN_Node_NFCR_CFCOV_Pos 23 /*!< CAN Frame Counter Overflow Flag */ + +/* Bit field masks: */ +#define CAN_Node_NFCR_CFC_Msk 0x0000FFFFUL /*!< CAN Frame Counter */ +#define CAN_Node_NFCR_CFSEL_Msk 0x00070000UL /*!< CAN Frame Count Selection */ +#define CAN_Node_NFCR_CFMOD_Msk 0x00180000UL /*!< CAN Frame Counter Mode */ +#define CAN_Node_NFCR_CFCIE_Msk 0x00400000UL /*!< CAN Frame Counter Interrupt Enable */ +#define CAN_Node_NFCR_CFCOV_Msk 0x00800000UL /*!< CAN Frame Counter Overflow Flag */ + +//Cluster LIST: +typedef struct { + union { + /*!< List Register0 */ + __I uint32_t LIST; /*!< LIST : type used for word access */ + __I _CAN_LIST_LIST_bits LIST_bit; /*!< LIST_bit: structure used for bit access */ + }; +} _CAN_LIST_TypeDef; +//Cluster MSPND: +typedef struct { + union { + /*!< Message Pending Register0 */ + __IO uint32_t MSPND; /*!< MSPND : type used for word access */ + __IO _CAN_MSPND_MSPND_bits MSPND_bit; /*!< MSPND_bit: structure used for bit access */ + }; +} _CAN_MSPND_TypeDef; +//Cluster MSID: +typedef struct { + union { + /*!< Message Index Register0 */ + __I uint32_t MSID; /*!< MSID : type used for word access */ + __I _CAN_MSID_MSID_bits MSID_bit; /*!< MSID_bit: structure used for bit access */ + }; +} _CAN_MSID_TypeDef; +//Cluster Node: +typedef struct { + union { + /*!< Node control register0 */ + __IO uint32_t NCR; /*!< NCR : type used for word access */ + __IO _CAN_Node_NCR_bits NCR_bit; /*!< NCR_bit: structure used for bit access */ + }; + union { + /*!< Node Status Register0 */ + __IO uint32_t NSR; /*!< NSR : type used for word access */ + __IO _CAN_Node_NSR_bits NSR_bit; /*!< NSR_bit: structure used for bit access */ + }; + union { + /*!< Node Interrupt Pointer Register0 */ + __IO uint32_t NIPR; /*!< NIPR : type used for word access */ + __IO _CAN_Node_NIPR_bits NIPR_bit; /*!< NIPR_bit: structure used for bit access */ + }; + union { + /*!< Node Port Control Register0 */ + __IO uint32_t NPCR; /*!< NPCR : type used for word access */ + __IO _CAN_Node_NPCR_bits NPCR_bit; /*!< NPCR_bit: structure used for bit access */ + }; + union { + /*!< Node Bit Timing Register0 */ + __IO uint32_t NBTR; /*!< NBTR : type used for word access */ + __IO _CAN_Node_NBTR_bits NBTR_bit; /*!< NBTR_bit: structure used for bit access */ + }; + union { + /*!< Node Error Counter Register0 */ + __IO uint32_t NECNT; /*!< NECNT : type used for word access */ + __IO _CAN_Node_NECNT_bits NECNT_bit; /*!< NECNT_bit: structure used for bit access */ + }; + union { + /*!< Node Frame Counter Register0 */ + __IO uint32_t NFCR; /*!< NFCR : type used for word access */ + __IO _CAN_Node_NFCR_bits NFCR_bit; /*!< NFCR_bit: structure used for bit access */ + }; + __IO uint32_t Reserved0[57]; +} _CAN_Node_TypeDef; +typedef struct { + union { /*!< CAN Clock Control Register */ + __IO uint32_t CLC; /*!< CLC : type used for word access */ + __IO _CAN_CLC_bits CLC_bit; /*!< CLC_bit: structure used for bit access */ + }; + __IO uint32_t Reserved0; + union { /*!< Module Identification Register */ + __IO uint32_t ID; /*!< ID : type used for word access */ + __IO _CAN_ID_bits ID_bit; /*!< ID_bit: structure used for bit access */ + }; + union { /*!< Fractional Divider Register */ + __IO uint32_t FDR; /*!< FDR : type used for word access */ + __IO _CAN_FDR_bits FDR_bit; /*!< FDR_bit: structure used for bit access */ + }; + __IO uint32_t Reserved1[60]; + _CAN_LIST_TypeDef LIST[8]; + __IO uint32_t Reserved2[8]; + _CAN_MSPND_TypeDef MSPND[8]; + __IO uint32_t Reserved3[8]; + _CAN_MSID_TypeDef MSID[8]; + __IO uint32_t Reserved4[8]; + union { /*!< Message Index Mask Register */ + __IO uint32_t MSIMASK; /*!< MSIMASK : type used for word access */ + __IO _CAN_MSIMASK_bits MSIMASK_bit; /*!< MSIMASK_bit: structure used for bit access */ + }; + union { /*!< Panel Control Register */ + __IO uint32_t PANCTR; /*!< PANCTR : type used for word access */ + __IO _CAN_PANCTR_bits PANCTR_bit; /*!< PANCTR_bit: structure used for bit access */ + }; + union { /*!< */ + __IO uint32_t MCR; /*!< MCR : type used for word access */ + __IO _CAN_MCR_bits MCR_bit; /*!< MCR_bit: structure used for bit access */ + }; + union { /*!< Module Interrupt Trigger Register */ + __O uint32_t MITR; /*!< MITR : type used for word access */ + __O _CAN_MITR_bits MITR_bit; /*!< MITR_bit: structure used for bit access */ + }; + __IO uint32_t Reserved5[12]; + _CAN_Node_TypeDef Node[2]; +} CAN_TypeDef; + + +/******************************************************************************/ +/* CANMSG registers */ +/******************************************************************************/ + +/*-- Msg: MOFCR: Message Object Function Control Register0 ----------------------------------------------------*/ +typedef struct { + uint32_t MMC :4; /*!< Message Mode Control */ + uint32_t :4; /*!< RESERVED */ + uint32_t GDFS :1; /*!< Gateway Data Frame Selected */ + uint32_t IDC :1; /*!< Identifier Copy */ + uint32_t DLCC :1; /*!< Data Lengh Code Copy */ + uint32_t DATC :1; /*!< Data Copy */ + uint32_t :4; /*!< RESERVED */ + uint32_t RXIE :1; /*!< Receive Interrupt Enable */ + uint32_t TXIE :1; /*!< Transmit Interrupt Enable */ + uint32_t OVIE :1; /*!< Overflow Interrupt Enable */ + uint32_t :1; /*!< RESERVED */ + uint32_t FRREN :1; /*!< Foreign Remote Request Enable */ + uint32_t RMM :1; /*!< Transmit Object Remote Monitoring */ + uint32_t SDT :1; /*!< Single Data Transfer */ + uint32_t STT :1; /*!< Single Transmit Trial */ + uint32_t DLC :4; /*!< Data Length Code */ +} _CANMSG_Msg_MOFCR_bits; + +/* Bit field positions: */ +#define CANMSG_Msg_MOFCR_MMC_Pos 0 /*!< Message Mode Control */ +#define CANMSG_Msg_MOFCR_GDFS_Pos 8 /*!< Gateway Data Frame Selected */ +#define CANMSG_Msg_MOFCR_IDC_Pos 9 /*!< Identifier Copy */ +#define CANMSG_Msg_MOFCR_DLCC_Pos 10 /*!< Data Lengh Code Copy */ +#define CANMSG_Msg_MOFCR_DATC_Pos 11 /*!< Data Copy */ +#define CANMSG_Msg_MOFCR_RXIE_Pos 16 /*!< Receive Interrupt Enable */ +#define CANMSG_Msg_MOFCR_TXIE_Pos 17 /*!< Transmit Interrupt Enable */ +#define CANMSG_Msg_MOFCR_OVIE_Pos 18 /*!< Overflow Interrupt Enable */ +#define CANMSG_Msg_MOFCR_FRREN_Pos 20 /*!< Foreign Remote Request Enable */ +#define CANMSG_Msg_MOFCR_RMM_Pos 21 /*!< Transmit Object Remote Monitoring */ +#define CANMSG_Msg_MOFCR_SDT_Pos 22 /*!< Single Data Transfer */ +#define CANMSG_Msg_MOFCR_STT_Pos 23 /*!< Single Transmit Trial */ +#define CANMSG_Msg_MOFCR_DLC_Pos 24 /*!< Data Length Code */ + +/* Bit field masks: */ +#define CANMSG_Msg_MOFCR_MMC_Msk 0x0000000FUL /*!< Message Mode Control */ +#define CANMSG_Msg_MOFCR_GDFS_Msk 0x00000100UL /*!< Gateway Data Frame Selected */ +#define CANMSG_Msg_MOFCR_IDC_Msk 0x00000200UL /*!< Identifier Copy */ +#define CANMSG_Msg_MOFCR_DLCC_Msk 0x00000400UL /*!< Data Lengh Code Copy */ +#define CANMSG_Msg_MOFCR_DATC_Msk 0x00000800UL /*!< Data Copy */ +#define CANMSG_Msg_MOFCR_RXIE_Msk 0x00010000UL /*!< Receive Interrupt Enable */ +#define CANMSG_Msg_MOFCR_TXIE_Msk 0x00020000UL /*!< Transmit Interrupt Enable */ +#define CANMSG_Msg_MOFCR_OVIE_Msk 0x00040000UL /*!< Overflow Interrupt Enable */ +#define CANMSG_Msg_MOFCR_FRREN_Msk 0x00100000UL /*!< Foreign Remote Request Enable */ +#define CANMSG_Msg_MOFCR_RMM_Msk 0x00200000UL /*!< Transmit Object Remote Monitoring */ +#define CANMSG_Msg_MOFCR_SDT_Msk 0x00400000UL /*!< Single Data Transfer */ +#define CANMSG_Msg_MOFCR_STT_Msk 0x00800000UL /*!< Single Transmit Trial */ +#define CANMSG_Msg_MOFCR_DLC_Msk 0x0F000000UL /*!< Data Length Code */ + +/* Bit field enums: */ +typedef enum { + CANMSG_Msg_MOFCR_MMC_MsgObj = 0x0UL, /*!< message object */ + CANMSG_Msg_MOFCR_MMC_RXObj = 0x1UL, /*!< receiver FIFO structure object */ + CANMSG_Msg_MOFCR_MMC_TXObj = 0x2UL, /*!< transmitter FIFO structure object */ + CANMSG_Msg_MOFCR_MMC_SlaveTXObj = 0x3UL, /*!< transmitter FIFO structure slave object */ + CANMSG_Msg_MOFCR_MMC_SrcObj = 0x4UL, /*!< gateway source object */ +} CANMSG_Msg_MOFCR_MMC_Enum; + +/*-- Msg: MOFGPR: Message Object FIFO/Gateway Pointer Register0 -----------------------------------------------*/ +typedef struct { + uint32_t BOT :8; /*!< Botom Pointer */ + uint32_t TOP :8; /*!< Top Pointer */ + uint32_t CUR :8; /*!< Current Object Pointer */ + uint32_t SEL :8; /*!< Object Select Pointer */ +} _CANMSG_Msg_MOFGPR_bits; + +/* Bit field positions: */ +#define CANMSG_Msg_MOFGPR_BOT_Pos 0 /*!< Botom Pointer */ +#define CANMSG_Msg_MOFGPR_TOP_Pos 8 /*!< Top Pointer */ +#define CANMSG_Msg_MOFGPR_CUR_Pos 16 /*!< Current Object Pointer */ +#define CANMSG_Msg_MOFGPR_SEL_Pos 24 /*!< Object Select Pointer */ + +/* Bit field masks: */ +#define CANMSG_Msg_MOFGPR_BOT_Msk 0x000000FFUL /*!< Botom Pointer */ +#define CANMSG_Msg_MOFGPR_TOP_Msk 0x0000FF00UL /*!< Top Pointer */ +#define CANMSG_Msg_MOFGPR_CUR_Msk 0x00FF0000UL /*!< Current Object Pointer */ +#define CANMSG_Msg_MOFGPR_SEL_Msk 0xFF000000UL /*!< Object Select Pointer */ + +/*-- Msg: MOIPR: Message Object Interrupt Pointer Register0 ---------------------------------------------------*/ +typedef struct { + uint32_t RXINP :4; /*!< Receive Interrupt Node Pointer */ + uint32_t TXINP :4; /*!< Transmit Interrupt Node Pointer */ + uint32_t MPN :8; /*!< Message Pending Number */ + uint32_t CFCVAL :16; /*!< CAN Frame Counter Value */ +} _CANMSG_Msg_MOIPR_bits; + +/* Bit field positions: */ +#define CANMSG_Msg_MOIPR_RXINP_Pos 0 /*!< Receive Interrupt Node Pointer */ +#define CANMSG_Msg_MOIPR_TXINP_Pos 4 /*!< Transmit Interrupt Node Pointer */ +#define CANMSG_Msg_MOIPR_MPN_Pos 8 /*!< Message Pending Number */ +#define CANMSG_Msg_MOIPR_CFCVAL_Pos 16 /*!< CAN Frame Counter Value */ + +/* Bit field masks: */ +#define CANMSG_Msg_MOIPR_RXINP_Msk 0x0000000FUL /*!< Receive Interrupt Node Pointer */ +#define CANMSG_Msg_MOIPR_TXINP_Msk 0x000000F0UL /*!< Transmit Interrupt Node Pointer */ +#define CANMSG_Msg_MOIPR_MPN_Msk 0x0000FF00UL /*!< Message Pending Number */ +#define CANMSG_Msg_MOIPR_CFCVAL_Msk 0xFFFF0000UL /*!< CAN Frame Counter Value */ + +/*-- Msg: MOAMR: Message Object Acceptance Mask Register0 -----------------------------------------------------*/ +typedef struct { + uint32_t AM :29; /*!< Acceptance Mask for Message Identifier */ + uint32_t MIDE :1; /*!< Acceptance Mask Bit for Message IDE Bit */ +} _CANMSG_Msg_MOAMR_bits; + +/* Bit field positions: */ +#define CANMSG_Msg_MOAMR_AM_Pos 0 /*!< Acceptance Mask for Message Identifier */ +#define CANMSG_Msg_MOAMR_MIDE_Pos 29 /*!< Acceptance Mask Bit for Message IDE Bit */ + +/* Bit field masks: */ +#define CANMSG_Msg_MOAMR_AM_Msk 0x1FFFFFFFUL /*!< Acceptance Mask for Message Identifier */ +#define CANMSG_Msg_MOAMR_MIDE_Msk 0x20000000UL /*!< Acceptance Mask Bit for Message IDE Bit */ + +/*-- Msg: MODATAL: Message Object Data Register Low0 ----------------------------------------------------------*/ +typedef struct { + uint32_t DB0 :8; /*!< Data byte 0 of message object */ + uint32_t DB1 :8; /*!< Data byte 1 of message object */ + uint32_t DB2 :8; /*!< Data byte 2 of message object */ + uint32_t DB3 :8; /*!< Data byte 3 of message object */ +} _CANMSG_Msg_MODATAL_bits; + +/* Bit field positions: */ +#define CANMSG_Msg_MODATAL_DB0_Pos 0 /*!< Data byte 0 of message object */ +#define CANMSG_Msg_MODATAL_DB1_Pos 8 /*!< Data byte 1 of message object */ +#define CANMSG_Msg_MODATAL_DB2_Pos 16 /*!< Data byte 2 of message object */ +#define CANMSG_Msg_MODATAL_DB3_Pos 24 /*!< Data byte 3 of message object */ + +/* Bit field masks: */ +#define CANMSG_Msg_MODATAL_DB0_Msk 0x000000FFUL /*!< Data byte 0 of message object */ +#define CANMSG_Msg_MODATAL_DB1_Msk 0x0000FF00UL /*!< Data byte 1 of message object */ +#define CANMSG_Msg_MODATAL_DB2_Msk 0x00FF0000UL /*!< Data byte 2 of message object */ +#define CANMSG_Msg_MODATAL_DB3_Msk 0xFF000000UL /*!< Data byte 3 of message object */ + +/*-- Msg: MODATAH: Message Object Data Register High0 ---------------------------------------------------------*/ +typedef struct { + uint32_t DB4 :8; /*!< Data byte 4 of message object */ + uint32_t DB5 :8; /*!< Data byte 5 of message object */ + uint32_t DB6 :8; /*!< Data byte 6 of message object */ + uint32_t DB7 :8; /*!< Data byte 7 of message object */ +} _CANMSG_Msg_MODATAH_bits; + +/* Bit field positions: */ +#define CANMSG_Msg_MODATAH_DB4_Pos 0 /*!< Data byte 4 of message object */ +#define CANMSG_Msg_MODATAH_DB5_Pos 8 /*!< Data byte 5 of message object */ +#define CANMSG_Msg_MODATAH_DB6_Pos 16 /*!< Data byte 6 of message object */ +#define CANMSG_Msg_MODATAH_DB7_Pos 24 /*!< Data byte 7 of message object */ + +/* Bit field masks: */ +#define CANMSG_Msg_MODATAH_DB4_Msk 0x000000FFUL /*!< Data byte 4 of message object */ +#define CANMSG_Msg_MODATAH_DB5_Msk 0x0000FF00UL /*!< Data byte 5 of message object */ +#define CANMSG_Msg_MODATAH_DB6_Msk 0x00FF0000UL /*!< Data byte 6 of message object */ +#define CANMSG_Msg_MODATAH_DB7_Msk 0xFF000000UL /*!< Data byte 7 of message object */ + +/*-- Msg: MOAR: Message Object Arbitration Register0 ----------------------------------------------------------*/ +typedef struct { + uint32_t ID :29; /*!< CAN identifier of Message Object */ + uint32_t IDE :1; /*!< Identifier Extension Bit of Messgae Object */ + uint32_t PRI :2; /*!< Priority Class */ +} _CANMSG_Msg_MOAR_bits; + +/* Bit field positions: */ +#define CANMSG_Msg_MOAR_ID_Pos 0 /*!< CAN identifier of Message Object */ +#define CANMSG_Msg_MOAR_IDE_Pos 29 /*!< Identifier Extension Bit of Messgae Object */ +#define CANMSG_Msg_MOAR_PRI_Pos 30 /*!< Priority Class */ + +/* Bit field masks: */ +#define CANMSG_Msg_MOAR_ID_Msk 0x1FFFFFFFUL /*!< CAN identifier of Message Object */ +#define CANMSG_Msg_MOAR_IDE_Msk 0x20000000UL /*!< Identifier Extension Bit of Messgae Object */ +#define CANMSG_Msg_MOAR_PRI_Msk 0xC0000000UL /*!< Priority Class */ + +/*-- Msg: MOCTR: Message Object Control Register0 -------------------------------------------------------------*/ +typedef struct { + uint32_t RESRXPND :1; /*!< Reset Receive Pending */ + uint32_t RESTXPND :1; /*!< Reset Transmit Pending */ + uint32_t RESRXUPD :1; /*!< Reset Receive Updating */ + uint32_t RESNEWDAT :1; /*!< Reset New Data */ + uint32_t RESMSGLST :1; /*!< Reset Message Lost */ + uint32_t RESMSGVAL :1; /*!< Reset Message Valid */ + uint32_t RESRTSEL :1; /*!< Reset Receive/Transmit Selected */ + uint32_t RESRXEN :1; /*!< Reset Receive Enable */ + uint32_t RESTXRQ :1; /*!< Reset Transmit Request */ + uint32_t RESTXEN0 :1; /*!< Reset Transmit Enable 0 */ + uint32_t RESTXEN1 :1; /*!< Reset Transmit Enable 1 */ + uint32_t RESDIR :1; /*!< Reset Message Direction */ + uint32_t :4; /*!< RESERVED */ + uint32_t SETRXPND :1; /*!< Set Receive Pending */ + uint32_t SETTXPND :1; /*!< Set Transmit Pending */ + uint32_t SETRXUPD :1; /*!< Set Receive Updating */ + uint32_t SETNEWDAT :1; /*!< Set New Data */ + uint32_t SETMSGLST :1; /*!< Set Message Lost */ + uint32_t SETMSGVAL :1; /*!< Set Message Valid */ + uint32_t SETRTSEL :1; /*!< Set Receive/Transmit Selected */ + uint32_t SETRXEN :1; /*!< Set Receive Enable */ + uint32_t SETTXRQ :1; /*!< Set Transmit Request */ + uint32_t SETTXEN0 :1; /*!< Set Transmit Enable 0 */ + uint32_t SETTXEN1 :1; /*!< Set Transmit Enable 1 */ + uint32_t SETDIR :1; /*!< Set Message Direction */ +} _CANMSG_Msg_MOCTR_bits; + +/* Bit field positions: */ +#define CANMSG_Msg_MOCTR_RESRXPND_Pos 0 /*!< Reset Receive Pending */ +#define CANMSG_Msg_MOCTR_RESTXPND_Pos 1 /*!< Reset Transmit Pending */ +#define CANMSG_Msg_MOCTR_RESRXUPD_Pos 2 /*!< Reset Receive Updating */ +#define CANMSG_Msg_MOCTR_RESNEWDAT_Pos 3 /*!< Reset New Data */ +#define CANMSG_Msg_MOCTR_RESMSGLST_Pos 4 /*!< Reset Message Lost */ +#define CANMSG_Msg_MOCTR_RESMSGVAL_Pos 5 /*!< Reset Message Valid */ +#define CANMSG_Msg_MOCTR_RESRTSEL_Pos 6 /*!< Reset Receive/Transmit Selected */ +#define CANMSG_Msg_MOCTR_RESRXEN_Pos 7 /*!< Reset Receive Enable */ +#define CANMSG_Msg_MOCTR_RESTXRQ_Pos 8 /*!< Reset Transmit Request */ +#define CANMSG_Msg_MOCTR_RESTXEN0_Pos 9 /*!< Reset Transmit Enable 0 */ +#define CANMSG_Msg_MOCTR_RESTXEN1_Pos 10 /*!< Reset Transmit Enable 1 */ +#define CANMSG_Msg_MOCTR_RESDIR_Pos 11 /*!< Reset Message Direction */ +#define CANMSG_Msg_MOCTR_SETRXPND_Pos 16 /*!< Set Receive Pending */ +#define CANMSG_Msg_MOCTR_SETTXPND_Pos 17 /*!< Set Transmit Pending */ +#define CANMSG_Msg_MOCTR_SETRXUPD_Pos 18 /*!< Set Receive Updating */ +#define CANMSG_Msg_MOCTR_SETNEWDAT_Pos 19 /*!< Set New Data */ +#define CANMSG_Msg_MOCTR_SETMSGLST_Pos 20 /*!< Set Message Lost */ +#define CANMSG_Msg_MOCTR_SETMSGVAL_Pos 21 /*!< Set Message Valid */ +#define CANMSG_Msg_MOCTR_SETRTSEL_Pos 22 /*!< Set Receive/Transmit Selected */ +#define CANMSG_Msg_MOCTR_SETRXEN_Pos 23 /*!< Set Receive Enable */ +#define CANMSG_Msg_MOCTR_SETTXRQ_Pos 24 /*!< Set Transmit Request */ +#define CANMSG_Msg_MOCTR_SETTXEN0_Pos 25 /*!< Set Transmit Enable 0 */ +#define CANMSG_Msg_MOCTR_SETTXEN1_Pos 26 /*!< Set Transmit Enable 1 */ +#define CANMSG_Msg_MOCTR_SETDIR_Pos 27 /*!< Set Message Direction */ + +/* Bit field masks: */ +#define CANMSG_Msg_MOCTR_RESRXPND_Msk 0x00000001UL /*!< Reset Receive Pending */ +#define CANMSG_Msg_MOCTR_RESTXPND_Msk 0x00000002UL /*!< Reset Transmit Pending */ +#define CANMSG_Msg_MOCTR_RESRXUPD_Msk 0x00000004UL /*!< Reset Receive Updating */ +#define CANMSG_Msg_MOCTR_RESNEWDAT_Msk 0x00000008UL /*!< Reset New Data */ +#define CANMSG_Msg_MOCTR_RESMSGLST_Msk 0x00000010UL /*!< Reset Message Lost */ +#define CANMSG_Msg_MOCTR_RESMSGVAL_Msk 0x00000020UL /*!< Reset Message Valid */ +#define CANMSG_Msg_MOCTR_RESRTSEL_Msk 0x00000040UL /*!< Reset Receive/Transmit Selected */ +#define CANMSG_Msg_MOCTR_RESRXEN_Msk 0x00000080UL /*!< Reset Receive Enable */ +#define CANMSG_Msg_MOCTR_RESTXRQ_Msk 0x00000100UL /*!< Reset Transmit Request */ +#define CANMSG_Msg_MOCTR_RESTXEN0_Msk 0x00000200UL /*!< Reset Transmit Enable 0 */ +#define CANMSG_Msg_MOCTR_RESTXEN1_Msk 0x00000400UL /*!< Reset Transmit Enable 1 */ +#define CANMSG_Msg_MOCTR_RESDIR_Msk 0x00000800UL /*!< Reset Message Direction */ +#define CANMSG_Msg_MOCTR_SETRXPND_Msk 0x00010000UL /*!< Set Receive Pending */ +#define CANMSG_Msg_MOCTR_SETTXPND_Msk 0x00020000UL /*!< Set Transmit Pending */ +#define CANMSG_Msg_MOCTR_SETRXUPD_Msk 0x00040000UL /*!< Set Receive Updating */ +#define CANMSG_Msg_MOCTR_SETNEWDAT_Msk 0x00080000UL /*!< Set New Data */ +#define CANMSG_Msg_MOCTR_SETMSGLST_Msk 0x00100000UL /*!< Set Message Lost */ +#define CANMSG_Msg_MOCTR_SETMSGVAL_Msk 0x00200000UL /*!< Set Message Valid */ +#define CANMSG_Msg_MOCTR_SETRTSEL_Msk 0x00400000UL /*!< Set Receive/Transmit Selected */ +#define CANMSG_Msg_MOCTR_SETRXEN_Msk 0x00800000UL /*!< Set Receive Enable */ +#define CANMSG_Msg_MOCTR_SETTXRQ_Msk 0x01000000UL /*!< Set Transmit Request */ +#define CANMSG_Msg_MOCTR_SETTXEN0_Msk 0x02000000UL /*!< Set Transmit Enable 0 */ +#define CANMSG_Msg_MOCTR_SETTXEN1_Msk 0x04000000UL /*!< Set Transmit Enable 1 */ +#define CANMSG_Msg_MOCTR_SETDIR_Msk 0x08000000UL /*!< Set Message Direction */ + +/*-- Msg: MOSTAT: Message Object Status Register 0 ------------------------------------------------------------*/ +typedef struct { + uint32_t RXPND :1; /*!< Receive Pending */ + uint32_t TXPND :1; /*!< Transmit Pending */ + uint32_t RXUPD :1; /*!< Receive Updating */ + uint32_t NEWDAT :1; /*!< New Data */ + uint32_t MSGLST :1; /*!< Message Lost */ + uint32_t MSGVAL :1; /*!< Message Valid */ + uint32_t RTSEL :1; /*!< Receive/Transmit Selected */ + uint32_t RXEN :1; /*!< Receive Enable */ + uint32_t TXRQ :1; /*!< Transmit Request */ + uint32_t TXEN0 :1; /*!< Transmit Enable 0 */ + uint32_t TXEN1 :1; /*!< Transmit Enable 1 */ + uint32_t DIR :1; /*!< Message Direction */ + uint32_t LIST :4; /*!< List Allocation */ + uint32_t PPREV :8; /*!< Pointer To Previous Message Object */ + uint32_t PNEXT :8; /*!< Pointer to Next Message Object */ +} _CANMSG_Msg_MOSTAT_bits; + +/* Bit field positions: */ +#define CANMSG_Msg_MOSTAT_RXPND_Pos 0 /*!< Receive Pending */ +#define CANMSG_Msg_MOSTAT_TXPND_Pos 1 /*!< Transmit Pending */ +#define CANMSG_Msg_MOSTAT_RXUPD_Pos 2 /*!< Receive Updating */ +#define CANMSG_Msg_MOSTAT_NEWDAT_Pos 3 /*!< New Data */ +#define CANMSG_Msg_MOSTAT_MSGLST_Pos 4 /*!< Message Lost */ +#define CANMSG_Msg_MOSTAT_MSGVAL_Pos 5 /*!< Message Valid */ +#define CANMSG_Msg_MOSTAT_RTSEL_Pos 6 /*!< Receive/Transmit Selected */ +#define CANMSG_Msg_MOSTAT_RXEN_Pos 7 /*!< Receive Enable */ +#define CANMSG_Msg_MOSTAT_TXRQ_Pos 8 /*!< Transmit Request */ +#define CANMSG_Msg_MOSTAT_TXEN0_Pos 9 /*!< Transmit Enable 0 */ +#define CANMSG_Msg_MOSTAT_TXEN1_Pos 10 /*!< Transmit Enable 1 */ +#define CANMSG_Msg_MOSTAT_DIR_Pos 11 /*!< Message Direction */ +#define CANMSG_Msg_MOSTAT_LIST_Pos 12 /*!< List Allocation */ +#define CANMSG_Msg_MOSTAT_PPREV_Pos 16 /*!< Pointer To Previous Message Object */ +#define CANMSG_Msg_MOSTAT_PNEXT_Pos 24 /*!< Pointer to Next Message Object */ + +/* Bit field masks: */ +#define CANMSG_Msg_MOSTAT_RXPND_Msk 0x00000001UL /*!< Receive Pending */ +#define CANMSG_Msg_MOSTAT_TXPND_Msk 0x00000002UL /*!< Transmit Pending */ +#define CANMSG_Msg_MOSTAT_RXUPD_Msk 0x00000004UL /*!< Receive Updating */ +#define CANMSG_Msg_MOSTAT_NEWDAT_Msk 0x00000008UL /*!< New Data */ +#define CANMSG_Msg_MOSTAT_MSGLST_Msk 0x00000010UL /*!< Message Lost */ +#define CANMSG_Msg_MOSTAT_MSGVAL_Msk 0x00000020UL /*!< Message Valid */ +#define CANMSG_Msg_MOSTAT_RTSEL_Msk 0x00000040UL /*!< Receive/Transmit Selected */ +#define CANMSG_Msg_MOSTAT_RXEN_Msk 0x00000080UL /*!< Receive Enable */ +#define CANMSG_Msg_MOSTAT_TXRQ_Msk 0x00000100UL /*!< Transmit Request */ +#define CANMSG_Msg_MOSTAT_TXEN0_Msk 0x00000200UL /*!< Transmit Enable 0 */ +#define CANMSG_Msg_MOSTAT_TXEN1_Msk 0x00000400UL /*!< Transmit Enable 1 */ +#define CANMSG_Msg_MOSTAT_DIR_Msk 0x00000800UL /*!< Message Direction */ +#define CANMSG_Msg_MOSTAT_LIST_Msk 0x0000F000UL /*!< List Allocation */ +#define CANMSG_Msg_MOSTAT_PPREV_Msk 0x00FF0000UL /*!< Pointer To Previous Message Object */ +#define CANMSG_Msg_MOSTAT_PNEXT_Msk 0xFF000000UL /*!< Pointer to Next Message Object */ + +//Cluster Msg: +typedef struct { + union { + /*!< Message Object Function Control Register0 */ + __IO uint32_t MOFCR; /*!< MOFCR : type used for word access */ + __IO _CANMSG_Msg_MOFCR_bits MOFCR_bit; /*!< MOFCR_bit: structure used for bit access */ + }; + union { + /*!< Message Object FIFO/Gateway Pointer Register0 */ + __IO uint32_t MOFGPR; /*!< MOFGPR : type used for word access */ + __IO _CANMSG_Msg_MOFGPR_bits MOFGPR_bit; /*!< MOFGPR_bit: structure used for bit access */ + }; + union { + /*!< Message Object Interrupt Pointer Register0 */ + __IO uint32_t MOIPR; /*!< MOIPR : type used for word access */ + __IO _CANMSG_Msg_MOIPR_bits MOIPR_bit; /*!< MOIPR_bit: structure used for bit access */ + }; + union { + /*!< Message Object Acceptance Mask Register0 */ + __IO uint32_t MOAMR; /*!< MOAMR : type used for word access */ + __IO _CANMSG_Msg_MOAMR_bits MOAMR_bit; /*!< MOAMR_bit: structure used for bit access */ + }; + union { + /*!< Message Object Data Register Low0 */ + __IO uint32_t MODATAL; /*!< MODATAL : type used for word access */ + __IO _CANMSG_Msg_MODATAL_bits MODATAL_bit; /*!< MODATAL_bit: structure used for bit access */ + }; + union { + /*!< Message Object Data Register High0 */ + __IO uint32_t MODATAH; /*!< MODATAH : type used for word access */ + __IO _CANMSG_Msg_MODATAH_bits MODATAH_bit; /*!< MODATAH_bit: structure used for bit access */ + }; + union { + /*!< Message Object Arbitration Register0 */ + __IO uint32_t MOAR; /*!< MOAR : type used for word access */ + __IO _CANMSG_Msg_MOAR_bits MOAR_bit; /*!< MOAR_bit: structure used for bit access */ + }; + union { + union { + /*!< Message Object Control Register0 */ + __O uint32_t MOCTR; /*!< MOCTR : type used for word access */ + __O _CANMSG_Msg_MOCTR_bits MOCTR_bit; /*!< MOCTR_bit: structure used for bit access */ + }; + union { + /*!< Message Object Status Register 0 */ + __I uint32_t MOSTAT; /*!< MOSTAT : type used for word access */ + __I _CANMSG_Msg_MOSTAT_bits MOSTAT_bit; /*!< MOSTAT_bit: structure used for bit access */ + }; + }; +} _CANMSG_Msg_TypeDef; +typedef struct { + _CANMSG_Msg_TypeDef Msg[256]; +} CANMSG_TypeDef; + + +/* ----------------- End of section using anonymous unions ---------------- */ +#if defined(__CC_ARM) + #pragma pop +#elif defined(__ICCARM__) + /* leave anonymous unions enabled */ +#elif defined(__GNUC__) + /* anonymous unions are enabled by default */ +#elif defined(__TMS470__) + /* anonymous unions are enabled by default */ +#elif defined(__TASKING__) + #pragma warning restore +#elif defined (__CMCPPARM__) + /* anonymous unions are enabled by default */ +#else + #warning Not supported compiler type +#endif + +/******************************************************************************/ +/* Peripheral memory map */ +/******************************************************************************/ +#define ADC_BASE 0x40000000UL +#define GPIOA_BASE 0x40010000UL +#define GPIOB_BASE 0x40011000UL +#define CAN_BASE 0x40020000UL +#define CANMSG_BASE 0x40021000UL +#define MFLASH_BASE 0x40030000UL +#define SIU_BASE 0x40040000UL +#define RCU_BASE 0x40041000UL +#define PMU_BASE 0x40042000UL +#define WDT_BASE 0x40043000UL +#define DMA_BASE 0x40044000UL +#define UART0_BASE 0x40045000UL +#define UART1_BASE 0x40046000UL +#define SPI_BASE 0x40047000UL +#define TMR0_BASE 0x40048000UL +#define TMR1_BASE 0x40049000UL +#define TMR2_BASE 0x4004A000UL +#define TMR3_BASE 0x4004B000UL +#define PWM0_BASE 0x4004C000UL +#define PWM1_BASE 0x4004D000UL +#define PWM2_BASE 0x4004E000UL +#define QEP_BASE 0x4004F000UL +#define I2C_BASE 0x40050000UL +#define ECAP0_BASE 0x40051000UL +#define ECAP1_BASE 0x40052000UL +#define ECAP2_BASE 0x40053000UL + +/******************************************************************************/ +/* Peripheral declaration */ +/******************************************************************************/ +#define ADC ((ADC_TypeDef *) ADC_BASE) +#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) +#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) +#define CAN ((CAN_TypeDef *) CAN_BASE) +#define CANMSG ((CANMSG_TypeDef *) CANMSG_BASE) +#define MFLASH ((MFLASH_TypeDef *) MFLASH_BASE) +#define SIU ((SIU_TypeDef *) SIU_BASE) +#define RCU ((RCU_TypeDef *) RCU_BASE) +#define PMU ((PMU_TypeDef *) PMU_BASE) +#define WDT ((WDT_TypeDef *) WDT_BASE) +#define DMA ((DMA_TypeDef *) DMA_BASE) +#define UART0 ((UART_TypeDef *) UART0_BASE) +#define UART1 ((UART_TypeDef *) UART1_BASE) +#define SPI ((SPI_TypeDef *) SPI_BASE) +#define TMR0 ((TMR_TypeDef *) TMR0_BASE) +#define TMR1 ((TMR_TypeDef *) TMR1_BASE) +#define TMR2 ((TMR_TypeDef *) TMR2_BASE) +#define TMR3 ((TMR_TypeDef *) TMR3_BASE) +#define PWM0 ((PWM_TypeDef *) PWM0_BASE) +#define PWM1 ((PWM_TypeDef *) PWM1_BASE) +#define PWM2 ((PWM_TypeDef *) PWM2_BASE) +#define QEP ((QEP_TypeDef *) QEP_BASE) +#define I2C ((I2C_TypeDef *) I2C_BASE) +#define ECAP0 ((ECAP_TypeDef *) ECAP0_BASE) +#define ECAP1 ((ECAP_TypeDef *) ECAP1_BASE) +#define ECAP2 ((ECAP_TypeDef *) ECAP2_BASE) + +/******************************************************************************/ +/* Peripheral capabilities */ +/******************************************************************************/ +#define ADC_PRESENT +#define ADC_TOTAL 1 +typedef enum { + ADC_Num +} ADC_Num_TypeDef; + +#define GPIO_PRESENT +#define GPIO_TOTAL 2 +typedef enum { + GPIOA_Num, + GPIOB_Num +} GPIO_Num_TypeDef; + +#define CAN_PRESENT +#define CAN_TOTAL 1 +typedef enum { + CAN_Num +} CAN_Num_TypeDef; + +#define CANMSG_PRESENT +#define CANMSG_TOTAL 1 +typedef enum { + CANMSG_Num +} CANMSG_Num_TypeDef; + +#define MFLASH_PRESENT +#define MFLASH_TOTAL 1 +typedef enum { + MFLASH_Num +} MFLASH_Num_TypeDef; + +#define SIU_PRESENT +#define SIU_TOTAL 1 +typedef enum { + SIU_Num +} SIU_Num_TypeDef; + +#define RCU_PRESENT +#define RCU_TOTAL 1 +typedef enum { + RCU_Num +} RCU_Num_TypeDef; + +#define PMU_PRESENT +#define PMU_TOTAL 1 +typedef enum { + PMU_Num +} PMU_Num_TypeDef; + +#define WDT_PRESENT +#define WDT_TOTAL 1 +typedef enum { + WDT_Num +} WDT_Num_TypeDef; + +#define DMA_PRESENT +#define DMA_TOTAL 1 +typedef enum { + DMA_Num +} DMA_Num_TypeDef; + +#define UART_PRESENT +#define UART_TOTAL 2 +typedef enum { + UART0_Num, + UART1_Num +} UART_Num_TypeDef; + +#define SPI_PRESENT +#define SPI_TOTAL 1 +typedef enum { + SPI_Num +} SPI_Num_TypeDef; + +#define TMR_PRESENT +#define TMR_TOTAL 4 +typedef enum { + TMR0_Num, + TMR1_Num, + TMR2_Num, + TMR3_Num +} TMR_Num_TypeDef; + +#define PWM_PRESENT +#define PWM_TOTAL 3 +typedef enum { + PWM0_Num, + PWM1_Num, + PWM2_Num +} PWM_Num_TypeDef; + +#define QEP_PRESENT +#define QEP_TOTAL 1 +typedef enum { + QEP_Num +} QEP_Num_TypeDef; + +#define I2C_PRESENT +#define I2C_TOTAL 1 +typedef enum { + I2C_Num +} I2C_Num_TypeDef; + +#define ECAP_PRESENT +#define ECAP_TOTAL 3 +typedef enum { + ECAP0_Num, + ECAP1_Num, + ECAP2_Num +} ECAP_Num_TypeDef; + +/******************************************************************************/ +/* Peripheral assertions */ +/******************************************************************************/ +#define IS_ADC_PERIPH(PERIPH) (((PERIPH) == ADC)) +#define IS_GPIO_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \ + ((PERIPH) == GPIOB)) +#define IS_CAN_PERIPH(PERIPH) (((PERIPH) == CAN)) +#define IS_CANMSG_PERIPH(PERIPH) (((PERIPH) == CANMSG)) +#define IS_MFLASH_PERIPH(PERIPH) (((PERIPH) == MFLASH)) +#define IS_SIU_PERIPH(PERIPH) (((PERIPH) == SIU)) +#define IS_RCU_PERIPH(PERIPH) (((PERIPH) == RCU)) +#define IS_PMU_PERIPH(PERIPH) (((PERIPH) == PMU)) +#define IS_WDT_PERIPH(PERIPH) (((PERIPH) == WDT)) +#define IS_DMA_PERIPH(PERIPH) (((PERIPH) == DMA)) +#define IS_UART_PERIPH(PERIPH) (((PERIPH) == UART0) || \ + ((PERIPH) == UART1)) +#define IS_SPI_PERIPH(PERIPH) (((PERIPH) == SPI)) +#define IS_TMR_PERIPH(PERIPH) (((PERIPH) == TMR0) || \ + ((PERIPH) == TMR1) || \ + ((PERIPH) == TMR2) || \ + ((PERIPH) == TMR3)) +#define IS_PWM_PERIPH(PERIPH) (((PERIPH) == PWM0) || \ + ((PERIPH) == PWM1) || \ + ((PERIPH) == PWM2)) +#define IS_QEP_PERIPH(PERIPH) (((PERIPH) == QEP)) +#define IS_I2C_PERIPH(PERIPH) (((PERIPH) == I2C)) +#define IS_ECAP_PERIPH(PERIPH) (((PERIPH) == ECAP0) || \ + ((PERIPH) == ECAP1) || \ + ((PERIPH) == ECAP2)) + +#ifdef __cplusplus +} +#endif + +#endif /* __K1921VK035_H */ + +/************************** (C) COPYRIGHT 2018 NIIET ************************* +* +* END OF FILE K1921VK035.h */ diff --git a/include/core_cm4.h b/include/core_cm4.h new file mode 100644 index 0000000..1fd9855 --- /dev/null +++ b/include/core_cm4.h @@ -0,0 +1,1758 @@ +/**************************************************************************//** + * @file core_cm4.h + * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File + * @version V3.01 + * @date 22. March 2012 + * + * @note + * Copyright (C) 2009-2012 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ +#if defined ( __ICCARM__ ) +#pragma system_include /* treat file as system include file for MISRA check */ +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef __CORE_CM4_H_GENERIC +#define __CORE_CM4_H_GENERIC + +/** \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** \ingroup Cortex_M4 + @{ + */ + +/* CMSIS CM4 definitions */ +#define __CM4_CMSIS_VERSION_MAIN (0x03) /*!< [31:16] CMSIS HAL main version */ +#define __CM4_CMSIS_VERSION_SUB (0x01) /*!< [15:0] CMSIS HAL sub version */ +#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16) | \ + __CM4_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x04) /*!< Cortex-M Core */ + + +#if defined ( __CC_ARM ) +#define __ASM __asm /*!< asm keyword for ARM Compiler */ +#define __INLINE __inline /*!< inline keyword for ARM Compiler */ +#define __STATIC_INLINE static __inline + +#elif defined ( __ICCARM__ ) +#define __ASM __asm /*!< asm keyword for IAR Compiler */ +#define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */ +#define __STATIC_INLINE static inline + +#elif defined ( __TMS470__ ) +#define __ASM __asm /*!< asm keyword for TI CCS Compiler */ +#define __STATIC_INLINE static inline + +#elif defined ( __GNUC__ ) +#define __ASM __asm /*!< asm keyword for GNU Compiler */ +#define __INLINE inline /*!< inline keyword for GNU Compiler */ +#define __STATIC_INLINE static inline + +#elif defined ( __TASKING__ ) +#define __ASM __asm /*!< asm keyword for TASKING Compiler */ +#define __INLINE inline /*!< inline keyword for TASKING Compiler */ +#define __STATIC_INLINE static inline + +#endif + +/** __FPU_USED indicates whether an FPU is used or not. For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. +*/ +#if defined ( __CC_ARM ) +#if defined __TARGET_FPU_VFP +#if (__FPU_PRESENT == 1) +#define __FPU_USED 1 +#else +#warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" +#define __FPU_USED 0 +#endif +#else +#define __FPU_USED 0 +#endif + +#elif defined ( __ICCARM__ ) +#if defined __ARMVFP__ +#if (__FPU_PRESENT == 1) +#define __FPU_USED 1 +#else +#warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" +#define __FPU_USED 0 +#endif +#else +#define __FPU_USED 0 +#endif + +#elif defined ( __TMS470__ ) +#if defined __TI_VFP_SUPPORT__ +#if (__FPU_PRESENT == 1) +#define __FPU_USED 1 +#else +#warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" +#define __FPU_USED 0 +#endif +#else +#define __FPU_USED 0 +#endif + +#elif defined ( __GNUC__ ) +#if defined (__VFP_FP__) && !defined(__SOFTFP__) +#if (__FPU_PRESENT == 1) +#define __FPU_USED 1 +#else +#warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" +#define __FPU_USED 0 +#endif +#else +#define __FPU_USED 0 +#endif + +#elif defined ( __TASKING__ ) +#if defined __FPU_VFP__ +#if (__FPU_PRESENT == 1) +#define __FPU_USED 1 +#else +#error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" +#define __FPU_USED 0 +#endif +#else +#define __FPU_USED 0 +#endif +#endif + +#include /* standard types definitions */ +#include /* Core Instruction Access */ +#include /* Core Function Access */ +#include /* Compiler specific SIMD Intrinsics */ + +#endif /* __CORE_CM4_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM4_H_DEPENDANT +#define __CORE_CM4_H_DEPENDANT + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES +#ifndef __CM4_REV +#define __CM4_REV 0x0000 +#warning "__CM4_REV not defined in device header file; using default!" +#endif + +#ifndef __FPU_PRESENT +#define __FPU_PRESENT 0 +#warning "__FPU_PRESENT not defined in device header file; using default!" +#endif + +#ifndef __MPU_PRESENT +#define __MPU_PRESENT 0 +#warning "__MPU_PRESENT not defined in device header file; using default!" +#endif + +#ifndef __NVIC_PRIO_BITS +#define __NVIC_PRIO_BITS 4 +#warning "__NVIC_PRIO_BITS not defined in device header file; using default!" +#endif + +#ifndef __Vendor_SysTickConfig +#define __Vendor_SysTickConfig 0 +#warning "__Vendor_SysTickConfig not defined in device header file; using default!" +#endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus +#define __I volatile /*!< Defines 'read only' permissions */ +#else +#define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/*@} end of group Cortex_M4 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + - Core FPU Register + ******************************************************************************/ +/** \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ +#else + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ +#endif + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + + +/** \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + + +/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ +#else + uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ +#endif + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + + +/** \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ + uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/*@} end of group CMSIS_CORE */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IO uint32_t ISER[8]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24]; + __IO uint32_t ICER[8]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[24]; + __IO uint32_t ISPR[8]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24]; + __IO uint32_t ICPR[8]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24]; + __IO uint32_t IABR[8]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56]; + __IO uint8_t IP[240]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644]; + __O uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5]; + __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Registers Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* SCB Hard Fault Status Registers Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1]; + __I uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ + __IO uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ +#define SCnSCB_ACTLR_DISOOFP_Pos 9 /*!< ACTLR: DISOOFP Position */ +#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ + +#define SCnSCB_ACTLR_DISFPCA_Pos 8 /*!< ACTLR: DISFPCA Position */ +#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2 /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1 /*!< ACTLR: DISDEFWBUF Position */ +#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) + \brief Type definitions for the Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __O union + { + __O uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __O uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __O uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864]; + __IO uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15]; + __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15]; + __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ + uint32_t RESERVED3[29]; + __O uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ + __I uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ + __IO uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ + uint32_t RESERVED4[43]; + __O uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ + __I uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ + uint32_t RESERVED5[6]; + __I uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ + __I uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ + __I uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ + __I uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ + __I uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ + __I uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ + __I uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ + __I uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ + __I uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ + __I uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ + __I uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ + __I uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16 /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10 /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3 /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Integration Write Register Definitions */ +#define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */ +#define ITM_IWR_ATVALIDM_Msk (1UL << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */ + +/* ITM Integration Read Register Definitions */ +#define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */ +#define ITM_IRR_ATREADYM_Msk (1UL << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */ + +/* ITM Integration Mode Control Register Definitions */ +#define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */ +#define ITM_IMCR_INTEGRATION_Msk (1UL << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1 /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1UL << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IO uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IO uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IO uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IO uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IO uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IO uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __I uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IO uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + __IO uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ + __IO uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED0[1]; + __IO uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + __IO uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ + __IO uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED1[1]; + __IO uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + __IO uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ + __IO uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED2[1]; + __IO uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + __IO uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ + __IO uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28 /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27 /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26 /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25 /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24 /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22 /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21 /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20 /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19 /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18 /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17 /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16 /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12 /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10 /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9 /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5 /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1 /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0 /*!< DWT CTRL: CYCCNTENA Position */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL << DWT_CTRL_CYCCNTENA_Pos) /*!< DWT CTRL: CYCCNTENA Mask */ + +/* DWT CPI Count Register Definitions */ +#define DWT_CPICNT_CPICNT_Pos 0 /*!< DWT CPICNT: CPICNT Position */ +#define DWT_CPICNT_CPICNT_Msk (0xFFUL << DWT_CPICNT_CPICNT_Pos) /*!< DWT CPICNT: CPICNT Mask */ + +/* DWT Exception Overhead Count Register Definitions */ +#define DWT_EXCCNT_EXCCNT_Pos 0 /*!< DWT EXCCNT: EXCCNT Position */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL << DWT_EXCCNT_EXCCNT_Pos) /*!< DWT EXCCNT: EXCCNT Mask */ + +/* DWT Sleep Count Register Definitions */ +#define DWT_SLEEPCNT_SLEEPCNT_Pos 0 /*!< DWT SLEEPCNT: SLEEPCNT Position */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL << DWT_SLEEPCNT_SLEEPCNT_Pos) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ + +/* DWT LSU Count Register Definitions */ +#define DWT_LSUCNT_LSUCNT_Pos 0 /*!< DWT LSUCNT: LSUCNT Position */ +#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL << DWT_LSUCNT_LSUCNT_Pos) /*!< DWT LSUCNT: LSUCNT Mask */ + +/* DWT Folded-instruction Count Register Definitions */ +#define DWT_FOLDCNT_FOLDCNT_Pos 0 /*!< DWT FOLDCNT: FOLDCNT Position */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL << DWT_FOLDCNT_FOLDCNT_Pos) /*!< DWT FOLDCNT: FOLDCNT Mask */ + +/* DWT Comparator Mask Register Definitions */ +#define DWT_MASK_MASK_Pos 0 /*!< DWT MASK: MASK Position */ +#define DWT_MASK_MASK_Msk (0x1FUL << DWT_MASK_MASK_Pos) /*!< DWT MASK: MASK Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_MATCHED_Pos 24 /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVADDR1_Pos 16 /*!< DWT FUNCTION: DATAVADDR1 Position */ +#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ + +#define DWT_FUNCTION_DATAVADDR0_Pos 12 /*!< DWT FUNCTION: DATAVADDR0 Position */ +#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10 /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_LNK1ENA_Pos 9 /*!< DWT FUNCTION: LNK1ENA Position */ +#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ + +#define DWT_FUNCTION_DATAVMATCH_Pos 8 /*!< DWT FUNCTION: DATAVMATCH Position */ +#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ + +#define DWT_FUNCTION_CYCMATCH_Pos 7 /*!< DWT FUNCTION: CYCMATCH Position */ +#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ + +#define DWT_FUNCTION_EMITRANGE_Pos 5 /*!< DWT FUNCTION: EMITRANGE Position */ +#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ + +#define DWT_FUNCTION_FUNCTION_Pos 0 /*!< DWT FUNCTION: FUNCTION Position */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL << DWT_FUNCTION_FUNCTION_Pos) /*!< DWT FUNCTION: FUNCTION Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IO uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IO uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2]; + __IO uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55]; + __IO uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131]; + __I uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IO uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __I uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ + uint32_t RESERVED3[759]; + __I uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */ + __I uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ + __I uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ + uint32_t RESERVED4[1]; + __I uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ + __I uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ + __IO uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39]; + __IO uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IO uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8]; + __I uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ + __I uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0 /*!< TPI ACPR: PRESCALER Position */ +#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL << TPI_ACPR_PRESCALER_Pos) /*!< TPI ACPR: PRESCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0 /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL << TPI_SPPR_TXMODE_Pos) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3 /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2 /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1 /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0 /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL << TPI_FFSR_FlInProg_Pos) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8 /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_EnFCont_Pos 1 /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI TRIGGER Register Definitions */ +#define TPI_TRIGGER_TRIGGER_Pos 0 /*!< TPI TRIGGER: TRIGGER Position */ +#define TPI_TRIGGER_TRIGGER_Msk (0x1UL << TPI_TRIGGER_TRIGGER_Pos) /*!< TPI TRIGGER: TRIGGER Mask */ + +/* TPI Integration ETM Data Register Definitions (FIFO0) */ +#define TPI_FIFO0_ITM_ATVALID_Pos 29 /*!< TPI FIFO0: ITM_ATVALID Position */ +#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ + +#define TPI_FIFO0_ITM_bytecount_Pos 27 /*!< TPI FIFO0: ITM_bytecount Position */ +#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ + +#define TPI_FIFO0_ETM_ATVALID_Pos 26 /*!< TPI FIFO0: ETM_ATVALID Position */ +#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ + +#define TPI_FIFO0_ETM_bytecount_Pos 24 /*!< TPI FIFO0: ETM_bytecount Position */ +#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ + +#define TPI_FIFO0_ETM2_Pos 16 /*!< TPI FIFO0: ETM2 Position */ +#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ + +#define TPI_FIFO0_ETM1_Pos 8 /*!< TPI FIFO0: ETM1 Position */ +#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ + +#define TPI_FIFO0_ETM0_Pos 0 /*!< TPI FIFO0: ETM0 Position */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL << TPI_FIFO0_ETM0_Pos) /*!< TPI FIFO0: ETM0 Mask */ + +/* TPI ITATBCTR2 Register Definitions */ +#define TPI_ITATBCTR2_ATREADY_Pos 0 /*!< TPI ITATBCTR2: ATREADY Position */ +#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL << TPI_ITATBCTR2_ATREADY_Pos) /*!< TPI ITATBCTR2: ATREADY Mask */ + +/* TPI Integration ITM Data Register Definitions (FIFO1) */ +#define TPI_FIFO1_ITM_ATVALID_Pos 29 /*!< TPI FIFO1: ITM_ATVALID Position */ +#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ + +#define TPI_FIFO1_ITM_bytecount_Pos 27 /*!< TPI FIFO1: ITM_bytecount Position */ +#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ + +#define TPI_FIFO1_ETM_ATVALID_Pos 26 /*!< TPI FIFO1: ETM_ATVALID Position */ +#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ + +#define TPI_FIFO1_ETM_bytecount_Pos 24 /*!< TPI FIFO1: ETM_bytecount Position */ +#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ + +#define TPI_FIFO1_ITM2_Pos 16 /*!< TPI FIFO1: ITM2 Position */ +#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ + +#define TPI_FIFO1_ITM1_Pos 8 /*!< TPI FIFO1: ITM1 Position */ +#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ + +#define TPI_FIFO1_ITM0_Pos 0 /*!< TPI FIFO1: ITM0 Position */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL << TPI_FIFO1_ITM0_Pos) /*!< TPI FIFO1: ITM0 Mask */ + +/* TPI ITATBCTR0 Register Definitions */ +#define TPI_ITATBCTR0_ATREADY_Pos 0 /*!< TPI ITATBCTR0: ATREADY Position */ +#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL << TPI_ITATBCTR0_ATREADY_Pos) /*!< TPI ITATBCTR0: ATREADY Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0 /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x1UL << TPI_ITCTRL_Mode_Pos) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11 /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10 /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9 /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_MinBufSz_Pos 6 /*!< TPI DEVID: MinBufSz Position */ +#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ + +#define TPI_DEVID_AsynClkIn_Pos 5 /*!< TPI DEVID: AsynClkIn Position */ +#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0 /*!< TPI DEVID: NrTraceInput Position */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL << TPI_DEVID_NrTraceInput_Pos) /*!< TPI DEVID: NrTraceInput Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL << TPI_DEVTYPE_SubType_Pos) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 4 /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + +//0 так как эти константы уже есть в заголовочнике K1921BK01T +#if (__MPU_PRESENT == 1) && 0 +/** \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __I uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IO uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IO uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IO uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IO uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IO uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IO uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IO uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IO uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IO uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IO uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +/* MPU Type Register */ +#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register */ +#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register */ +#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register */ +#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register */ +#define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_XN_Pos 28 /*!< MPU RASR: ATTRS.XN Position */ +#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ + +#define MPU_RASR_AP_Pos 24 /*!< MPU RASR: ATTRS.AP Position */ +#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ + +#define MPU_RASR_TEX_Pos 19 /*!< MPU RASR: ATTRS.TEX Position */ +#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ + +#define MPU_RASR_S_Pos 18 /*!< MPU RASR: ATTRS.S Position */ +#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ + +#define MPU_RASR_C_Pos 17 /*!< MPU RASR: ATTRS.C Position */ +#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ + +#define MPU_RASR_B_Pos 16 /*!< MPU RASR: ATTRS.B Position */ +#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ + +#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + +//0 так как эти константы уже есть в заголовочнике K1921BK01T +#if (__FPU_PRESENT == 1) && 0 +/** \ingroup CMSIS_core_register + \defgroup CMSIS_FPU Floating Point Unit (FPU) + \brief Type definitions for the Floating Point Unit (FPU) + @{ + */ + +/** \brief Structure type to access the Floating Point Unit (FPU). + */ +typedef struct +{ + uint32_t RESERVED0[1]; + __IO uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ + __IO uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ + __IO uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ + __I uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ + __I uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ +} FPU_Type; + +/* Floating-Point Context Control Register */ +#define FPU_FPCCR_ASPEN_Pos 31 /*!< FPCCR: ASPEN bit Position */ +#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ + +#define FPU_FPCCR_LSPEN_Pos 30 /*!< FPCCR: LSPEN Position */ +#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ + +#define FPU_FPCCR_MONRDY_Pos 8 /*!< FPCCR: MONRDY Position */ +#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ + +#define FPU_FPCCR_BFRDY_Pos 6 /*!< FPCCR: BFRDY Position */ +#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ + +#define FPU_FPCCR_MMRDY_Pos 5 /*!< FPCCR: MMRDY Position */ +#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ + +#define FPU_FPCCR_HFRDY_Pos 4 /*!< FPCCR: HFRDY Position */ +#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ + +#define FPU_FPCCR_THREAD_Pos 3 /*!< FPCCR: processor mode bit Position */ +#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ + +#define FPU_FPCCR_USER_Pos 1 /*!< FPCCR: privilege level bit Position */ +#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ + +#define FPU_FPCCR_LSPACT_Pos 0 /*!< FPCCR: Lazy state preservation active bit Position */ +#define FPU_FPCCR_LSPACT_Msk (1UL << FPU_FPCCR_LSPACT_Pos) /*!< FPCCR: Lazy state preservation active bit Mask */ + +/* Floating-Point Context Address Register */ +#define FPU_FPCAR_ADDRESS_Pos 3 /*!< FPCAR: ADDRESS bit Position */ +#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ + +/* Floating-Point Default Status Control Register */ +#define FPU_FPDSCR_AHP_Pos 26 /*!< FPDSCR: AHP bit Position */ +#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ + +#define FPU_FPDSCR_DN_Pos 25 /*!< FPDSCR: DN bit Position */ +#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ + +#define FPU_FPDSCR_FZ_Pos 24 /*!< FPDSCR: FZ bit Position */ +#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ + +#define FPU_FPDSCR_RMode_Pos 22 /*!< FPDSCR: RMode bit Position */ +#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ + +/* Media and FP Feature Register 0 */ +#define FPU_MVFR0_FP_rounding_modes_Pos 28 /*!< MVFR0: FP rounding modes bits Position */ +#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ + +#define FPU_MVFR0_Short_vectors_Pos 24 /*!< MVFR0: Short vectors bits Position */ +#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ + +#define FPU_MVFR0_Square_root_Pos 20 /*!< MVFR0: Square root bits Position */ +#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ + +#define FPU_MVFR0_Divide_Pos 16 /*!< MVFR0: Divide bits Position */ +#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ + +#define FPU_MVFR0_FP_excep_trapping_Pos 12 /*!< MVFR0: FP exception trapping bits Position */ +#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ + +#define FPU_MVFR0_Double_precision_Pos 8 /*!< MVFR0: Double-precision bits Position */ +#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ + +#define FPU_MVFR0_Single_precision_Pos 4 /*!< MVFR0: Single-precision bits Position */ +#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ + +#define FPU_MVFR0_A_SIMD_registers_Pos 0 /*!< MVFR0: A_SIMD registers bits Position */ +#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL << FPU_MVFR0_A_SIMD_registers_Pos) /*!< MVFR0: A_SIMD registers bits Mask */ + +/* Media and FP Feature Register 1 */ +#define FPU_MVFR1_FP_fused_MAC_Pos 28 /*!< MVFR1: FP fused MAC bits Position */ +#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ + +#define FPU_MVFR1_FP_HPFP_Pos 24 /*!< MVFR1: FP HPFP bits Position */ +#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ + +#define FPU_MVFR1_D_NaN_mode_Pos 4 /*!< MVFR1: D_NaN mode bits Position */ +#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ + +#define FPU_MVFR1_FtZ_mode_Pos 0 /*!< MVFR1: FtZ mode bits Position */ +#define FPU_MVFR1_FtZ_mode_Msk (0xFUL << FPU_MVFR1_FtZ_mode_Pos) /*!< MVFR1: FtZ mode bits Mask */ + +/*@} end of group CMSIS_FPU */ +#endif + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IO uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __O uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IO uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IO uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register */ +#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register */ +#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Cortex-M4 Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ +#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ +#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if (__MPU_PRESENT == 1) +#define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ +#define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +#if (__FPU_PRESENT == 1) +#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ +#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ +#endif + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions + ******************************************************************************/ +/** \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +/** \brief Set Priority Grouping + + The function sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + + +/** \brief Get Priority Grouping + + The function reads the priority grouping field from the NVIC Interrupt Controller. + + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) +{ + return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ +} + + +/** \brief Enable External Interrupt + + The function enables a device-specific interrupt in the NVIC interrupt controller. + + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ + /* NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); enable interrupt */ + NVIC->ISER[(uint32_t)((int32_t)IRQn) >> 5] = (uint32_t)(1 << ((uint32_t)((int32_t)IRQn) & (uint32_t)0x1F)); /* enable interrupt */ +} + + +/** \brief Disable External Interrupt + + The function disables a device-specific interrupt in the NVIC interrupt controller. + + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ +} + + +/** \brief Get Pending Interrupt + + The function reads the pending register in the NVIC and returns the pending bit + for the specified interrupt. + + \param [in] IRQn Interrupt number. + + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + */ +__STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ +} + + +/** \brief Set Pending Interrupt + + The function sets the pending bit of an external interrupt. + + \param [in] IRQn Interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ +} + + +/** \brief Clear Pending Interrupt + + The function clears the pending bit of an external interrupt. + + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ +} + + +/** \brief Get Active Interrupt + + The function reads the active register in NVIC and returns the active bit. + + \param [in] IRQn Interrupt number. + + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + */ +__STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) +{ + return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ +} + + +/** \brief Set Interrupt Priority + + The function sets the priority of an interrupt. + + \note The priority cannot be set for every core interrupt. + + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + */ +__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if(IRQn < 0) { + SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */ + else { + NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ +} + + +/** \brief Get Interrupt Priority + + The function reads the priority of an interrupt. The interrupt + number can be positive to specify an external (device specific) + interrupt, or negative to specify an internal (core) interrupt. + + + \param [in] IRQn Interrupt number. + \return Interrupt Priority. Value is aligned automatically to the implemented + priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if(IRQn < 0) { + return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */ + else { + return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ +} + + +/** \brief Encode Priority + + The function encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the samllest possible priority group is set. + + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + return ( + ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | + ((SubPriority & ((1 << (SubPriorityBits )) - 1))) + ); +} + + +/** \brief Decode Priority + + The function decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1); + *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); +} + + +/** \brief System Reset + + The function initiates a system reset request to reset the MCU. + */ +__STATIC_INLINE void NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + while(1); /* wait until reset */ +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if (__Vendor_SysTickConfig == 0) + +/** \brief System Tick Configuration + + The function initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + + \param [in] ticks Number of ticks between two interrupts. + + \return 0 Function succeeded. + \return 1 Function failed. + + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + + SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions ITM Functions + \brief Functions that access the ITM debug interface. + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ +#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** \brief ITM Send Character + + The function transmits a character via the ITM channel 0, and + \li Just returns when no debugger is connected that has booked the output. + \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. + + \param [in] ch Character to transmit. + + \returns Character to transmit. + */ +__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if ((ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ + (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0].u32 == 0); + ITM->PORT[0].u8 = (uint8_t) ch; + } + return (ch); +} + + +/** \brief ITM Receive Character + + The function inputs a character via the external variable \ref ITM_RxBuffer. + + \return Received character. + \return -1 No character pending. + */ +__STATIC_INLINE int32_t ITM_ReceiveChar (void) { + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** \brief ITM Check Character + + The function checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. + + \return 0 No character available. + \return 1 Character available. + */ +__STATIC_INLINE int32_t ITM_CheckChar (void) { + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) { + return (0); /* no character available */ + } else { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + +#endif /* __CORE_CM4_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ + +#ifdef __cplusplus +} +#endif + diff --git a/include/core_cm4_simd.h b/include/core_cm4_simd.h new file mode 100644 index 0000000..c1678b9 --- /dev/null +++ b/include/core_cm4_simd.h @@ -0,0 +1,650 @@ +/**************************************************************************//** + * @file core_cm4_simd.h + * @brief CMSIS Cortex-M4 SIMD Header File + * @version V3.01 + * @date 06. March 2012 + * + * @note + * Copyright (C) 2010-2012 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef __CORE_CM4_SIMD_H +#define __CORE_CM4_SIMD_H + + +/******************************************************************************* + * Hardware Abstraction Layer + ******************************************************************************/ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/ +#define __SADD8 __sadd8 +#define __QADD8 __qadd8 +#define __SHADD8 __shadd8 +#define __UADD8 __uadd8 +#define __UQADD8 __uqadd8 +#define __UHADD8 __uhadd8 +#define __SSUB8 __ssub8 +#define __QSUB8 __qsub8 +#define __SHSUB8 __shsub8 +#define __USUB8 __usub8 +#define __UQSUB8 __uqsub8 +#define __UHSUB8 __uhsub8 +#define __SADD16 __sadd16 +#define __QADD16 __qadd16 +#define __SHADD16 __shadd16 +#define __UADD16 __uadd16 +#define __UQADD16 __uqadd16 +#define __UHADD16 __uhadd16 +#define __SSUB16 __ssub16 +#define __QSUB16 __qsub16 +#define __SHSUB16 __shsub16 +#define __USUB16 __usub16 +#define __UQSUB16 __uqsub16 +#define __UHSUB16 __uhsub16 +#define __SASX __sasx +#define __QASX __qasx +#define __SHASX __shasx +#define __UASX __uasx +#define __UQASX __uqasx +#define __UHASX __uhasx +#define __SSAX __ssax +#define __QSAX __qsax +#define __SHSAX __shsax +#define __USAX __usax +#define __UQSAX __uqsax +#define __UHSAX __uhsax +#define __USAD8 __usad8 +#define __USADA8 __usada8 +#define __SSAT16 __ssat16 +#define __USAT16 __usat16 +#define __UXTB16 __uxtb16 +#define __UXTAB16 __uxtab16 +#define __SXTB16 __sxtb16 +#define __SXTAB16 __sxtab16 +#define __SMUAD __smuad +#define __SMUADX __smuadx +#define __SMLAD __smlad +#define __SMLADX __smladx +#define __SMLALD __smlald +#define __SMLALDX __smlaldx +#define __SMUSD __smusd +#define __SMUSDX __smusdx +#define __SMLSD __smlsd +#define __SMLSDX __smlsdx +#define __SMLSLD __smlsld +#define __SMLSLDX __smlsldx +#define __SEL __sel +#define __QADD __qadd +#define __QSUB __qsub + +#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ + ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) + +#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ + ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) + + +/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ + + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/ +#include + +/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ + + + +#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/ +/* TI CCS specific functions */ + +/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/ +#include + +/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ + + + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SSAT16(ARG1,ARG2) \ + ({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ +}) + +#define __USAT16(ARG1,ARG2) \ + ({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ +}) + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SMLALD(ARG1,ARG2,ARG3) \ + ({ \ + uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ + (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ +}) + +#define __SMLALDX(ARG1,ARG2,ARG3) \ + ({ \ + uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ + (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ +}) + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SMLSLD(ARG1,ARG2,ARG3) \ + ({ \ + uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ + (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ +}) + +#define __SMLSLDX(ARG1,ARG2,ARG3) \ + ({ \ + uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ + (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ +}) + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SEL (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +#define __PKHBT(ARG1,ARG2,ARG3) \ + ({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ +}) + +#define __PKHTB(ARG1,ARG2,ARG3) \ + ({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + if (ARG3 == 0) \ + __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ + else \ + __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ +}) + +/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ + + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ + + +/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/ +/* not yet supported */ +/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ + + +#endif + +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#endif /* __CORE_CM4_SIMD_H */ + +#ifdef __cplusplus +} +#endif + diff --git a/include/core_cmFunc.h b/include/core_cmFunc.h new file mode 100644 index 0000000..8b77c85 --- /dev/null +++ b/include/core_cmFunc.h @@ -0,0 +1,617 @@ +/**************************************************************************//** + * @file core_cmFunc.h + * @brief CMSIS Cortex-M Core Function Access Header File + * @version V3.01 + * @date 06. March 2012 + * + * @note + * Copyright (C) 2009-2012 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifndef __CORE_CMFUNC_H +#define __CORE_CMFUNC_H + + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#if (__ARMCC_VERSION < 400677) +#error "Please use ARM Compiler Toolchain V4.0.677 or later!" +#endif + +/* intrinsic void __enable_irq(); */ +/* intrinsic void __disable_irq(); */ + +/** \brief Get Control Register + + This function returns the content of the Control Register. + + \return Control Register value + */ +__STATIC_INLINE uint32_t __get_CONTROL(void) +{ + register uint32_t __regControl __ASM("control"); + return(__regControl); +} + + +/** \brief Set Control Register + + This function writes the given value to the Control Register. + + \param [in] control Control Register value to set + */ +__STATIC_INLINE void __set_CONTROL(uint32_t control) +{ + register uint32_t __regControl __ASM("control"); + __regControl = control; +} + + +/** \brief Get IPSR Register + + This function returns the content of the IPSR Register. + + \return IPSR Register value + */ +__STATIC_INLINE uint32_t __get_IPSR(void) +{ + register uint32_t __regIPSR __ASM("ipsr"); + return(__regIPSR); +} + + +/** \brief Get APSR Register + + This function returns the content of the APSR Register. + + \return APSR Register value + */ +__STATIC_INLINE uint32_t __get_APSR(void) +{ + register uint32_t __regAPSR __ASM("apsr"); + return(__regAPSR); +} + + +/** \brief Get xPSR Register + + This function returns the content of the xPSR Register. + + \return xPSR Register value + */ +__STATIC_INLINE uint32_t __get_xPSR(void) +{ + register uint32_t __regXPSR __ASM("xpsr"); + return(__regXPSR); +} + + +/** \brief Get Process Stack Pointer + + This function returns the current value of the Process Stack Pointer (PSP). + + \return PSP Register value + */ +__STATIC_INLINE uint32_t __get_PSP(void) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + return(__regProcessStackPointer); +} + + +/** \brief Set Process Stack Pointer + + This function assigns the given value to the Process Stack Pointer (PSP). + + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + __regProcessStackPointer = topOfProcStack; +} + + +/** \brief Get Main Stack Pointer + + This function returns the current value of the Main Stack Pointer (MSP). + + \return MSP Register value + */ +__STATIC_INLINE uint32_t __get_MSP(void) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + return(__regMainStackPointer); +} + + +/** \brief Set Main Stack Pointer + + This function assigns the given value to the Main Stack Pointer (MSP). + + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + __regMainStackPointer = topOfMainStack; +} + + +/** \brief Get Priority Mask + + This function returns the current state of the priority mask bit from the Priority Mask Register. + + \return Priority Mask value + */ +__STATIC_INLINE uint32_t __get_PRIMASK(void) +{ + register uint32_t __regPriMask __ASM("primask"); + return(__regPriMask); +} + + +/** \brief Set Priority Mask + + This function assigns the given value to the Priority Mask Register. + + \param [in] priMask Priority Mask + */ +__STATIC_INLINE void __set_PRIMASK(uint32_t priMask) +{ + register uint32_t __regPriMask __ASM("primask"); + __regPriMask = (priMask); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Enable FIQ + + This function enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq + + +/** \brief Disable FIQ + + This function disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq + + +/** \brief Get Base Priority + + This function returns the current value of the Base Priority register. + + \return Base Priority register value + */ +__STATIC_INLINE uint32_t __get_BASEPRI(void) +{ + register uint32_t __regBasePri __ASM("basepri"); + return(__regBasePri); +} + + +/** \brief Set Base Priority + + This function assigns the given value to the Base Priority register. + + \param [in] basePri Base Priority value to set + */ +__STATIC_INLINE void __set_BASEPRI(uint32_t basePri) +{ + register uint32_t __regBasePri __ASM("basepri"); + __regBasePri = (basePri & 0xff); +} + + +/** \brief Get Fault Mask + + This function returns the current value of the Fault Mask register. + + \return Fault Mask register value + */ +__STATIC_INLINE uint32_t __get_FAULTMASK(void) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + return(__regFaultMask); +} + + +/** \brief Set Fault Mask + + This function assigns the given value to the Fault Mask register. + + \param [in] faultMask Fault Mask value to set + */ +__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + __regFaultMask = (faultMask & (uint32_t)1); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + +#if (__CORTEX_M == 0x04) + +/** \brief Get FPSCR + + This function returns the current value of the Floating Point Status/Control register. + + \return Floating Point Status/Control register value + */ +__STATIC_INLINE uint32_t __get_FPSCR(void) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + register uint32_t __regfpscr __ASM("fpscr"); + return(__regfpscr); +#else + return(0); +#endif +} + + +/** \brief Set FPSCR + + This function assigns the given value to the Floating Point Status/Control register. + + \param [in] fpscr Floating Point Status/Control value to set + */ +__STATIC_INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + register uint32_t __regfpscr __ASM("fpscr"); + __regfpscr = (fpscr); +#endif +} + +#endif /* (__CORTEX_M == 0x04) */ + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#include + + +#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/ +/* TI CCS specific functions */ + +#include + + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** \brief Enable IRQ Interrupts + + This function enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_irq(void) +{ + __ASM volatile ("cpsie i"); +} + + +/** \brief Disable IRQ Interrupts + + This function disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_irq(void) +{ + __ASM volatile ("cpsid i"); +} + + +/** \brief Get Control Register + + This function returns the content of the Control Register. + + \return Control Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +/** \brief Set Control Register + + This function writes the given value to the Control Register. + + \param [in] control Control Register value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) ); +} + + +/** \brief Get IPSR Register + + This function returns the content of the IPSR Register. + + \return IPSR Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get APSR Register + + This function returns the content of the APSR Register. + + \return APSR Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get xPSR Register + + This function returns the content of the xPSR Register. + + \return xPSR Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get Process Stack Pointer + + This function returns the current value of the Process Stack Pointer (PSP). + + \return PSP Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, psp\n" : "=r" (result) ); + return(result); +} + + +/** \brief Set Process Stack Pointer + + This function assigns the given value to the Process Stack Pointer (PSP). + + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) ); +} + + +/** \brief Get Main Stack Pointer + + This function returns the current value of the Main Stack Pointer (MSP). + + \return MSP Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, msp\n" : "=r" (result) ); + return(result); +} + + +/** \brief Set Main Stack Pointer + + This function assigns the given value to the Main Stack Pointer (MSP). + + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) ); +} + + +/** \brief Get Priority Mask + + This function returns the current state of the priority mask bit from the Priority Mask Register. + + \return Priority Mask value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +/** \brief Set Priority Mask + + This function assigns the given value to the Priority Mask Register. + + \param [in] priMask Priority Mask + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) ); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Enable FIQ + + This function enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_fault_irq(void) +{ + __ASM volatile ("cpsie f"); +} + + +/** \brief Disable FIQ + + This function disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_fault_irq(void) +{ + __ASM volatile ("cpsid f"); +} + + +/** \brief Get Base Priority + + This function returns the current value of the Base Priority register. + + \return Base Priority register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); + return(result); +} + + +/** \brief Set Base Priority + + This function assigns the given value to the Base Priority register. + + \param [in] basePri Base Priority value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI(uint32_t value) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (value) ); +} + + +/** \brief Get Fault Mask + + This function returns the current value of the Fault Mask register. + + \return Fault Mask register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +/** \brief Set Fault Mask + + This function assigns the given value to the Fault Mask register. + + \param [in] faultMask Fault Mask value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) ); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + +#if (__CORTEX_M == 0x04) + +/** \brief Get FPSCR + + This function returns the current value of the Floating Point Status/Control register. + + \return Floating Point Status/Control register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FPSCR(void) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + uint32_t result; + + __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); + return(result); +#else + return(0); +#endif +} + + +/** \brief Set FPSCR + + This function assigns the given value to the Floating Point Status/Control register. + + \param [in] fpscr Floating Point Status/Control value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) ); +#endif +} + +#endif /* (__CORTEX_M == 0x04) */ + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all instrinsics, + * Including the CMSIS ones. + */ + +#endif + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +#endif /* __CORE_CMFUNC_H */ + diff --git a/include/core_cmInstr.h b/include/core_cmInstr.h new file mode 100644 index 0000000..e5fd9a8 --- /dev/null +++ b/include/core_cmInstr.h @@ -0,0 +1,619 @@ +/**************************************************************************//** + * @file core_cmInstr.h + * @brief CMSIS Cortex-M Core Instruction Access Header File + * @version V3.01 + * @date 06. March 2012 + * + * @note + * Copyright (C) 2009-2012 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifndef __CORE_CMINSTR_H +#define __CORE_CMINSTR_H + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#if (__ARMCC_VERSION < 400677) +#error "Please use ARM Compiler Toolchain V4.0.677 or later!" +#endif + + +/** \brief No Operation + + No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __nop + + +/** \brief Wait For Interrupt + + Wait For Interrupt is a hint instruction that suspends execution + until one of a number of events occurs. + */ +#define __WFI __wfi + + +/** \brief Wait For Event + + Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE __wfe + + +/** \brief Send Event + + Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __sev + + +/** \brief Instruction Synchronization Barrier + + Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or + memory, after the instruction has been completed. + */ +#define __ISB() __isb(0xF) + + +/** \brief Data Synchronization Barrier + + This function acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() __dsb(0xF) + + +/** \brief Data Memory Barrier + + This function ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() __dmb(0xF) + + +/** \brief Reverse byte order (32 bit) + + This function reverses the byte order in integer value. + + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV __rev + + +/** \brief Reverse byte order (16 bit) + + This function reverses the byte order in two unsigned short values. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value) +{ + rev16 r0, r0 + bx lr +} + + +/** \brief Reverse byte order in signed short value + + This function reverses the byte order in a signed short value with sign extension to integer. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(int32_t value) +{ + revsh r0, r0 + bx lr +} + + +/** \brief Rotate Right in unsigned value (32 bit) + + This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + + \param [in] value Value to rotate + \param [in] value Number of Bits to rotate + \return Rotated value + */ +#define __ROR __ror + + +#if (__CORTEX_M >= 0x03) + +/** \brief Reverse bit order of value + + This function reverses the bit order of the given value. + + \param [in] value Value to reverse + \return Reversed value + */ +#define __RBIT __rbit + + +/** \brief LDR Exclusive (8 bit) + + This function performs a exclusive LDR command for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) + + +/** \brief LDR Exclusive (16 bit) + + This function performs a exclusive LDR command for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) + + +/** \brief LDR Exclusive (32 bit) + + This function performs a exclusive LDR command for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) + + +/** \brief STR Exclusive (8 bit) + + This function performs a exclusive STR command for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXB(value, ptr) __strex(value, ptr) + + +/** \brief STR Exclusive (16 bit) + + This function performs a exclusive STR command for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXH(value, ptr) __strex(value, ptr) + + +/** \brief STR Exclusive (32 bit) + + This function performs a exclusive STR command for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXW(value, ptr) __strex(value, ptr) + + +/** \brief Remove the exclusive lock + + This function removes the exclusive lock which is created by LDREX. + + */ +#define __CLREX __clrex + + +/** \brief Signed Saturate + + This function saturates a signed value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT __ssat + + +/** \brief Unsigned Saturate + + This function saturates an unsigned value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT __usat + + +/** \brief Count leading zeros + + This function counts the number of leading zeros of a data value. + + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +#define __CLZ __clz + +#endif /* (__CORTEX_M >= 0x03) */ + + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#include + + +#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/ +/* TI CCS specific functions */ + +#include + + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** \brief No Operation + + No Operation does nothing. This instruction can be used for code alignment purposes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __NOP(void) +{ + __ASM volatile ("nop"); +} + + +/** \brief Wait For Interrupt + + Wait For Interrupt is a hint instruction that suspends execution + until one of a number of events occurs. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFI(void) +{ + __ASM volatile ("wfi"); +} + + +/** \brief Wait For Event + + Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFE(void) +{ + __ASM volatile ("wfe"); +} + + +/** \brief Send Event + + Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __SEV(void) +{ + __ASM volatile ("sev"); +} + + +/** \brief Instruction Synchronization Barrier + + Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or + memory, after the instruction has been completed. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __ISB(void) +{ + __ASM volatile ("isb"); +} + + +/** \brief Data Synchronization Barrier + + This function acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __DSB(void) +{ + __ASM volatile ("dsb"); +} + + +/** \brief Data Memory Barrier + + This function ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __DMB(void) +{ + __ASM volatile ("dmb"); +} + + +/** \brief Reverse byte order (32 bit) + + This function reverses the byte order in integer value. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief Reverse byte order (16 bit) + + This function reverses the byte order in two unsigned short values. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief Reverse byte order in signed short value + + This function reverses the byte order in a signed short value with sign extension to integer. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value) +{ + uint32_t result; + + __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief Rotate Right in unsigned value (32 bit) + + This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + + \param [in] value Value to rotate + \param [in] value Number of Bits to rotate + \return Rotated value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +{ + + __ASM volatile ("ror %0, %0, %1" : "+r" (op1) : "r" (op2) ); + return(op1); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Reverse bit order of value + + This function reverses the bit order of the given value. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief LDR Exclusive (8 bit) + + This function performs a exclusive LDR command for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr) +{ + uint8_t result; + + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief LDR Exclusive (16 bit) + + This function performs a exclusive LDR command for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr) +{ + uint16_t result; + + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief LDR Exclusive (32 bit) + + This function performs a exclusive LDR command for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief STR Exclusive (8 bit) + + This function performs a exclusive STR command for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexb %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief STR Exclusive (16 bit) + + This function performs a exclusive STR command for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexh %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief STR Exclusive (32 bit) + + This function performs a exclusive STR command for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("strex %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief Remove the exclusive lock + + This function removes the exclusive lock which is created by LDREX. + + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void) +{ + __ASM volatile ("clrex"); +} + + +/** \brief Signed Saturate + + This function saturates a signed value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT(ARG1,ARG2) \ + ({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** \brief Unsigned Saturate + + This function saturates an unsigned value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT(ARG1,ARG2) \ + ({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** \brief Count leading zeros + + This function counts the number of leading zeros of a data value. + + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __CLZ(uint32_t value) +{ + uint8_t result; + + __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + +#endif + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + +#endif /* __CORE_CMINSTR_H */ + diff --git a/include/system_K1921VK035.h b/include/system_K1921VK035.h new file mode 100644 index 0000000..8cddbfd --- /dev/null +++ b/include/system_K1921VK035.h @@ -0,0 +1,53 @@ +/*============================================================================== + * Инициализация К1921ВК035 + *------------------------------------------------------------------------------ + * НИИЭТ, Богдан Колбов + *============================================================================== + * ДАННОЕ ПРОГРАММНОЕ ОБЕСПЕЧЕНИЕ ПРЕДОСТАВЛЯЕТСЯ «КАК ЕСТЬ», БЕЗ КАКИХ-ЛИБО + * ГАРАНТИЙ, ЯВНО ВЫРАЖЕННЫХ ИЛИ ПОДРАЗУМЕВАЕМЫХ, ВКЛЮЧАЯ ГАРАНТИИ ТОВАРНОЙ + * ПРИГОДНОСТИ, СООТВЕТСТВИЯ ПО ЕГО КОНКРЕТНОМУ НАЗНАЧЕНИЮ И ОТСУТСТВИЯ + * НАРУШЕНИЙ, НО НЕ ОГРАНИЧИВАЯСЬ ИМИ. ДАННОЕ ПРОГРАММНОЕ ОБЕСПЕЧЕНИЕ + * ПРЕДНАЗНАЧЕНО ДЛЯ ОЗНАКОМИТЕЛЬНЫХ ЦЕЛЕЙ И НАПРАВЛЕНО ТОЛЬКО НА + * ПРЕДОСТАВЛЕНИЕ ДОПОЛНИТЕЛЬНОЙ ИНФОРМАЦИИ О ПРОДУКТЕ, С ЦЕЛЬЮ СОХРАНИТЬ ВРЕМЯ + * ПОТРЕБИТЕЛЮ. НИ В КАКОМ СЛУЧАЕ АВТОРЫ ИЛИ ПРАВООБЛАДАТЕЛИ НЕ НЕСУТ + * ОТВЕТСТВЕННОСТИ ПО КАКИМ-ЛИБО ИСКАМ, ЗА ПРЯМОЙ ИЛИ КОСВЕННЫЙ УЩЕРБ, ИЛИ + * ПО ИНЫМ ТРЕБОВАНИЯМ, ВОЗНИКШИМ ИЗ-ЗА ИСПОЛЬЗОВАНИЯ ПРОГРАММНОГО ОБЕСПЕЧЕНИЯ + * ИЛИ ИНЫХ ДЕЙСТВИЙ С ПРОГРАММНЫМ ОБЕСПЕЧЕНИЕМ. + * + * 2018 АО "НИИЭТ" + *============================================================================== + */ + +#ifndef SYSTEM_K1921VK035_H +#define SYSTEM_K1921VK035_H + +#ifdef __cplusplus +extern "C" { +#endif + +//-- Includes ------------------------------------------------------------------ +#include + +//-- Defines ------------------------------------------------------------------- +#define OSICLK_VAL 8000000 +#ifndef OSECLK_VAL +#define OSECLK_VAL 12000000 +#endif +#define OSECLK_STARTUP_TIMEOUT 0x100000 +#define SYSCLK_SWITCH_TIMEOUT 0x100000 + +#define SYSCLK_PLL // Использовать PLL для тактирования +//-- Variables ----------------------------------------------------------------- +extern uint32_t SystemCoreClock; // System Clock Frequency (Core Clock) + +//-- Functions ----------------------------------------------------------------- +// Initialize the System +extern void SystemInit(void); +// Updates the SystemCoreClock with current core Clock retrieved from registers +extern void SystemCoreClockUpdate(void); + +#ifdef __cplusplus +} +#endif + +#endif // SYSTEM_K1921VK035_H diff --git a/lib/libCANOpen_drv.a b/lib/libCANOpen_drv.a new file mode 100644 index 0000000000000000000000000000000000000000..ea4292cf22dce7b17bde23a32dbbdc99392c8b16 GIT binary patch literal 371844 zcmeFadt6n;`aeGFve|0^;+BobRX2O9sbq0+qopM`x8fxX)J!b_MbT6Uu&gXGyI|?b zq>F+TmFHAm5wVk{N$DvotBsKd)6=0cF|7`W)XMtg@BPfIjcAwe=ll77|M>l0ub;hU z&AgxInP+C6nR#Z`%-R$)BDZ)}!S()EJ1+ef?@o#zI%G&({51|o9A|ZXIvfe{Lz6^~ z9Dl}GK4aQ}|3Cb{#0F~g7KSjZaAsP{4e=Q_Od7Q)H*Y~cyGTf%SK_10&Yx8{JKs}S zyfC+vB<9RpG&?grW6|vVB?RZ@mu9AqnwVRhyKsE|qPe97Ch>;F3-dDPWG~L+lKCZ< z$!0-o@$5@-q%AHk&R<^{ z8gj7&E|6BZs3gDm4zB2OfjQK)>?|TL%$>I&uW-rC;{4p%giG=l&7QfiWUengW>iYn zq|{LqGv!RmO~vy{`A|jHltm?X<`<*FsNB4Ks$AB*xdo-! z1@q>V&RaBhX3~(nd8KT8{+!E6D0yOf=EB^fB8X)yf{VB{H#+H;T85KVm>qw{cs{$uFjgW=&x#NcvGNW)TDH;&0&G0dxl-aZSC??mKH$Q(?X~v>Cg=|9Z+4}ArIYNahIEoPG!VbadZ zFDc2NP3>^?;uuUO`We8^vU?F(1`T347QU+h6rI*zfjc(oLH8zeynCvyqd>rJhAUO&-I?tNcGC2#~WG#3L?w1lV9lgB6aY!5$S7d zD+2m>E0}UFIc;YL%Z&8y>`2ax@McR5YGkeYDU02*&(EPdibe;^EH=1S{frITvQKwd zK%tbMLq$qKpqS)PzkXUlKtW1*WO;(ogH26-vEz%h!NbGQTE#zXAA?NMF4fb`6Y9C} zQPZgHZZyM z>#~77hce7>KuXiUPq9`tC3i(~@@AF@+io=C5(jyxMO3SeMuHMskN|pcr`7H0Rka(9 zq(o}tMq@}~9nz8hHgBV`#XSh+CmPPUjYfK+4=ZQxS4h$WN=?7Sf<|Lw&*>4tDu+kA48msIP#JATQ2tG$RB2GmtM>^9If4C#vVp^7a;(y=|#+23e%AmcJfQ; z+QXXs`#l_(AbQw8q0R_Q_-zkIC0yRa5up5D5BE;!W?JKaw`9@7!3n+|{-5O!LrX69 z@c&FlFxRos2qLSX2W$zx9{!){6Ls2XkY3Ukf|z=k^ivOqBBmZ@`{L@nMtzpoIN(%0 z4ZFR@AtyX-LS<^E7wH5wu^vzI3dG5RUr1Hz4Q~SLNGxU@LrUWIkWYe!V9K>VbqMBZ zJ#rnu6Q0Tq6bzqpCPg`59H9Q|Nqo#vOC+D8@qCUR#26TnP*wZJjyi*;5wmfiXRDzy;Xk(;er&Iy#_cuy9F?hkj*^VvtlM!h z-H85D&Lpz~hF4DX4DvA8N~zg%FJ9 z8XJgpQfXB_Zan%q!`yJ!8Rz=ZOgn(NCuWgv?on&hjv-6bj>J0}!Hq2c`x*Plk1;>I zkUZqPd?np#_+xbV$L%^(F*3PzcbUk8z06EM%+x~(5#_08C8aV|Zjf9XjY`Z{(z&xk zp2=D(%P41+n%wplr5wTM%CeGMf8tc7wYx&CB#Hg)ik;d`bvRZ|cG!zO2*#xiX!M8Ak1<+(3n zlu-Xxn@xKDOrZ2QhlBs0WSD-Y30^_P`l`_=Sfp#JIIVLoVe)*wa z0!9P%kkN0jnL6KZfSLNGpQ|Ocb9W;RSa$B#?bIve#VS*^eUeLXwS6=;Xa^MUS#HkQ z<)cRIV=kiaMW9hK^4y7SG*?MZYavV9&y~%j*wwJVJ;f!(+PxJ!D!m-te%8>`t6EkD5 z=FQ(7Kr`bp-+bsgGqkn~*X(XnyE`yD!doruAo~vsm9CR~GejQjnhg^kTdL5~)Mlf1TYtf~%DDiIf?5dl@h<^>UXx^X9qTcA0-h37fg_M{h ze>8_k(teJir+UXFx8^Muy+-Nm<)YtMYxr^&%P^N@Je!yQUjIezpx#r^dsOd>BWRlE zMvNF5K~a1J-RP0lh%q8ntwKjB8pC(^ju zYlNa@Ar6`s6{*Rs?=F`x2E*dM{G!g-(`m&w-P2p@jQURewmaJ#@jvvt*b9N^(O|DM zc-grz+v|)2ozm~PM^O&YvIcSz0l%VTN?r2-4_}|&}fhbNLAl7e9OIp zC@s15i89&sa?3H5wXG^s{+D%!PrXDx%>l7i*!T<*YX$jmk_(E;!uECx}9w_$z zhZ0z8d6_bhwXQCc2I>tp+~Zbb4A+<*m-_HG9{233DVFV-t*RzG=x+Gj@qglTgHiin z?sI!#gusho3{K(xOnB5_c+^py9<@97sNZmp+6x|4_)P4R?iMRAc1^`T&uKF~=L&P} zU16@hG)8UQUdgRxC@CoJ;(mel1hl4fYYW1@%;!hr_zbr4HLQkvOkssL-S=Q;OCD3; zx7{Tz!iw;iomPa$90-p&aM`(n?KRwE3h8&;Gmx7+roivJCjpbk6!;_ecvBlZ=I>}r zfj07(Li(`Vjojoh1wP^)3``zV;LqIsOl|O(zoRVz+Q?%H>CfFk$W0zo;4j^Nz~nIn zKI#7Tq-ZHT=I>~0-&VstrjS1EZaG=QJ*L3lyZ;SL9#i16?tjAncJT&rk?;nV3iQBY z;X_3aT<$|@O{4x3el95Phd8ergx-Wda${ZrX3*PS)&D-?d>+3 zoE0HFBT+Bs*!eE`BBu+!!~)&g{P?*2GpnIa)$j@k{?)gf^m(Bx&?9PsG@Rbi)Yt&= zt`gAQ-it{wWS7iyENvqsiuMZp1K#V1e%6e??|l2JG5mt*4V1WpJT-tARF4cqf!DjYx zU8t>llbI%2QIB8Z_ZrN0taetrRoaSFjj=K2HjmuVoEOBcs?^+Ks6Ts+zAow7dORuR z+?_g)(y-vZqS51e-xr(T)MsF3tE7ZBNrRO0QhQ*7*LbZ*Kw7==T0BxQUgKcA9q3>@ zok=%wP7~522li@mTyrtc9?sc=JQNPaP@Y3P&vDK? z&S^$Er;GdnPCWow3XNR8k;|XpoD)d*8K^g*p7D}XJ}zy@v3(~?wgH20tupNPrnLOTJP4YuFdgE?swN={1eJ!Ru3Bz<=Ej*&L0 ze0(bFCFfi152cWlIJvOI26&gn26@%k9u3NR#<^lF>&wqIs!a11(HF6}f*jpMz4V&UG*6nzYuC;3B$XA~eJw#2qd41N=8c<>p>;->`Z);Iq=UbM! z46HE2lGcs>rlo}HlU&$tRZ)5}+o1NJ(>^+cJ;62psbJkD=lp%AvG(K8M6o8md`y<8N}ZSOOSRn(dOlB^=? zE#9shQQxkoBaiXZ5r+5cM_PiHP`~E!lIb*6jmyUfp))O7Z}T}_tgwRa7pL@lxn;V= z-e|{pmx|r9-$c3Jb1gUT#=8!y$2$kT=e!qTFMl){CtoRxTkHi=#bYgu$$mYU?pI@E zB}S@_#u{T1_UT{kt}&*%l4CGN#&7X8KeYRu8U=@=0XJ9+Z#Jtai0adIdZprzfVh%J8XEG54k>l9!*F zXx1YU^}u{1Jf66AJ_30?YK$9D|7z5x#+b-cw_<)za^d!q_1P8GIhUx8$7(Oc4r!38 z_P3|nmDqUrOE>!5*+AtHO^)r?P-l#FkwkY_MQU%L@rhC;=3ikL#uS~2ZA5u={za*Y ziFMGboLh#yM;1?~@qI{EBE#I9lt{DEr(25k!q1H*E21pY{vTM0x5h>KPc_I@Sz{|w zS?kkf1DamwNKQz;wj%XbudV3@P)B*?HYvCwbv#DQr6vBFnB44vM7CG%U?F9ij%w^As+sk5q@oEK*^UArv99zNuHizZqWJkJ|)1x2;X9C}~ z2>E~lJLCgQd0PR4d`OPQRSD?CO5_M_w_)vD>tQlWNS zQ^NYo6_%=JaYA-~8FSh_>bl2km#5aZrY%p7O+M>cKD;2U^@6ginRU#C<`8I}G^zpn z-rInpfM$%sU0X*XP+y?gqxJ)p09^^RVALL0WAYc2YO)C zOD&yk3F;Z;8WcZ_on18sZMhk3nM`f@_{McD?Cb{6LO`1|`5e#|peUdjlfMJn1JoC2 z_T-a5hk&jGS}^(FK*xcG0F_Q|0{Rwc1klpSXv^7OfYN~;nEbx^#&k-YCl?JbhzJ}x zsL%QPe~xKlt}!@Q8VJAH&+x0+JlzpnzR%&Zobi*(_ifJZQEtb(m6SF-NA0+_SYGe* z(5K9MqEoV*G`3}byVa#s_-(RozS&%RtegEdDeI|E{Hh|$r;oCEnQM5?>upl^WZY9o zm32m5qI9kQdHKBSw7>sGBk#qv&DKqRuL%80)wnEq<`DOa7!>_`>__c5o`;x;9fB4o_E{3UxBr9aw|r!@B1P; zn|K3um-%=+)v!*boznhxmJr?e!fv`LP_U0*FgDmw%2<^&oMe+*2QIh9hVplCd+b&5 zLxx^^9o^xC?8|I*Xql}x?VFZhnm#?Ne$bVWY`@_o1{eT zTa!*LRAbv3UTaJ4o^X`vnw4=SG{0q-g&u4fp_52gh2Rw~< zj-S$i=cFkg;W=Z<2YAk&auCl2Q~rTx>6EweTsmbRo)1jf(}MfGd&Fr-6a2<2Do#Qi z|7d54MU5zr>tCo{>W4zZzSx8tPN zhSMXP1v^G5WhI@)bG$rRr2herLOV&wOnm-~5@aIu$@V*UABkW?vESu-Mo-fr*C-=XDZ=@q_) zVjm__Keb3qwb*v4E*1BMjIXc`kLr@Uq!lx*x*{;kF3MQC$iUQ{d97X2nwgfIJ&;$W z(~t{7zgW#FtvJn07}f;?Fv8N5^Io-o!f7Dv{zLV=so?nyf69vY7JJS$34~rd&)8EquAdhx4mCx z<@UE$sTj}tI!i@;`$K80LWk$-+#L)Vo|-Z7rdw6)bkwtf9?aFztlw0lCrd3?`01u! z1yJ1G;VgDS!#&e2n^dfovYTwC4L*&%cmE_>MObS^8T4L*H#4@o&Dx!veYEV~r}Wkb zS3UkzRrOytso3wRXG5TW(r9=A?03|&Q9v_BzYA0d)E8*>=z5?MpeunEjNT1&C(sa} z($Td*_W+FmS~_|&&@!NOpa({8Y`JIpzYJS*Rjn;n@;YJz8$L9`n*FMjGP)IV#LD}y z9|%kXdZy*}=}CsArer$ZYt&+Gr&J)N>iw#u3i2jtI0d3NiT!Oh<;64pigZ4pZGAG` zJ_$;ol7hXYv_9svqWD$V%X^eVWA(p`uzKuIl_2omYI8^*B-7eB7T+`YRqV#Pv!N$h z&3BJ2(2t$;vz@8$I#Z`QQ(twaKJQE&<^9fF57tQ6s-8zYAAZ9Ut%F9v=gY0?=&V}` zO72^UcmEr)^TVDn@Fwj1rdm4c7yI?U*$Ax}hCPS0X`Z=8ff9FY$56ws{tbM00bcVP z2CI2}I#O)+^h0fqz<@JK+Lkjxfp51t-0$*l5&WP3WRkgwkv)!2YH@e1rL zD+YPw&2)o8t>xddJSJ+f0ksH0EheEBj>T`_oq+1L1=J`|XMmcsxW=UJ0ktovvq4>x z|5uZG2-GVvUuTxn8|gE|D%Qc#l@KW0+D1$6|dOF=Emf54>v0%|&_4}e;oe^(20 zWu7~qr{t_ClXElA-CdlTJKMQ`mK0NMB*(?=N}HW|u59v(+52ZJ`Dytp^7rQ}bJFIl zn6rP5GB<7Rin;se)*EGU^~M7T9)Y2bGJ=NSk6=RxMhHWQKyV;9V-zRO zdvVe=0O3l6ID{bx!w^OwBqO9Fj6oQWFcD!A!c>GA2ssF|5eg6%AQT~#A}m2zicp5| z075y!Dugu%Pav#A*nm(SUyT#eYU6LHO&#!S2zwCf5e^_6L^y=tMQB85LO71ljBol}5auH+Kv;xOgiwqy31JFC4niKn9SBQsGIKXVslD1*3Va_z8N&St4%2j zLZ!RjFcRvGUl16+wWRMYHH1I}8$t*|7(x_eK=~Cm=!gfXF zHz577*T`v{I;TBywhxDKd}Dg!#2O=T4&_KWt0{xhNy-``qzL7VCvEhJO;}Icyy0A)y30Nz(1kquAd~mspUv8v>Qvd3EgqssEqadCXh=|G>^y{H~p^_#Hdn&F$>E#LkxI zU?bU;Zco3pU~YSq->v*s3-|j)KH4pJ+?rz%Juqjw)ImL9>6nO`Pr>&i{isgsfB6U2FKe0Jy$pLzI$xrbLx&eB zSFk_pm{KBl)aP~MJ3yjIE-mK6Z)Cev5$s>snuC21?dX{+$|r%7%?k>h#?gr&f1gcZ z{ZtQp4aRRs(nB@tM&rylUg@YWIbbx$iL?XhZ_RWL(&xoU(7TEU5yv=$w&v9 z=`zTKnCWVyqv9K3(TIZlb|y#UP&%@p(t5s;Qm}0NG0RWB^o{>$PwvMCx8bV@*58gZ zB}uXK9G?{=pS=*D+pf!>nOMR&e=LEJ4L1uu`D8B7cxmqjN95GOLrd4Lt+fnFKD&Ln zg5Bod;$>H(F(j07^uRAjdd$md|2V!!E@=Hh3zg5L$*iC49)Hj+vOm$etkM?9G~}@H z904(x<_Jq%YxHH5Cn(`!9_Y8(=jFCPY`5piE{8|D0(%+vAWy9MEpwyM?1=TK=sz}> zb`_1rx4?c~@Hyak+5wsTUx59)@YR@DkEII^1h#g;A;5YU90eTEiP3k!;tddGode7>2hD>B$cbR)$j> zzHh2C`raWusrBDi`{iwr%4b)z)^E$6&SXzBR|wCaw}81qp;gX@=EYQ_7eEQSgz_aQ z5tmS$3z@6uC6qi+dR;nCrs>zEY4U0t^h)OM9 zIF9vStD<&Ea$9{?tS6ew5I27utAPCEM6^2dTytJ;UW%~Rbkkb$V&r@2~9BZ&oYuA!6FEFDD+aJP=@}+4mOO9ojQNP6d(HYuudo3HZ?A(pp#4NLW#+@AQ z35lWJC)?yL81CupSN=W83!rrNE2n%3N@u@vigV#`PiMb!N**Yk{VMc;V)o>NqF=vU z=)=Q3!C1#GTu^#5_Ddi39cyM^u;wSn743>Fm-KaU&T%XxgnUB=@k_c9)T=Dv@|$KChx_;dGC9yh!1 z;qjO5yLo)VeHV{Ux|i_yl>1H|pLXBD<8R%IdHlV*l*g^^5+0v*7xVa>`*t4x;4b2^ z;V$IydG{h7|AJq{s7b89(!olwcT2)Pbq;pyQ>u-?DK$nMMr<|4=WJLoBxx3&HvSAt z%0oITNqkL!T`7Od9_Pg_I(Lxi74e>BdW%6G#Z1Xg-!D64e!4*;N_P6VN+(xw`tmBB za%v}6?c}PRc`cn>ODEUT$rWBpoKh@vSv)k_1q~-9oxi=I+6?f}?eqWl{teq@;htIb z4B)ZDGpzIb4AoPzgW6VyeL8(bX>A}&RJ!RGAmZB)+upcc+2v1^KU$-lQC(WUs@m0t z9(N{rHEt>K9vt6Tt~_4mOgmRIs|M!;IC*nOFRwOi6IUCWW3>^GEWW!9sEMOrl4L$w zo>{)S#(GA%;)8NJXCGR^@Emr}zFG^;*jeQx<{A6Hz7Z#2pBl&UYYo=-jnw|0YR~f? ztM`_SEVCWm___Wx4_hzVCE-L`_GWn|YFVgIDhrWS**W9PFai7Qh&6- zKQ57fXD5D5Q&szBi+#zYC2I}2?8uU(xFr$y`qYPy*D%)(LtZ0QJX*d3H(>f1d?(v6 z6nBxsmh?Hl@+Z|pUs!a*R~6LO1kcSpZsa{VZj{x#HDi!@#?piL;KkpQOdTbA2YLRM z@gLlhG~*Wm#}h))f47?b*E{{y+MNM%EN)5gUCJA~2YH^!_zY)C;ulBV8wPnQGY)rR zeoKOT4k=a!=ZTDewCLu&$aM2wWGmf^_|H7QvRz7)Dgw+~kzGb$*_oBv8D#+79?;#0 z`;*&N;%;=4-)7&vh~H+*CUGxf!EHy{D0hS3CX0C!NB1Iw8!Wg9p?kcpHz9NbC2m5Z z8`i6I6VkWwGc}^|(t8jI_aG#h+}Z>8AYuF-r011aC%A_VzaFX7CdK+K7r@#(O=-X zVD#sBmX1D#=hD$lcs?-tQ#{AtbQsS`H+_ufjGGSOIs2yf@LX`yJ9w7fv>(r;pILrJInu#Z5>vZbEA4CM511d=;|*U&Y+m@J@S5f9b00ydUk9uNvv4bIVG83nEqe zPTz8HvVSFJnge%?dWGg%Z4BV=B&&^>H8jiUOwwABc{+Tc72d|VX0_p}q0uJ3ggKtj zc*)EfdG7tr`;7x92d#`KJJ2$3<)D@F8OdpMrXtF|S-FYRrj^xoQt3AZ#g?|l&7E^V z?s6AGs{!4I&|S!&mAP-=mpJC#M=<7Bu+5L(eTW$+DDSi@p}6(1Y>j+{--B>!&Q&R| zVjc$PP@d>=aoZu}?@u0>?4R~m)Q4*O3O!T5p=Vx1PA@MCua4JRbwZv*THhn?B4OviT=zI0W=IG(Pm-Cwr9Jhi+s zbpw7$wja4E--~_>^MD@p49%U3;VqP$g*eLY^&OYhe%c!LF%jr2Sm!6U{g5*M( z>roy*Zya&7wEUhX=!v5o7Uzpb6KYH8qg+!Z*CY!~D7k`{?30(A_|Ab@$BjvjD7U#- zt0X0B`i_aoWwm4<7TeK)@0I9JV=(H^fQ#>PI5~?-D%llXzO_~!ta`#42=7EI$Zz)G zi1mLqhp3<6oENd*JkQd&b)yID_MN}eH+hZV_b#I+>OHZerOz(PLEnH&v8pG^)Ov(# z?b*=Byj>%i>4l_IdZjOPChs5()b=9|N-?ySPBg|v(G8R%mYv;vKmBTB0*f*KOJdKk z$!r%}h`-VCAp4qA|BLmK;-nashL9;8lNL!oN*g7+yidAX9w*-_FP2xybz|-5Tk1VE z3ExHc?~#t*Z}*_{GR66Rm-Cv?=1rGL;!f;LsvVND60^RGB*SSaPC~~r*8!v2EwtPA zK66=azdy-+AHGvsdzrlUC-P;9@3uUAnY{m>$lss1y=CcT@|Hi5e<1PcmfJ6rxBiLz zLy5~;=3FMP|A~Bg;@p<$m&phGiToppnJp79lMng>dGbkO5AVkJzM_x2|AA}`Kk1;a zNgUfLUsPuf+aKg0DZNuF_!6n+lLIcRW5^}^izl%)#@&g>tjjvS-X=Li%y*#APljKX zJM>R-uS4#4w#m-Wn15sT|L^~M;Igv9d}T?Bb6S_NO*Oq4Wv$s37PF~k$z{1Be7P>0 z5tJ(uxfX9zoe?pAX}RsPd_DgpUz6Xmj+?hxoIPWTTW-B9U#~yOw;uVf+vex&6*Hyf z#>?`B|4F`S$QQHC>I{#$wk7?te35^WFB17I+calnOz+O|5cLQ0G-|&8dhli1qyI$u zpI^H!lkWW|(hr>syG**zA4p#u@h@$qTD|ynfSL2zum8KF=&Es_;C>>r^+NpHMtu)T zA2!Nj4%hY>MCqU=LP+@?t}Vm~Z;x8#ynGgSb}DzeFpIYuEP} z3t0W;v)CfO4yqpcvwyAJS{v3JF`qccR#sBpq+Z9Xc=^He6OG`BL>cHoX$))M9O{?9 ziFAMae5_S@bo$`SFC|u{s>dk@RcTmc=Q(=5(LsC_I<)?Mu!Por@&dRcgX0)9~RpKW&m8V>d zakLYt#NRxk9mw&x%GAW8l%~A_#R|8$g3|?{{-4alsVe1!UBqrf#dp=RO{@i%)73wq z`*op5;%^7go`>qm2E313i>Rb^IrKa>kHu0P_*vyj`l|mJ_L_UVL!?YyVRZpu!w16f4aP3lLxC!&3VyL7~Uw9_Ju41Z^#aC`LqNOSAh^C~OwUJpftg-_^dd982!E1 z$uT0o414(WYbKxS>2LD=yYOu$pXwfL@`JnZ9VVaJ6Jhcry6}@tKDE(l@||7yWhTEA zzl*YBmpyGc?XoqN!HRHcvloAl&tHm{=vVor(69u%mTNwxuaTRqZp3#a9<|0Jp6$Y4 z6^QeX+4*x@dqwJiCdsLqyBd;NVOo(+7s<|ayJX+t>+u0VC9pP)l5BVbhWo=~))f3D zIB_dMHxahIbn75$P-*SMYfxp432yDL_bjt<|OXL@0NVp zZZ@?|Gqp|U+6th}=%P(=YL{pey-L~&5})F~h7xrPv-ak73%5q_xCwe z)@(YjSrK%Fb*Y)vsb69OrnYcXTLjlu3~i1s+B9dtCECQeC2hrt zpPJelPL}Kn3OrORZJv)?RdMc3=@`CxGn~ln#2GPj&|52gLncm+t5ZAhWjLJ+ug7^K zPJ|h&y!7w&Rr<@V0g^IM@ye~;Wy>I`L5@3)GdC$wiEU~yT7KNsJ@7-6dW|QdSZQf$vqkz&b%CayPsOy zQI;9z?cVhI4xlWcnc3c+O{qI2#|Koi1ZB`SUYqk&OD+Dcqt#oBzw3Cq0bidsOHOC; z*DbR1XX4D9LY$c=8X_#y8oN33ig6n0eBu86?e_;Ots|8$?{}>@(h_b_8zubWEvI@wKf&+*x#Ox()uVbEdOfxb5yHBooZEhwn0aIt*F&^ zEdi*n>inrC5D2H*{4Cpf|E&8TZV7Ty-n`-$moIOTswJk`9Q7+1ep5*QRH@?%{E5-# zOa?`a4a48?>-tZY{Iq5GA5e5T%v7uR|&`{BBOS#uS0AS>o`wKxNH}KkCE$RLea4HE3D2)?3&KXuO$E(w%PuPB1e{dR!{t4Q5VBzmm9_ zW>!hR3V#??o@nNk_4}yM8>OHFRH*EqF_FnxlKli#NYRrhYqk{h4InNt3Z4L*B-yDM zEQkeAOjQqj3JEJysZ9aYP*TQ;y##Lb;h`+x74S(t=l_RcNSc|>BhigCt&mxeUk-|z zEa6X=GS+>SJV(;0&$XBEmt5rn$xeT`m1(ct05nh3N7X)v1)49ArX8a0yG@`#TXtF& zlNShNv!xMQC{TzkdkosVNV1PX0b$y^^O3Jm@cL>iw*VChG(fw>0d%`SS86}T0~HGt zr>(*ZiCiMk5Ut~Lpi+T`X(79S77H}OHqnF9?~v?yC@ zW&qME5jf{gA4g%9xx^s?=REG?sLZmQI7Hyxy!j$0D26O`ucTOIlX=j`w6Y$_RJ~{Y z!s&1R2CGWCo{4E~-%x@vHY$(?j4JhE_U8$EOx&BB(`>Xwc$C@~T*{6{FIDsQjh_Vn9Um34_N{yfzpencOl~k1#=u2g$5Y@t%Jsf}K zSIIH4joI(TX9-HKz&279|0*7NN)9rsqyegm^gIhx{Ybwkyj_U;hnlr67Fg=ZLb4|? zrNo3GfN4xA6;KXlA?e^QHX+Ilyc5dq5ZK?(Y|@=3UuE`!eDIeDj2{`>`-K7DWn!7x zpH2h5+r$#HOYmmOJtn4h?1RrzmMWX69aMd^<0<_^YDf2B;5;ovVUmzhH>5LVorzJk zzoAc+^(NMs{p(ubN>jDfYzBO( zO+UfcD`!oN*~E)(H*o|D zNlP1rzb|d#aAyAt*`&k7=&!bSfPXMC?9Chfqrh0ounc~zk? z)^q$Q%z_@05LTjD==lW52Ac#aiiHkzfME9#B3bBX)VvTMA%cZIJRXFeK0-JP{Q-Z` zTM6|M!cfY1w4j%d&9Wg8uOm zM21VsUs0G!<)FlIl0Jt@)CYk#-jpW8@d{5c2^MN}Dm=;!CIRyxl=n-fNuZ7i+JdGi z6D6e=G^(T)1LM?(`9$ z@6#CMUg9HYEYx}mgu6_FWM!cpV?emuNANT4bdO2EWMV-_Ux3I`N%@(oKn0@;f01++ zfGVVUP~u~zv<)RbMk~o0lc02Cp(klrJZ=)?0JDI#CPDINq1R?WqQXbeS!jD62v7J3 zs5S4ICrtu6n+1hWgUC~oav!RrQcX~&mnHprSh(ke38>R6rZf#U-u0V&1oTYe2ISuC zD*)p?BOO_`_y`#9FWv=-tv&+A``6gFD%*SnbSAIUc9Q^K7P@9BBx-yT-C1bpaS(R+ z2tk;;4ItF|2(V4g2@rPr2!Sm0BbwcHK0*Mxcmf9LE+4@kqbwbM@Kql{2VoKjfApGw*7Barp7shHO#B^ZWN$!4(LaqPUwda0Sv_b*eL52{QI^v`_+ z8~S{57E}K1BcR0WQRA7?>?2SCzYawKUr5SCXjDlp3TVTS>4up(12bDWYf4l1tZf0I z-ABMMo-pwSI8>iLn6?1*R60xopB9IUK>0yZc2EJN76tgpdL~jmQ(!WyEL>)^!a}cD z30ch~NU}K|bdw-cea9q0#9vl|kzXYxP!}reHKZ;*H4e_vlqQ3ur^drM`Uo&cdTIhw z!hHnlg49H&MED3)Kp>5$NLk6H0!S?ih?VsoLA-z=Ou5o0%?ofdWw4LH3rJ$hRXzeQ zU?@|r_7SLnVKmd@WaVutfYhRZWLeLl0y3~aNil_C5MX%sRFeRM^qiQL!IU(Uzzx#B zFVv;WiVOKwQUY~ZvOW~X549cuFWZ;B4-0L(4TMQPLT?y28-&R|0-W#U6cDEP2{XPTd<3joM_vSBs*iwGi+r7OvyXsPYu_>uruhh%#g$t?nC>IMfzP}Jgc&{pty)C5 z#Yey_UR4jmtv&)~F?S6!O#;p0CuyU1 zi~C;#!fYP_F3Ct&TwWUu=s7+DTwX62R+;M~z~$XJ0)zq|0gn0{*>s+d07w1g zOc3V#2o@AeTiV-v1WbJHq86A0l}5?SaS&N3E5+2U)S2kkzshS@)6Ljb8%3hyzC>OTW75R;T0bN-Fo;l5H|S;=+^5~LD=jgpj*$;PGF0VfNq_+ z2!yRZ0=o5sr$N}}BcNM{J`BQk9|7HZ9T94Lgr1mh8SqFud<1mse(IxIlR(}21o?oS zCP9OJPtvBZ&PO2I9JwEqU9yq^vslO?Y7QQ~;2CA*F{Hw7z{|1nFPXpOhyQvLq(7I# zj$(^ILd~*L$A$1e`gf*K(-45~7 z`=Ga(LLc7?a8{1E3o9oTcTQFol92aR&^t__5mx~GAcuFuIAvBQDaT}e2c#nAqh>6E z%%Mh5d$kB^P+$br*cL%m3W=aH!!$m#3^|apMTxiKw~*v7-osdsOpD`BqHNUS7g=cs zH+0|YBky)n(GxDZ8YAfZ5dS?*~H(bA=aD&Y%Fp)f_Ug+S;(Ux6NO z3VkpIAVP^q$Dj;vp%EH|Ph6ojyq>a0E0OuIJnQaIewOud$R6<#%*Z0hm}&%BON$_L z1V&JMZ4uOi+eLtzU(Bg5&^BePEpE{3eVb)9M_vI*!2v+NF{PT?TsOn zq9|KQsBAvysix5P4*{epQFQD|LZcMrFbN%e4|I0qrPmQaChI?vamFcuCkd+h(h|V&O6ZRSZNdpqMsDok0#i0q;@vVe+WWiHynU7<>LcL4~Z&AI_iT=q^}7i zdQ?4phxJ;KJ~ja9;UYc$Fw)nF^an7H^?H%s0IzHv$MFnqc?;!bqy$UsW7 z=;K&$wPX$gqn}#>kitP&^veWNIp`Z5odA%=K^zO97DXUCx0wa!2vOjsEBiq1J#`-H zsg2fN1wZi5ZZjsu|(l!X)tsJCmb3X3Oc5l#vaAf%T z4$8I`bjkT12(t6c3S@K2x1*Dt?>3@mos05t>)`y9I@`H~n(5qG%9!rFy?`-)=bFiI z2hMwkp+QdNN(?$@$yL}EUZKs55V93NnVY9g*dNq;1|7}z-|t-=v@R}=fFSu4FYd)5E%Uyfjt}qMK3!E zu$KcHe8w!GH)X10uuZGim!c}Jd9#`J79Y|qdMy?HwnlW-HG9DAU@7ZXE&>=oq_umf+yz2{?tplP4@Z$>5T-0F?o>M}OI zc5dQNO$ZLMW4rZSv$#F z%c467w1}p&ez)I1a;Nny$X&5GF@b4kdQquYERIiN+P6K)9#Ay$(4inQX zcoyDD)qd39MeZwd7c5|!!K--%{oiJ_pX{?hXT4X#wFPRw`2Pn;47p!>Qbm|+0=8D# zg`QNn##GW0H2g`VB`Jo42c%&DPt_77?JvDSz3v-4+>*xUmKKl&lq8U>b)b3LP=Qp< zoeDHeAU~~xX2>-HXD)&)IzK{B{Pl{A=DG)zGI;fVWXtLxY z=>cQ&8Ee*Vmb9PxfJ&P-ZJNXC0?Lrhttw>BtC3|v~RM3as{$!f7t?*C;9)1qC>R*B7ZtdpfK$_>^`;G z5_kPk8ofGd`2sn#v73PANP%CW0e!W5Hv`QTXsH%Nk_DoKMy)TFEp47aN3@Aw0nHbv zNqd1h>^6zJrQ=L(g|a?;8>3Qvg66=-Ym1}-WS0S>AECC~D`}YyP(Mq@W0}x{4Fmb< zGEr|;`gzy{3lyf+leN|g6s5J(5Uvo& zp?%T_^n^ftwV8E5PYN_Zi#Y@Ilt5Q%qXz>$El`~HgbQe$Ktr@2mjkUAwH~I${2QoJ z@J49+u}#L`pyU0YtmTpUHV9t2wgUrIdq$u!T2Cw)+Oq21=&u6J*1kOo^f!SDv}>DzUJ_`5R=pMo z2i;Uck>-6G=oNuVweHjpn*>^--THT+%>pge?s^kwi$G=C`u#v#1$sb>e-CJzK;>HD zhd|o}TBVJq*;FIY8f_^9+9A*r+7fDQtw8Ive+K~V6ljC?;G;mh1gh4CT?O>2KpVAF z2|#}r=w)r$P@vZY+M-=cGjF#*HQK1DK(7l_r;WZ9=na8h)4XKCJp%2~zPlS}uR!(M zHDy3=3Uom0{vgmkfevcZF-Np|fevX=F9E$JkXNhN3iP%>joO)7p#1_hX=TTO4hVEy z>qGPR9f6uPdo|FzV)UHQ{;?P6pgKHfbkGmzV}Z_VhZX|iU5v)WFZxM12(3Zzn51u^<{lPM zmh^eI0e&K6Ros_g8PpmDSCe$L5b#q0{U!Zt8VW~*aG<0o-3$0n!L>>H^G5)i1Pqq+ z!|wwg6~ZBse&H^_&jdG2(nn7LJSJd-q!%3o#Ek=0ISLmKWR-sju0zrXlgIg7Kqt7^ z)8xUZxq1Oa{_-~dT4qrLB!0$wTU{G2mD6BF_NA&AMmt*<0X9vP2n>FPQjaaM2-;CTU8NqR0#>7NB$Bk8Yw0Qif5Pe}R;UcmnnaGj*jrdj=~fEy(JFEp($ z2v`l{pkbOM^KrjX(tq{<$^ya*zJrBLQv`fj(vJ{S1%$6VNzfwT7D@ksAnt)^3c;f> z>V2!sO;>{sy#Y`Y+&W2LNDb5l_ccjhLC{~oJ(9kjV1R)2lD?f_pnwM?J@`eyZUP>Z z^g&c^kbs9I{Y~O_7tjmS5!WVQBbq?-yoZ2Il75O{uz<%U{X9XtfX$K~xCt;sz!Q?b zIS;U>fTtvVFF{;X(b)J_(my8HOTbo1|AJtcfafHA9j!p&qWS3Ns6&7e0-|4|XbwgS zh>nz~y-@<9=f0&`7A;iaoX15=aBsmyXZ&;{U>^Zt{pDu>9RkAK310%n2nhQwqhaP0 z5C(mN#-vL?SnyC2U|#`YvdcJ@3kaj^nFn}U_4RD}< zXlFJRG)O=+tb8XRuHa~>pe6rB9_dN}QT1C%)nL(H)TWT&RRW@b;v~SUg)s80y&f=5 zKnNw$0FD~%0&spy+PLFXfUJ*I8oN$Aub9eZWc`THDH>6lVtsA z(v0$nJ4Mz{(#RPl;8a=PNL*BhxYJ~P{!GBp0?xn<1aVP2;@&Fj4XXh&1k923H;IeN z5;qT;uLB$>;A{+)#{p4y;?9wE>j}UK0v5>nd&EUkh&x}_*Te#53b;Vlj}R9vBkm$u zKm8!!jRF?Q`s1`sKtqXJEb9-f0?Zb$6x~gE(Qe}2A?tV515OrjiL7gD0bvH>-Yx5U zEr2%(xK!4?#D!Ied!MXdbq4Te0n23lbK=5C#JykEx6=%rF5m;Q{w;A~GvYoZ>$AoH z-XdVRte+7A5XqWIbgoV6K2`WIenB5C$ghTFjJx0nQTe z2}Hz&y@~sjthe_C%olJS#xrqYe&SZj`mUP*=L)z%*3*cK-XQL?mjRzuL|+m2ZK(RIY#BUzPPuv{)||@HJUqNSe{@#C=`X z`+o;`r+|B8{ka0by99hw*026I;8K~tXV#-u1n(8_fUG}CEy5@uRR?9=u>!D6a1Y^Q zgp45XY1Z zF}{c!rReY74v6tZ(4px1NWkX=?5pU3v}j_u5qE&17b4Q07w}3&pG*tTi=r3e6g}ZD zfEaz$DG7>h`G43u@A$0h^Y5Q?-?>BX5CXCc$P$qyA|phI5yCJG5t9(6iijwvh=8cL z0IhXvLDZ^^hFZ1OT1(vnagVBXTa~)2)>^gxthN5E)#v@Wu5<1|LiIOZ&p*#|cwOIX zU*A2>$jv6$Yn?4mrr%Y=G8m<;NTwgz1NP_6j!dRozYNRRl(sUN?s*C9FPyDPrjI`! zmZ2)`XiB9G=$Fn`C(|E@W#mdbE}1TFg#DGX6JTF}WgtsilT80r=k{MaJBfzXWdDt` zQ_g5TnM|+O_QVvC?~-J?UOU|*&Mr-+TkQ<{sI$wG=|7KyeazVv z$@Fzs!T#3SmC5uCN5MYf?D5HTqq_S^XIJrGkxhqXwke~NlIeGT1N*eIrzF$QrD30O zb~TafVVR3EUYkr$9}4@Nv!^H1*J@FH-q|yf=|k>?eZko?lj(i%DPrQv_v~c))PrGP za`xP0y7!B)%;PT1^7E7F9{a<->TDx@G!=HMvo|tgwetVL+0DuH$v46>>E-)WGJT&` zhS!~aEt!5sr_DE<{V17!OD*}PvtK9ESKSQzP9i-3-;#p#jVoaP=xoP=^wC$svS3Kt ztss5%Z(-kawogI&H#%Uv@9dz0^g-(1KRH`okp7Q(u&gffttv=&*4X&7vl9x^&%Oc6 zVk7O;g7or(U_W-Yp&&9o!o>Gt=^b+jfoIRr;U8+KU;nhFCAbnRA>_41sEJzR5$YE7eOWs(J{^SbS|8#b9 zLHhU~!+z!LQw8bMHDdqi>}v(-i6yWsf%5&RAibmr_Fv9^U63BF{tcK*sS?h1OQp|l1DkZVPb$59Eo_0agHq`~Y=KQVTb@eK(n?t9Y*i}#{s7ok z&Q3_BpK1+T?CjK3dgQUNt(|R1rTf1ITjK12sq}{XVcR&nFqOV*Z`e|2m!#51T?5C5H2tFv2D z=|Ara+t=CqQ|Z$mgYD<+gQ;{kMP_SJ6&|LU8({}H`)DeCsf-6Y`*L}cX|QZ*(!Q2TUvVz%2xs3&rF$k|+2N#picWcz(#3kuWa8c6J{Dn=1(3N+c-;==Tg zw1`e|wxrNLvMt)z+0w#veHq%R$@FYOwJS{j^<&umob6bc-eV9f+px4{g~j6T9;6(0hp7YiEJzco^q8^4pPuZa7XUkSz8_{rvV*?l-(mK>Ff$|O4p~pJ?N_XgSPS5xi^aQ6L z{S)*)P8V?eOV>C(R&}4~^g$OwPjdQ|-q4esK2d$NueH@4{fQawm9{sQDYkmH zM>J$kD?}f6F_HTE>=3@O`{*DTx@_5@Qtc{+#lx;)`~1@EhiWxr&<6~nU|6`H38(CW z<-Q0Qt-0+2SfrN31_cT?y=Y z0?bIMM_mZD8RBk$JH3u151hh2iOXJLZDJW|UE&1N`oyWE(-X&H)dQ=ICy`KB>5t3N zuU{BcRiOGKdPO+iEaY3CK*#c}MY?A}5B7y2J@2Q4o4eQ%2%q41AZ+~cn7HLPciCAj z{{n@32Jn{O++}yQ{NEA$2T=YHIfYw1NH;pEGvFS~7kkU!AM;DRspQ37TF^-7)f8ZFOa zyZ2jnP^upK^Gi;r43)6)hU&Pbdvxiomi~~!=$qBiM<2T=2zzz0+hf|VvNv;r-`WiR z6cukJMXrow|ICrqN3ym=RyD92vjAC7<5irX^7_bTc-E$}lJclD6LVw}BG~~svT2d* zm>k*cNcMvq*)n7&j}3w=Gcs?Cp!y0l5giP9f@Tkc?9`{YG>ac4r^;-xnQ+h(sGcrs^Lcj}o;MWkb_`V~k9fNq?qfZ5XPNa>P_ynZ3^$cgEPc}o z-KdgHv@&ce>!&h=wZmr6V_1#UCokt=`$J%o%$G7wGNUgX!-VH=pX!*Y)7h27CSNuc zyN|^lG>%Dmm4Y>uby1ac$9@Me>`1MtO=bNg{3inadG+KYg7BwhMLOg4M%@hvYNo!0 z;aOhbS_^tALA}6dl?{jrtdEAU8liBr@oNBvy)@W_mX_;Tpbu<@T-FP&IvZoI#i)&9RG0Nq4Bcoi%*3cJ+aroGWPf=N&U!PvsMfC{ z@4;SzoAA62m~!uG?gC_CDWg3IE6Ng69z$GeVx=aoEK3A6?`aE8dwcot-)BNR{L|iE zpA+^2K=n@xSvcOlWW(#TeUKlZw7(TVki&TmJZ@y>`s9b=} zzUa%%rcV1p)ly{pPx49R`-Hw?tm(cxr5oQ_^|5^_Y}_3qpPb`6+wi!7Vq6EPbmKdZ zl>Rl?$AR+W-^YEQ&bG`SSHE|X7T{#`am|E7}E?;&_o!U;b|SnI;BZP6+a zA)M9Ox_u;q{=o2?&q6r6b8Gcna{aAq%3pj9!Ca5Gfc51-pnL({A0FVs3lN+qp>3!K zy6`##8zpSBJC+Bz@FfJ#0Q-K*&|OtSZlACjh7ax7jpd2lZdl_Ru!b;yAb?SLZ0FYZ zVrUz1{~eg0K!uJz2SCgLM#{`K;^lD10MRZ!C=~gMf;`o^b7Eo?j$>=%q1+s*sqnpsa1CqmcTiOA1Um00N~Wv`0~Bo!zd?%X5`tYMjM~w|1B*(+54%)cTEUE>2`^lIu6E32eL9 z3GUt8ygUlQWU-i9&p()3cSeP8^eW9s$}P3N(LzoS%Y({|*o|QX?d*0M7D4rc2yqIB z>LjR@qi4ZLR`#hHVgt3tTY_{Hf|?$i=!dgA6;gluiJGucP2+38*_{Szi};9U{{YY$ zaCWCrS_4Yk^W8k)YrwgkYz@#cYmkJt2At=@jR-E5(AI$ST^M%Yh$*2RFE8k1(|ta| z2B7>8Cs3pd-SSQZ`kN)6C_n0C6D8e|&rAWIDC;`eMA4tlbOU^%tnakVM7hZ0okRV9 z0Qf}N;KExG+$^C@l#5;XGJ@X%`(96bou9Rv`kSLU!RX*xhf(;;POX27 zq0Nb5>?4B!Ka@&s!}u^nhXM?#K_nVdpW>1o#&$c9JT)kchg3Oc8d9ZnixzuEn-3{$ zg34O7>agCXt>tbZsGN^X<7<3IhM$M5XBq^R#f(x7o7ryQ!)72t4VxhhiogAu+8peI zg5G97EZa986bEBl~@G~Td~}1hv>H9X9%tYG*S-kw2wy0i?GiE-dBfsU+E7j z{tkFwE%3fdte@&@+M(V73%jtU0p3*$UHAfm=YT49H>-nMZv9lsJcsrSCwZCGv|;0s znKDo6Waqw5aeN=BWT^}K98CjYp#Up6p$$YP4|wgXL9pN9Yl(7h$IPv30cZEHamw_# zCC=^GQ!O!}E3E)%#XrBJoxpB`{WUQBizZwy=-BZ|g6kf2_#N;U#{9w&XRT(pNFob{ zXaJRWO0=gg6_+4>8~-_mFi9HqM z6U0?mRLW|~iTK=rQNmJ9_i#j~_R}85=vnhss&)zY?36e`{?DVDh3^dck0`_cBQu<@ zOh$ET^9LDCK)eEjWkAKAFlR%Y3G6u#W~6LK)j>5O`Ux;<9?T;U_lY?QrWZR+4}d&= zLXNt@WMnCi%1((k?1UA!BOZapaG>HBFjFBW$z|HtaDB}~DH|$JmO3RW+gtl&u`hi2?ILU4ugY4lJk>6v zbAqyF#=W5dC$oJbGu>rHU7Op=t1;6={(+fA!y&Au1mO@oNEizVws(&UDzcGLVqLy5 z^1dU=WJ1;@DvFiA$a5^Q(R6d<^Owk{=6m=&9QpKQHBy}?eGi}CM?TXdpDEwN=Yz=S ztjK4d@8R=R$TR&qD%AXTFO zuFc$|Yz?`)7J93GMv%ynA6dYzNfGPhK*V|{OQP?j`nPd$2sHMm{qw>&gCt7&c z=*;sN{CzIlN5VQ8rn=(<4AT)1;X$$-h@h{8`dJ!;D`hzi!4zPq{?ZWPX%enLuvC_p z>UqnYju%LHDT0fDpk~<>NC$Yq7hAzE$`pJ+e!&NHw1RKO?{>fnKEMn98T^MXqu>L) z;6r+FYz4eH13Dh0ob~Bb9Wd;kv6k@>5}t_QI3U=+-Q`Hzbu0{PU)Th7e}}>$$G3yH z)!z+Z5_AN@#?a)ItMGL_ae9ls4T)sC$ev-oTfh8 zKoxO=!h02L4m6QWPlMy9@sz|Kv`YW;Ts@lvH=$DB9JxQ5ryd@wbsUiQd%0?@ zLF_=og33oDb#kT`$TGL!(moq$ch1u)wzOL#ZFR0T3Ozii)bETc=Xtqm4~_PdNP9}2 z)^p^BKVr|?hZE8xOb@8aUWD?x!L_T_CLj}+}4uyJJ>x!KL*~8K>2ap zk%SlRU?cKM1U~}m7_xy}f|_Zh;gEKg{VE>BnV#3 zDM}eZj!;Mz)1dljtOh~o?;O6(7Nzo=5Fv59&&lm5&gS(z@TlxT;q47qMjKSFMJA8^ zGcs)v9Mf&KJRNC|&eM*RmI2?D)kMDM7qcOt9+4Pn#t1pz= zco<6)?*$Ay`(3l$UF-ES1V>8vGVM-)DhW3tXascc`ckR=E$c(D4@h*_(uG0z`%)X1 ze?suGgxuJ_TxySN>UO0`f%0W!AHGuBLB&{!V4;M!KY;MnQhOx&E`k>&d~OGXTV2@D zmpf-*_>QL`{6ndI$CX$=Y51$ZgMTgNrw(u53I6rc=w(@L`Kx!pzv23a32-Y=IfceN z^bl?nDMO~s_yGtSO-~1^u125t`o$ln+4?d)v7Ym2&w|OcN6keK5`8CcU9EOuqgDxT z-JMG9$w&Ww+<61ux;vE)QA18aP$S`W$6A0f5*~x#C_t^--COq}*mV+F>-O;0y%WK8 z64JUoy>*B5XCDU2*St@>UT#;9V48&1i@FG8>u z@FwpQH*vK$`K~cP!CyP{Ep4wBQJ2{3vi_y^x{T(uSJW>simp7+TU$5N^@$bq1FL6n zKmBlTr14F2eRZU-*Uj?2=P<|bhL|NnKZ|{+h^HZr5%CJd$s*o?I7@`?VmFBR0-^~b zsM%*A&B9M&LkEunVWXaxdOroFwhpH-`PTpnRf=BP8PU1HClvR2EE%lqn#o-wlU2=4 z*wM{|VP;W&(%giN#!QAqCR>`D=;47f(z>p)yxrVHx9~F2Se8k_yqvMD+fvqz$b>!8 zO!_r9(H*{`EQm~|G&f;!GZPjPi*j_HiT1oqyPOo6tZQx(x67H4$t}%I;&!t zJycSNT`-d+JZwDZka%Q0RAMW@1V&aBFzkvG%+^+bGZ3tj@Rr+5I8H0Tn+RT(a9EQG zXG++8H+Dfl%fcfiw!Th-9W4*E)d*+a$CmwSjmCjo@u{s`a0_Y z?x2H89g7E^90XrRjy6@3>#KRv{RS$<>_OY8`~3-?ztvgKYfz8;0akiiUTs!&1?wl+ z!*VJvi}ejbRW~+#Jsr;sA=9x{mF5EhT>pCuKc1GB*xQ`2*4OiPCDD4m zq^gAO(0ZO}R(qJD1wE*_U=30J*4m~6T}{MGGZFvR+8RX%-WTsh^`@Jt_rpdV+&tqq zTidL`Z0v@gqI#-zVW>l-SN%9{!s;dV9`Y0%GN%&pmagr!Rgg zkxgBc;e(nrb1Bx}($*U73ZNUM_HE~HX)D&BDAJq2u+qcL*1iMjN%Wlne_!_Zv`zYb z5bQ0Xy)XO1h36nRO+tHL_74|6jo?uU?Vb6TF6=p!Zz=(QiT0mqo8b>5xLZPdXa1F2 zwqs)|1SZ%!^MAU~-<5yuZrbJTRr$YSeyYDI|Hh3E!h3(f-;{sr!ut{2Eup6@HgE>F5Dl%WMG25Juh~lzhP?a%umo>4(!YK z8^MOd$V9)g6rRw!qu!z>)=%(vm zJ2F0+KK5#yVHM}u2P-YiTRqRz`aAtKW@N%4y|Mxmt;}ELWuy>xh_Aem3Tx}$*=A&P zV?+_q7n~YsowsAnN0{lXUmcm*MiJUe2oCzyrAccVy&kW5ma2v`eL7!5?qQ=U@6&l^ z+MWQOOv4@v_;j9`9;NSwZb9&Cz^C(UpAH`&cu_)|&U0M2aZm2K0iVuuU8w&?Lich$ za}V$-cM^i7658wU1KsjD1dmB*--#TQw$a~t6wg5bAN}*v`J?|}_Z*7B0Kf|wh?y=qTc|Fn7$z}vLp|I((&zN> zsr36W)VSH3>|O4pMx(ul=aW^~sD~WBFO5#yXPG?XwRhN~(}VSt_9^Q1C@{=ch|%e4 z?YaL#@ShUe_cf!__K>%CC8rUB8^>%Hca; zNxGN4N49;eH0@s{))Y>}@Y|w7ocJ>em0S-;yyV{&MNgWBeQ>#14NxH`QkL<+uo>K` z<7#*KOAsv16f%qpxvZ)`G4l&)w-_YT^&x36cHJbRJW*5_>Y0(3^ob&Cu?hBF+EYb# z&mN3@nBs-wFw_GfHyl^Ai&e=CCq#xd9oSmKGOtp-RY}jKe7cnt+392hMZG}9wZ`aL zl-blvu-B&E8IR033-t!ZZam9SKY?n1sr4+VifLn_*qT>+O!?qB%Fxcs(ACOtAuism z?TYLi7S>iOH-%em;ry^E|4DL@f_!ZSIeKrxecsA?X@P~4*28_?%DxX^eD$AeR=a6@ zJx}d61Hstebw|3T6`vMSFK@Rkt*m3mo5Pk?1LQE?HvKKFM*j$>VC<`F@wy4GZW*te zT3NY+nmgN}yV^@L5aX~>J?y2qx|MYa$3J_ba!spf*;rP^XxU~Y*vnN7f|_sH%EQ$j z@obBzPVk7UTiHXs_#MgWR`y}h(R&5KBEViXtZr4MDm20W1Q=#p>FQQfwTM29;C>*e zseO@57JDXIh{DDmJpS`c7PpEgsXaVh+-k6f`k(Q8514MlWO1u~m{CNZEs)eG!b8@Z;VVz-|K0LGVMsAE(@viXNvl47cwl?@qP%^F+;X+b`~k z`ANg=$Z^{l$n+SM=fHBBnB1FX zOrDdMBYZISoHqQ{YWRm@zIM2sp&p6(dfOg0(sG=bwLQ!zEV*fEv^@+X<{-eg2dVud zCq#z=EY+pRw3I)COLi%@FWHhS`Ae+IG7J`;Opk735L7DMFVCUSk>+^9ZDntlYzMkU z;Uv?GV99pPk?CwM*{H0nssh>9$L18n)`Ls-qfTuLtjjm0pc}g|1ij1K7Fd^`LRD4) z-sNoztjn)LaD{}{qI z(>oPdr++}mcNNw;y>o0d&ii*qH`;;0*$VKHQ0Btf2 z-Ut0oF+XYaQ9;-(=B5n);~QwZ$NW@3jr1t6)5tl5KTBEIxak=iO>3A$d*93$czGF0 zoA}dHWj^L>{S4g@^YwlRc}+ux->fFH`wH50WSrXZ_iCay0zS&5wo&#Hq89+(ZXAwm z7t9$FdTM_LtOnh97e(g>8+3MJy%4>|+(FyugUScd+`+iffq-DimFKq(Dr*>E5}p~E zpTMA78_BN7k?9L6WqbEFVYNq*n?3SZoTqbqx-#S>dnZRWADIT~*LiUm>Q%?1(eTX9 zBtM3)q7iCd>r1Odq#Q-Ndta1e&$#6 zrUmfvBejj64T#nQ^i2FrXeBP$w)I0SZChDQbE;=A-j03>dJU+Xw$b~Syz0xxay2YG z)z{&o;W~^hsZ|*zE=m@Lvh?k$C~4c(_?NCSl^x}RnoIuz_j1Cz_yY5X&Aa&J zgn8UajjjWRndi$1^Bg+XU(yX<`3O$0CZgV4IJ|Nt{MML1ypn=gMNdVZZ3rJ^T5J2D zS4Drkjou$@tBLN|Mx((m&nbB7$==H?>t`%RzW_u1bS635Czvx%NBA){41ri!c@aY8 zw6hDN*_|yTEoNohYa4w~d1vIQzk+O`c2y6fR~cK-1vOn+%ferH+dqY2*r<|u+y5f5 zyQbF(H1kn_xBV{?qcoGALGTz*KKBKje(ArE({>!sZh-P5B)rjuqY;b*>Lw6gZ4uPy zL-24}Zl;oZrpr9jWARu7c&5ud(fCU!mmiy0Ybsm=L9MCWIn^|b?U5#`(^(Q_}%Y?=Ex7C+56 zOKr|u5xtUizQ&xdmvg^F&sDLr{)qnLjI-3{+_#2zoj_FVcg^{J*l>8F=WVg`7%WBs zUT3Mzc?F_nS!aF8M^S*VI??m9*!esxewcBV+MKr_+MIP>WzL_iBH8@9Lkdpi140DH=N2gEJFY#GbU#`VWY{sM3f zS$iM8@ejWvm=A=FdKBkn91+@0ZJE|Dz}Mdq;aHV%GlJWJp+_BdqJr3K$&V0x0Qete z@972aIhlv(fEClH1^Jkz^I`bWHLD+~YuS@K>`5^^$#680yaw z<{!Z;iI;k6V9mEid&wSl9AY;;{(mF{3x2`wkUW29n~P3=jp4ev$q}YIbf-bQ zIM}1GtGJ~8+GG6qO(q#B$@qOaTB5EsX32TR94ThPpGXoz3rmfu`T@+ah`ERMObmA> zSh)BNxNB3M!Gbf{EE4Neos;^DSkG#G%Ced;?Os$HQXbHvU+he9*w;gOZCn$MN*=a_ z+n9pApbpo!tGYB`!p21!4Z3WIHSV+~8dq=AEw2MM;tKc09I&yqJ48PqSfr&w7iVfB zJtWsEL}#Ep38njxjJ_!V)pNgAfo)@&1nJ9b#<-Ds;Eljpq`b zfr_>;`$FskEbay~OYX|j)81e$mS(sLqm}Yfh$|p26{Fz#kB;sHX3JAPqZI2kBwK+h zN#digj?(e3A8^{_TBJ8Ox+;LMao5wJZbI}oT>lDG+ykQ@nd%5sJPxxr#3(T@!7PB7 z2TW6#UW#LBN3eE^k~rMy*sPV4B3uD+nHWX58Df(dW%L-tBLMI6Nuu`6YxqUF^VPKl zU`(Bk=i7)r!E39+d;+tQ(S0Ovgp5ngyePz+8!^*AfbK59JloXrq7J6A7l!J9CJLR~ zt?_-%kVt>ucJ!mstD)a)SwCYgdY$nvYht$(z>3QN_A?+Y4HW08k0eS?l zf-aNkB0c%n#R5*e(ldzn3Zk&KLjQH(ES$yw6`#QrvpReUGfO^I=B4yfdGbcUY<`5z zX@Gfu3-PfSMLcynpXmVPsdqEFt^mTu1h*9VsGZ}Y)WjX?4C@@ma zi0Y=Jsv2t0g=v<5R zm$kao`C()4v+&S=l$GR2^$$FzNw3>7PgMlHtNEwuCc8T9_5-R0q0##nUkaGY!w~3m z+_r>_g!LR)1HH+qUkIURqroD5d8CW!LjI3oeB_ge!rG%>k!F_kB{Hyd99W+uRmf&J z`5ptP1@ONm@AE4=v!M?S>C1VZK zUl5MeUy|vyA%(0TD?~2>VdJ#3sr-CIXOsCEz>=e3_-&wRva2ymrP`+SQ#Ji!`|Gj2 zP6dv&i{;2lGm>OathAMLqOv0D_iZxks=ef0WS{P1%BDy$wkqtNSlvg+dw?YqU^E|P zr;whumo-1Fb5m^pCbq8w`Ypjg+Qo9D<@%CnKK{;%691tkfB9x}vbqAbN~oVuS`?TI zgBxMks6SAzC`I%oaX$kpc7ho=hr2OgnvB(Uo)*c49|amAC)v%$W+t$wA_Vm+mVT=z zSUQ_51;wYeSvrVOAShnnX6fSxa`Xp^FKV;2l(8fz-q2?0+2_(JK=H+GmOgd|hYz6m zk~T{(c!w9&K=Gw*mJaU4D|(>#$8DAl>_;Ji;>+4B-EtyLpr89QiA#Atf<>PjwnfnB-TaQM{ROuWfODkLN)p}Ix$sJg7M+8EtzJ>}T zJL=r3L)bcnU20To{iH%s8+U`9++k#E9z^8{Qj`iokvm|4pmi8d?jYZioe91NK5dLZ zRT>q-qA}^nt93T7c6pKT+kyYeTxB-%FwQk*}bxCU#vSSo! z8*!)H46@dpqac<|R=nemd8I4Mb!J`2b)p~IP*-KWlM&RlTU2-}gBQMgjCP2OdiSSUy5YV{RHRJ2K62+7=Z@Qi?VFo1 zXPR6;-fm<{K?|r913HEMx_BQBOxXb0%}jE}#h^~1EO#$s0u0`nWRLv5N}w1rI2_X@ z?mz|HA#7h*UH0Q~UF15H|6VjRZW24*q47ElS*F7y+3?)J3R|8haK{nd!=WAO!#l^N zX6!h-^_Cg7GgxAvTPa_h;>T5dKh;Q0ab zns#DtTs7GwFUBR~x~L5%=SGT}hrbt%8c>nE3AssBYpEVnH6ldpm!ECir%_W(%XC9F zioEt89ArmAFGgr>u7LfS@&!ADQTghfQ&FeqHi>G|(3-AlU#Ornaw;W$=C(!iMxNC| znOLtq4$qD>GMp5*)0b%2{OEz zbg`xh=ekT2#h7v8OG~ZnGy)4oe07HigIXco zGKA3<9IL^_W>F_3i-LfkxNFMM8)?UwpkBzsaN>@yf{buhEb^aRb4w1;-*vHz+wDk- z|J8a-SN&HT!TCU|;MkyYR|M-|Uda`_0rP&YK+K0g-(da1!iy8d-+tSbU)yn_Uxw;k z{HtZ%EaFGlewrIV%n+*oeFMn02FR3A%%uN9fT`FXpBq5Ts{cX&{Q*4lI$HuUXZ{xg zP-DArY4OsXnz|tjrpFxs886}2~S6@&f7}7KlTocj49<>%Kx-`38I5QUc>~>+!IuNT> zE6(E7*=Dmy&FIWb5wiqfsx8_6T-8+VZF5z&%W?yVQSRS20H$`u16>tSA!y&YEOhgC zm8B^z2X1i*zK@&d9i`zE2(@k))C=j3mv++F5UG;EYHUFH6-p>*VK_u4!MUcc6N8H8LKMqTlAygEw{!A@wFULMvTLnz=edl>uQeqa5VM&BmnP zw}*j^%C=@cU8o(9KR^)>%P);Q3L)g%Pp#~AubN^!4BfSs=^gQafJGR zmyJfv|16t0Li210?GIFg+HR0NqO5A0L}_QHd4=X>6cEiW9|W~RT>%xgwn>x^iCQ78 zX|8~1cBx~@N=RMdhN9FHD1;P#`w>tEJVB7LkP7X_q7HF|(Bh0j6py0hA+$21fN1fW ziIlDvio@46#jS%vjTDEkvxCf$?jaP1Z+^TQWk$6^`uXwvIT^+i0&V6R3`KrI+HRPC zLJfebT-PK@KaYVzNIy*F3Q>=`Lg7h4LF43gH4-xVZ9knM!ff{}YE)FeP3>C+Z+TbQM^y_$if!z&bK(wxN7V z^ac2a!EAkzd$E&OfUa^f&ONlVTnb?#IIcLBW(X6+1xyC%Z>@cvM{JA;6*COx3Mng- zi%^k~$0awps^9}qD@e|@6tdm9tG7?a}x`A*j9np~%A)~HRC4^G#t$#)X> zRpi*bb@bZ^NVjClKRXVEw0WSGCD-7spHv8gS}hmPjO%1qG>8VPUIQSnB6>1SP=+{u-|6+pbL;5*tcmX@?x?iNVNS zr7Ve+otrBUKwli|ySAtwq8R*tm!55p?b?`KVQkm?-`bgNfov}V`hKUa*(YSHrD4Zl zLm>s1Fc&tU@~a~a?aQ%mJ#)1B$vX_@D1gsZZNYYRvX$F~2gE`P5v+yPD#&Arcm;%v zSHGNx6>eSynhmgU32CX?HQ@J`qq_)xXg9v)&ysc@(WDh|qkG0BFdVJ~odgh4=oBEj zR};C`+5GdkT%<^_nPsj}5#|;Lln&^oFWE>b0v*-%>rQ(q03C(viQl?Vup9qF$8eFu3 zjRq3Iu%;UDY@>%X9S&X*(Q#nT^GF5&xnm~e8|L`@=5zt8Ur|vyEkBbOCdt@I!=<`C z1+)t`6iwfdXxNaLy&*A^B`hJSK+D_-@yc1yvdzvpHYY^uXrj64vxMu@+?2_^VH;~% zeg^Ea9qYW3%218lk%i7;8;W8$x7$J~mjR5kmJBRg=~n>Vw`*fV_GV0O z1u{)0=1w5DX5w|g+oom`X@P5AGe(zRX#IX#3kByWt)?1#kQ#oz3TMtyq1}2*$oW$r zGx}vgVkS5P%9oev@$wL@!O^}@gS|QosoH(MlWL1Ioz(iHdgrbO7Je1!Y5;}MS|Hj9 zMV{_#{!XaU2%5!;zUT~UhoRLylHZ3zY;z5QXSWa<44}=1?yb8)YA9 zWDjyf&VNn5`IV9yGb&YwPUcNz-75w zX;j^=+y>Y0k}(jIiGVt~dVy7*{HFtvQplgI)e7n63p=3!M%D@q1iU9idE4vk_HV8Z z=r~shO|^qsgV0Gv)(TzhQlW0#3ScXwBOLh)UFuRH`;p0@L5K}cwwau5&;A1TYs;`+ zNZYwKxw+W8Ykh2=upi;~pU2NV;Y)uRIW=0Q(>H>yaq@bQ>~qFyfdx_Y{M&>(F?$fu zSwnAPkzQxX{FPLb6B($DNv!lWOt>&R+wR z`5TZdy9C4cTpn~2RPWoTw|+c#?ZEzF(78iX90-%jAx(sBH()BGl|$6V2F+e&5PwC7Q0;N>{u@1B9{x@9Lq)A59G})_{^o%w;a&pP@Q{b zLNCbSMJp#}#eC`4LZ5HE+ly9?=&Pl_0s8hFz3BS^X6eQ?GJy6=qbnL=v1t2PVQFch zyNzrR(ytRE6&h`1gV50~6?uP3U^o$1=qn=|gm(2kMX0}#4MGRIRA_-qh3to!bM_x9_J8MENHz=%Aw6Nxn5}CP zb(t%K)Xc6B^?O$ceV9>*DzuqUC)5>i4^b7a5So%vh&tRALMLSuqAqoX&MM7o|spR8U9*!xf_HT_L2g;R;b_xI#$7!xf@#aD~uK8HK1PTp^^P z;~t`lY>dR3ON+on*Mj^`21a(4>W)z~{0q_vgkn>QYe21(P(l3;_LR39~ zhtSfDLX`f?2NXirWfY?Bc7@PW8HK11Tp{#TMj@)R4dFT=4Q|g|)C5-uX?(jPJJNG@ zc}5Ob&X)vBEVCAt+L72X&4jKtvO#E^^?df|hR82BuM@f+@FIwEk7h+EM#ZKiBn#PR z&+-X-Nvc?S<^i%R|2cAKe>kQx=>T^pcuPb-4Sq4A-vw*B$mT0Bc^cgg+&QBAf(J!( z68|%U*?Wf zF1gn*7|(BZ+}6C`h?^QRZfVH4p&{dThK!pTGHzwa+&psWicEepHbZ*-W;_q+^_%el zq}Ol8H;`Vx867kAn=vp`zZun;`ehCSa?#ZnV3-SiiB${tSN;`UoscYiWW(fLex$Xx z{jpJYI4A8jttL(G6VYvkGohzp5fA8_pf!**5aR|AtsZ_VlD`7p8qx2A)g-d{9IQSU zognUwfN0(Nt8}7KXRZdQWdQA<+pcQ>$c!37qfLSm?9zYflm6GPI$5Z!a>$n=Z0W+T z26;4wu7gzd7y-9}ynAOq2&u{;eHNs;LB0V})gV6tsb-KGWU3fsTrWt3EnV16LGGE) zyaCcPpP3!YGap6jna|V^^UPL1{1nnNpQ#b&na|8-J`-U}7n#RB%hR8@Vy zg^aruGVWE#xKknHK81|C6f&E6ixamE#i1vK)U*t4p+{UQq&jOr*XE4}gmz6L#a-x3 zBO8SL&Z|~vCOcvaGX^8OMw7Dj3CYoCj;Lbmw>lv$NUjj&vFqa4EzdOq*mD)Ok3Nv< z9U0a)iBcz_5K`$}0h4#NgX3mLC^pL8>`;unOS5AEpt-vg>`hVsO@c$1)xTayr;a4g z9h-_FdbwO^h>>-pK~r2R}2ioN1t)MMVJ_!1^6Y^^e)NusUQs31{ZDswP90aOx zvJy1G$w{DkCuf4@JGl_#EwjCOOm6vCIjnccoC_hnUUM2Dy-k1ezzAu+t_AcEEx~GFGjO`*tDYGkjqK=a zw&Mi1$CTc$Pl>B3FRZ#Gf}u^Hg9V~hv0;F0gf%xMS1mQ^CD*K11Bs5~=HfkISYU-T zkhNIVHi^>5U?_yD0arjYyY@tap^z^|4cW@os*d)%=gmL!9Atj>?AcJ=g~+XAGVrgq6eKr>mOj}Dp8>QAj`J6~Ed?ovzS{b(ASr^3 zX}KJk&a~R(CR1Qk67AV%N3^g{H2q(5c2BO@e7kiStkx7Z7NP5bNF(w_*9a}4^CL|a z^{WOVwkE1_#J&rwR*P6%?JA53!?}fAX2XuABZp~#3O^5gCP1;;5l=B8^FkP-McOCw z>?wrNWMjR)8g!$RH-qkU@@~);C*wf5e^TNy70jNRsrj_J7$d^7IY3BRnOua59R>%) zr8l{%;e#);9uR@+Q$P_Cd>S7+i;f*c=U-n&9=tu{zVG{MP9Ag^NPILolI z_mz)QN)0>V-&=_@%jY)tGLeHXq1=yPtlH|nBd)I9gOHc%D>|;Q=(xtB<0^|*omDo` z*|Cs!FGE?|*fhu~n)k(-AWctpzIbXv#?ulq+oPG?j52d+$J0Z9whJLmpWeaxsqu$L zlQQ2O#gu<`r1^EfyIB}ZdXxH?pPLmzg(s1$6%o`6oeo4_3W-$Vn|&!H7bz0FKgnF7 zBm!!b5sC<>QI^?O9(xrq7c$C0q$=4g2f0YWYj@1{N`1ayj=><#1PU> z$y>K2!t;UrNrJ$xaip}V(0o8f*{4wm?3zGIc0%(38D(#R5!h8kO4dSyftIuDY)17$ zu~GBv{D{lCp!02|c{B*AyOEN9$5o1+q6n1%UKCNiT_MyTNCwM$HHjDoxRt1C0Cyo( zxgc16f6ydqnsHidL^S}I38}p?dn>TN)mva(?vf-+#spVRE9H>IXtwumdk8vuNa$=p z#cbYWGtFqaP;At^hqNwJV4)HxNt<2rrwvx}9hIXD=Z1W`K zVf2rh&GcgQ(cNBO$bn|AQJ1~KjnLNt6jbPXAeylvb+T_ZV=$L*&xX#BW&yvjNj&Ge402Jq*~kjl$Qkc?Td1 zp?86(y+wZDZ2tFV5(>7Bg($xIL(uL*KI$5TPI0NwhgOybA)PC+71EP|fAbX6quRIA z3g>;54O|xoc11RJT^zgR-X)YRS2RIfVDDjto(iB4Qt4a)V;7~*xw=9tfCfQaD$x@# z^ZM4tWs+Ev^?s}H^yfkEJNY@tn;~;<=2yxPUhDdt{3w|2j;{bHp->|b^`6L$&gS=? zgo1z5duX|K1n3u`g+?|AEpn;QVnFRtYky(qduD^sX>KEQdd5c7dRGX2V5AoJW>-ff ztfNA)dtH;L3tb^3_wDy4O8cUZ;*W=%5E<9nE~5<&h0tar8-%t1UKvqOxq`IWH5v(} z6N=;3S=>pk5R!XKrPJ0>4RCsruV+6an_>Qag8e2$do!<>`Q1*+{81-KTf9{1{}=0? zGh|<5(y^2Xy=`Qz&=!`;?JO`kqfSoVeWKnl_c|fDx74rkhHpEB=P`5Jj#1w;=Y-rM zzq3P)n`vfKFQnlaO=XdqD9tuL2?g6uH>bv8eigo0+VY7kB}MZM58Ac`eYkF}fCQ9?npSh}@nG)2A8RX`L=q;C0} z#gb6aES8?o=+O+zX#9jGiZu*r1<)*(go0+Vu0eQ%De8r81fp0XH#wW%UJ?qL#d;T^ z&RCR7=p!JCCGt~e^J7UUXcntKV|TC(|9T-k7>{C!EO$0PmV|<4u~s2mZHjuKwLlb0 zncz@POZY~j+26N)I*)yM`R|DMQxm8%D= z7hKdZw;^qId8E2*q#247yVu#zb+~&@i{?i00QK1bGqXjpPn+Uc^*OO}Izq8jb+5Oopq@4E+VbBYKR-F7Y+F52BG7OtQES`r9$_(RA@8co}#w6g0zLp zCr6!-Ld&bJNz@8}Mi+|1)n&fwYhew}&YbTXjL6%$6zl&=^K2*oj5ufAi+WWk=Vj3l zSb9!qgpsvEBV8)Aw@ZbpjcgD)$jDluB}O)oX0B?ee`nDSz4u$Q`IL!~L*#U^%IRG! zN~4{g6w>r`g($5RD1??}6rzrIh0y7ySk41!QP&u!u_Nj_0DqyIO|hH@(xP58PG%7Q z=IVov?OZ4>a($Di16?7s5Kxipn?$X1h0tXgg{b=hLJ2(%xQ8f}rNz?+a%+$O#k`*X zcX`G6<+S=VWcE%##4^D9M%4eb3se-31`%EAb1!0TEK0-#xErA7aKaM+T1`l{ET%&B zKq*I&UMquMT~`EMj}3Ot>*2ZR7n^zQk)SJ_B(*CyFYP7DOSlpsFClN6=|VL?vGQt` z&*5mE23S8yn_U%1PziZtdzW*tONAB~*+81P=0g2@i`Z0mLPU>mh}6WjP3;hNc7@Oo zz!eb9E{|Y;Z74tQBvAtarjt+{q2&owWQMlA#Sx}k83wyTD2|YQE0f#&|GhGBw;Dyx znNT63j=*=;Uq=77fF4H$&j}A_;lFp|{BL!TJ-UjUx89o9%TS-&LAfUd71gi*Ne6lT zGiN<-a}VoP`>z)4f3t&f`(nH8ppM?A7E!xo&~8x7BB6348-ymhRH)XaLWjCkNHahG z$Q70$%852;TMM<>G!rUT-Zc!4LI}+?vLUP1>eEc*$%1EFiGBm4b3k?o@LsS|a@Sg#Rv={qQ0)t36} z1(6zny1tC!j*IYHQ9ON4t?QHs$K}<}3h2_yUR@m>*>4?)oD}g7M}C_lyOoh#qg7B0Q9odg-N2J|rcZN}) z^oWJv34q3n>e2wj*A|HTfd_%7f%y7H1oce-dN>|mYE!)-)U$Ct=#H<8pf3jWoLdjA zK#DOlJ#IXzWUJSdJC`T!g|OXUn`-H2lR|r z4{YO0b4dNGW#U%gPGB<-U+W+)0xkwN0`c_<#8%)nAf7kUH3C-w8-W{v_);791*(B~ z{y^GTSPVWAi06akOMzv;3Sc!5UnLMKb4OrEECg>)uD)LdoCKT+#FySo2x@_OIsKro zsmp*VfIgazuZy5B1}+8kdOyBm*`3Iq$dSJf{UPuXP!f$p`Lu`b2D}hZp<&4`#ert2=2Vo6>q)+aS1;hxtT>IS=1)g*$lgtnnOWunrze7*<@*9t~}M|%R@MyBnKo- znjDdE+!VHp>^Jhua9!H)@S-63({P7e-^gHKq9D0j`&>nGKvAqKj)>jU1*yG`yM#yd z)$@)a9sA&eq~orgNIL$o(@6K3!*iBY&BuL6C*8Xv>Ew%9^HTer&L5_vrWG^4Qu}`( z%i5!VO&I)J>toA zq({!5PkK~GnlQCw%`>D&w;oQqbfe-Qb6qv*vbX+By8QfN(iJaUPI_$lDWof(lg)8Y zEF?XC;~AtU{Oe}YRRbROGc_uDLBFJuQ6t zr=ZirVb6ii2!F)pl=@+K20fNKGwk&!=&bNnR`%4n;nm9iyl}5Ap!374hJt<+&Qp7> z3l}Kc_2Jc%K^KKXMu9ej2VDxfIP9mUxFmdi574FIVb6np9QL~lbXmBj3UqmRJ!@d< zif|BL?xY&SW7JYthA*k9t_lk{)ux)lcg_NB3>UJCrG6TgUje#0e6=3*v+(98K-Yxx zdDxq}He8}2T^F|I$!F^4;b;9pzX(tHHRy(L!aJZ}hATINZVbPW-><^t>7bj!YZifi z9X_O%+7uRa1N|m!R4?BgK5`D|mhh=RfNl*(_65BerkOaY_eyKmgYIg3-?N~*+xEIw zCw7gfpkFJc&qyBZ_GhK9@2vEg3zdHJq0+R;cN!x4`D>NVTdefd0ZMzRe}lKxU%_Ra zl`eQvX+QNrutl{9PSQvSKJKdY)ncV>$1B}YT@vj5N2Rx`wS&Xd$H73AIykqV(!yR! z=c*He*M6z=^Fx*PoT`-KkXEVNgC>jfb5%9?EUk2lx;6N#mH!*F`SZJyyz^tFud6SD z-S1O+WrNa_)yF}Jx66DP{Z*mT<1Lq7b)tW4ebix| z=!>jPR-GyOq;jQ4jaK@^D5bo8B>ikZrHwX1Do+-DQi0N!mn!|>=Sl}yzUwB6zVZO2 zgKe~|wjSU5vLwfRtn?&n)kXV?Zf8CI>~5m}YU6N*rdzP6gVKF0=4R{t8p~_v!z5pF ztI}1Al%8WFdB#Z5`&-F>YVFYDmy+}uru6mKlrFRJGs#Bv`1kw9jJKVFY=p(GhkNkn?M>OSwOP^4>;Si;NAEfldgy4X(jo6KUAuBjryiGIRH%U|CY-S1MRm!^~!y{NQ)2c`PKHfBV< z(oY{yI9((+aDxEzxa;QcaKy$uBXyJu2(w9O4#tU=nJeR&pT1{O{XgTnf2yx z&Jev^Cx_sG{gs|-@^x)R_q3M0>QT|7ZNxr)isNZI}W|Yzc zo0Q)1W2O54i&Me<=KJwl(QnOFT4ud@nT?-M%&XVIlCQG*K4PQg=3OM2Z8PPL!$i-S zr*w(UuerY#{o+$f`(LJ%R|KSgSg3TD!6AglIN^1_O<%f-zG_0%Vlqy zWp|m)Pwtldy+0}a4;xW6)~aJ|kNBOnKzmzZ-Ww#FWi}3XwtDGLic&!vYqvQzuV1`R zk`A{k{j;^$iMxu{f5A-;u2H(udbZJ4gD-9L-hP$j>un6|XtVE^2T4-eU1>*av4@t5 zuKbivtKeG||mX)pKJxTO8428iT z-c^J?)RFb}b)_ehHG6bFrN^vP+Ktwrk1Us~juw5YjqSNJMW171U>{oEPNH2ls3*Fw zQLpscPa|oU+cf_A%=vL-QSkl<_`ApQ2dVoK`=|m>Bz}59RGPLw(@5>Q z*K4FZ>r>s-9xwi!bninHdHUt^Nss=8#`O8&*Xoe#!fTEPZ4Ni7tWSr(I)&1G9=`j- zC}8n_E=Jz&ONK?^!1}(VyA8OIbkGwUNq3*xjpvVpk65}gDBR$1NZo z_SK7|!}ZWIRsIfvQzJI0ODfvzN4n>&bW*DNIyJz=Besz4|Ba^B+zsTFI_%XykuH5i zU4GoAy-8O;Q&0NC@JsdZx=??}!%b9|OF>QH18STb!mmbxZV7)#oWk4w4|#6_-$r%q zk9%}=5THN^5OyeA*$Gf+ zp-}d{>^qdT>;<||)>2w%X=!OG|L^zQ8EGUtg!a9De((KX_%LTQb7$_o=brtXJGNxF zw_7saJ1iOSotBLFE=z`dx5d%=?zcE}Sxx_sDPza~`8PQ3!DzSM^GFUn_ukuaobDwp z%{;IJ$AYgw0Xj5{lPkF$l&t5zgH_N~?-JAVzqc00+G#!<3Wh}cF$FO?hem;D**2FoOcQU!is$7r z-tv6@7{D()UvL@T_KYHC-}A&i0Qksr)_VYd@${_**rM+F7~psnJ^|oVwd?|b)70=z zfb&(P2H*nq>7f8us%MJ;u2LiK0=P+iu?xV>>Q$hs(U2)7mhSa_HdAs8{`>T~W?z8O(919YV9P(t~OCq3RpC%mV-n|9KeXrdO z$Ex*g-L!>BZZ0NPmmK#ljwf1+@OpW4kKE^R;U@2{R{=ce-B@Q|pImn?EB@I5t_P0mvV*8^Oj@<#$(sJ<8r zaItEj47o&wNzvQYJS-gh^^54=Y#1-ROKEEnJ!?}?8BTj7T!zQxsi**k|+{;D@H3E(v^OO5pJy}u%M|KR-*rPZh2 zkB$QPqqpWGfX}>7{21WR-mz~0eC|E{TL6FcUVRwA-@O-+Q2yba$p^mjzJ3G17JV^C zcC7vrdF(j-__+Yv^rNKD6ZG>Z0-U6e<^WID8%qH0(NB@>@74K*01xP?B%25I%!dIU z*1x$F;1PWrTRx^g{T;yL`iE};JgN7&1>h-NLYeine*a2^c3jEP&_rpGem~ z)9dyHcu^nG3-GdjsTklDeJvOKHGSkffY)^&Mf;n&w-ewkedbnxU+H{u+^_YPmjK?; z>-GV7SGV)=5ALwv@O2ysaHa1SF5FeVW48eO(0B4!fUA95n*e^~ z%e?^LTHke?^pAa*9>~VGC&~0i-!{sSn|x)D0o>x-ek;JOz8Vd1yYIzm0C)I)&2I1V zee^WI-M-*(fO~x0$*=GAT}*1d-`B;95BLJr01x@{IKYQ}$DIf8sP98g^D*CB2Ln9e z+y5beCw<2}1MpMd{Fecq_N^m#Jm+g52A}s`zX;$(-)EZvUh+j}1H9_n_#1%Nd@t_- z@P_XX69C@yjUftt>3jD9fM5B3v;yEazBM-jyyKfr)V=Tf`@H}k_~u;)@LONqHh_+VBWgo`bUYmXYCV=a+4>%g&hU`Uc05@kh zuLZaz`$n$AZP`zgUT)7W`~|?B*?FAwUD@B}kbaW=>=J-`vL74?aDVo%LjVtC|NKCJ zhqCXW)PFep%S!{%@UKh55DA;2@)H}(TOn|;&^0MBP1&9!|Y z`}6MtyqJB$wE!<=U;jIRSF#`44)ALBGbD}Iv)c{>_<6Qf2k>V0?QHp0_R1*0ud<&X z0QhxwHigGK*@{H;ZuTQn0p8F4RzAQ7*~gN0f15p-4}6sU-fDo4v&%T@-)HYnM1GR} z#;yRLW?y+ez@M^1ob6}X_fx3;C41s{fX}l(=fu9qewn!bd-gN$0{k;O_(OoNvi~*) zVC%3exWvZ}dyw-xe%SmxfNjIRmGou{tEs&*5ADX;CO#4k+se5TMlrd z|6mG_ll;Fp0^k(?s2YG%{f}1yobJDSA;1~_Z1Ar>(|->c=q!IO2Y-%#mmdS1>%Wlw zo#&t41#rIq1d`N6{t8a)Vt>JF0GIl2;~H)EpYZE?f3n6k?pVYpTt%9fj@`T zdbPj$J%DTcLDJy0{*U7T*ZEhR2ynfB-;V)q@IN;i;3oeg?C)lO#c=?)`fDkWZu6fV z1GvLK>M4Lb{bM-zyZzJ1w?FY;6#%%`f75V)`}`Mu2=IXaqwfGb=s$wQ_ppDg1@MUf zykh|#^B-~+z~lb1rvYB{YtH>8|FwGqyzGC0?DUHN=sf^l_1D$`yyida5`fqJyZjvB z=l)*>0p9eta~a?AU-lfpFZ{2D0eQ{;5u8pMeLo9Z^_Nf9K*ImI`9DVIAIBu~j zegtrgbq#yiYTbAUJXKH>cSVfpg_zO=Tq1N_ta76<>8^}=rfws_`m1vti&a}>Z<&uq3l-gD8#0NXqz zPXV0Zxqb@3iJm7ZSx)jSA-$dKX>S2I#d8|Rd8+5alK?LDTt{}??&;ujmw7(!2e{m` zq6**&&u^~>_`YWs4);n=FDHGKr}9#OA9(I80=UL=(0qU&c}nI0TJ=@;~c))WeU;Ut`jZBPe%Z}<_S?Ez2~Vt6ySZ&Ar$~0cupWm zedxKK9Q0dHD_7-X&pDjm?>!BC;18ZV$^bs`oJ{bk=aPDWuRI@+>bI!xaPY^dkIwL0fQT&Q|Ukr$~uivccH z{XYY^L|u~$aG9FQ)x2DN`7yv1s+XAfzN$|ET&d;|J@=|NhXLHDdPf1=uX=t7@PK;k zbbtrdX7>J&I-?TcVbyy)z$0on=kTa{#s~12>LUssSGUasctWjYlPA?1q_d}0e5UDfs;zN{;u{QWErU)psTUe5Brg8Q^#7-qipftKBrf-_)5; z0DPggbGUz3)h_`2LtS+_z*j2Hw`}o_T?=rG_tA2It=_ju6Q_C4c^cq!@AU@*oay}` z7w#}r5NdIv58_>=d{y#YS+HjD)Lvv48crU=0-iIg>{^>oKBIqmc zaMIuweGcjD7=0oi->QH45Wul|ANF^go_ia>@p?@yz&3p^XM2Law-MlEU9l426unz6 zz^S@#GQeqiDQA1SUb`IN3?1U)d{-axKERo}`CWjs^!7$RsukHG~`2d&c zDWtQ@^^wHHoqFwPfV=c3`vcsqYq9};qK_kQ-lK<;bMDpe{TARpUCZ^mUypba-~pX; z9>9b89b)1kU3@se!}|3j0UpuUT?6o_uDt@_G5s=!`=tKr#{f_171IHJsz?6<;AwqL z0l+i*R1);Fx}D4aobF`H=k+$qvlsMAqWow2i<yieg69w0&1{zBszdHg;c>%1IQ z^vvJjxah)LaBRMn1h(XLj=kki7vLEC6`x(cgng~p_85*UKWxMCfLFMF-}+)Pj)@6; z+rcFrIJTWba_U&X@pQh^isR~oiIA>gM8vx82XI{f)pi^={DC6$+Y6`R*!R!ZaqR!< z1sn%nJs!u6yZUh4)b%Kihn_GM$HTAVT#lF%!SOrUT+}0PAju!q@CJ@Y@A)Qvr(0*w1vty<{}I61RwJqM9P2w==5wv@ z{2btW)~-_k&a*CO_ZM5m^8qfg?jZABY8}E=*=}7*WdFcAW;VbNt-pByuC}h`%&xH( zQsP`|-TFMhb=L35$=6$vE`S@X#!GAxsCkbluRW*+$Ay!)ywT$*aTeVN`%N#t^+_D- zb4cwCm-gV;c;8z4$%z*ebyIJQ;y8V62*>;%@ygz(vESJj9f{*UtLktpxcLkmgZ>pb z7S@i!v8e4H9E%@nz_H}B_i-%!kPBM&C6Qm=cN&g!){tc?o_+|&xo2|N*LlwO0$lIe zzXIR}&uc{Xjh@%IoHu!{CdEDEIge!atY+hpRX7RfR zxQzd;$i9V3JKG0(``AosbR_E5we_!Q?(6NU>t5H{U)UIpM&gNv zaDU;_{=W9C$i4@ro;z^I&mEY2?!fwJO#<&b1l{!~pXlh@l;92XvP85ta$t8)`?`%C zomuVs9=HMB_qDALtmY5`vo=?h=O5VBvoSEx+qz6~W?Q$eI0r0;5@3&e~%ogYBfL_TIkEMEm;E;F>J3HEt)GJNvpftm*7K%v`b? z)NSl(Hy08eovYh6t{X@U9JZmeAJ;&siT;5OWZCcotWz6nb{p2V17KesLS=!3dgjwplv#dR^%K~4JPhNT%KRh|( z^bFswdUznHts;+nVm{g6_iQjuTeu&{)gE7=_WN)p1#?hhY-z7g6;|r8a!V}>%C&&n zqY^FE`k+=h_yhKARjacBwQrstCoorg)dWlD;YTQ_3j?|!pvMN$Fc)2pM?-Z;K<|pX zy9M-l*1 zB<MIJ2j zL@pD0^ZD}G&m@jGpeF`&G(a*c4d~tQOrTO*Ihn(M*wsVHRE~F-kk&v2sB#y+R*?YD zAtmT(0i74XuR=W&zosvj)44cZ6wou&DMtm=pYZ_JZ_?4H=;#d7(eHQA z(dmOb+6Ns06jE!jnto{o-lO~>X`?P?~w>6=XU z6?Fe2)BTG(=>D3)-48X{Dm@D$0of4+u0ajHs(i{1p_nAtVU2n(JUTg`_mq+A0Des| z6iXHlVd?w>fZCI#|G$|2PuM~Ke;(ZbQ1h+Qxn?O-Ly=Jpx|(5NeByP~lJ@6Pi`fQ7 z5k%W4t*1dO=gB2doR8EK61MRAR_HQxxFD!&f_i^wMu)Q0q(#uaeGub5b!bo?h3=F` zi?q%Wv}imHb*Za^x-zKu1sNLII}O*Gf*Ox?1rhZY$!y;mgLb#a!*3w$*a1odnK zd>Hi@-vnKNF$8fArlhLN=1ZsA9aagnN@y-%biPFy#>h4L8{%PZaxz?ouffAa;$gsz zhvMX;|4BTIr}|3bq4ewUFfbSouL>T<(c~NrTusF?hV&jjYqg$Os3+`&pM_NZdiP2> zr77rJ1T+*u3q!9i2YPcwcg&#Z>-MR!umNVm%si};n1?Y+CF%7Yf;%vJrfF{lDP?2u zU+#olxR-RIbyQXtZ_S|Y6VV3dGtED1KTIbV2FpI$vm1s&lQNH%-m<-F7c3ezSq z+L-{!No_C_p!8qOr&k-&&T~IK)X3Jt6t$*m?`+sz<1|`S8`dv2TimCOsObV8vSSDu%f)0WrBkj7C`TP6O>rkOqurp+c2HW-xBEeM{tY z%p#l`OKw+lIsvU=mu5rwPR1!vi(%skSu|PBVUlKJ3e*HJWHEb?bT%+UQ9XeVf~0Yp z?OQA_*mXHh&AVKuKo%Z0N4yqxiPLE4J9L+_eciA#*~3a39w6RXwyz%O<^4i&s|fiU zi+B9dmChO|U-j3Y&La}lxJrY~<$V0lS!V4WF`X+*kd2kt54Wq(qoohQfC3sGoe;cf zp)hx1U1(+=2>gtrmphoB9MZ#QFfiT*K?s;hG;^-- z-Y~G>ez;eKfm?d5h@G`yF@qD1l=nzGxTG+k-EpcgKm)7fB_Qy{f=bx8uooa|u@++& zX&Mb6>5GqCl!0hmtHo;fKy2{wNh`y!N{9lehq8p*tHfu9 zxE$u|9w%g40`DZK#~E2b^^j9ZS_OT(9_MSm_R%5V*83$wN zI}H2*(Rw6CIt(huzypXYYRa4;bxyV~{B_eFCz>B7E39f*YSdJWB0=e7LzGf1P;FAR zVp;dZ|6sX^!Gi_W!o9^S1q&J~kJy+Q)F2g&XS{jBymV1%hK*mVJ(V7BT8Qh8UEE@v zUWtiq4uUy@rFPNoG>O(j1X4pPM3NlSr_wQeyqg92h>vm*pg$43yBoh9;jE#oqCI`; z6ezxlxq6KH>?koWGA*QIp%q7{FA>ZGVQ-<*k$7ghh4c@9hJ|EAnux^tj<}ta6t_y9 z2?0y`1&XtaG|X2q-P_G z5zv+M3-$aWB$2Rr&!=GM;g9EfnbMI9uqg@ctG+`12n=z^(^KsBm8Sh32FS}mcthQV z_>^ZLuGko5EnmOAhxtaC^F%;ln z!c&8s3g91H4`2n#u)LD-OK=3vJK*cXF@HnOrg(gtBs0VH?aF9QloRQ&Ldk6sz6u0%01s(3P;+PT#14O4;($*2$IB_@M7l3d8$ z;RQCHif|VILx;%$hHR73m@RZrX`^6vh#M-knMXCvat^;3os^i!%hwsbdY! z(`eP$-+A!c5fXq@#XBhMAr`n0RIdthR!trNrrO0E-+hrt07?=I>2X60F!o5?FnpOv zr0M7Nl?Viy*Wo#}hb5+fH|WdF;Pd-rT+U=L_%3NlTatvuxeX2Lr7D2;v7V5?l$pQ+ zV4f}_41!<_GbryBg9Qd=#*JgTTWzxRaAw_RLrBU ztx6hL>guCW8v%mhk1nB{q2MG0nSIkSR+U2>Nb9M_cZTUj^N7qaiT;QhMO&2fnhJ+Z zn4w@15t26!xPX<0*!uwtYpD^zaq`&ifk1{$^-I*DK$O$d!J?6*c?wBOq%lO`1$r6p zl8k4UEV}5%jrQG;pxv6EL9>6_@q0t|lU+8OY?PsSffLSbFkHEV{$*6gmrS18qX}h< z=Jee;OT$5)Y1-Obd#2e_#jHILcw}VgA>}gx2j3#5{hcHnigZNx7~~+g17*h`{cJoW zDiz5AlEI#Qff13D)$>_olVX`935`8iRcN3tKN?yZzYtTzFDxQaUWT{wx9J19B#~K2`N;QSRtAc(eqK2bV0yQ*XV+c};0k9S#03HR? z7R(H$F}j@nAO>Y}2Z$L^zeDH*GAo3x8oJjJcpL(oz0#Z*Hq-8P&$K>AisJ$4XZoc6 zf)58?LBtJXW}h5WW}gq6K8=iZ#B4uQi&i6%npM6v+Ph8qWu$~Q5+Sudp;G0L%2>7K z_~C)eLwz)$cU31Lt47zs%Jm%xw6OI&R%`8=i!=2(0t}qW5U-r}Kk^19N|m`2L>BNnu)SbfRvx6M^D0q!twShifd}(WYqLrL52++2&0zyUwX0> zpQL;gSD}y!W~~>xo(Xz^HzI?`H;OzulSiv948UD*$!0n2sm?zW$sqOV0;HXShyj3s;YnUaAyCPKJQ_bL9PJ`Em^V%>K6y=QsT>1@Y z)zJ+5^6pgoUYQLSo7}e-9*m@5fCu1c+@hqnKbBX5Jh);86loxenUrBr^>{+?NW4`^ zQVN)d?tx63Bskw}&;+}ZXq#)}tV&lHltP7|8Zte=`=@atVUuzvc_Mb+Ay};8YBvZv z)}PK$phVAnJ-iMBGo_~Vnjv{s<0T3swA5B*hZkE%RQCGSxssnuiq}ZVmL>;3`EV`QO zx=`+Ra6CjNwFTV`>QoQZ8+GhVL!_gY;Eu^|!aW;3O^?_c7esmkHrRAjC`J~rkT)Aw zX?ZToW={g~ozFlVtSGt^t_ zs6{|*KsFx5e6GZG&Xy4)VIxi<8y>}^Nw{5%Q`&k`?n@fPFOWhbDOiX9{mOyE+uK&f}KSPtPB%*=JNl45bgEd3KU=08>L0EPyuUVTiI0AcuMkY_vImPf57VA0rdSVGn1}0YN zQI&d@I=oWnmN9U=kA#n5fAY>EBq6$K$IMa#2$my9$2div8h}-}7y8Z}Z-mA89Fe6H zRUZm+*$QuF&VR#f|Z) z)fv9WMI2;O(2mQY7oxrmc#nh%4TG0UpeRoSr1*NGP$nZ&=urn&`V?YI z)OH&F%sdd^8E{xI%TMtagD*Y$(j9g=?SJqck}0Po1tU#D!Zab2f(1{`A$n*}i0sUh z^@ZG~knpO0h!5N<3+Tl`y|Pkc$+l2c3j0(q(r~9BVPL`_=(ll^J{VkKBrtu#+JJ5q z{{UVycn)=p$Qdn?E70p|d|)x@VWvp@gDMwKbN!b=NG~F?=nxX0ISjr~87PKDYxGtv z)sNSfgD?u=>Z0~+0*W(-<;&DEs3S*6fphk#r=g(nwo8sC64bk}`xu?Vy+aLoaOtN> z^)qBB=7xyQp+UV3M#_26BMVUa9Mr8r4fTD5l%%dk9Y6s47FnhQISS?F0e`^IG&Dt9 zf(v0na9!;4`v?bpgRxHg|8=8`#eQchP_&!SA&imn2v|S_u!O+_lB7|~-v+{FM>|zu zshE)zyZY1zSkxSKKGX;CjpbbnnFV5#$M*24TJT^~I(d9}nJBN8jP@}yF?0*{? zD~sbY@A;}jNx#NGFcG<(|8}1LrtJs6f2>b|EcQ?bnPvUg z(6_Vcebf8@ua|+vcqD(PD5W&H4D@?>eMgYC67TN_{#Wto^ef3N^usNA?(r}_&EL*- zr$44t==%jFxq>rzG6lGXLMS$OoigBv;1V1`k{b&Zk@R7k?o$X3cwoD!9z%cB6MX((gHqQn&l!9a z*%8u^?UorwpYL_>W5k{_xE-(Gj@C8(xJq*ggUo#6gjm?S@b6tkgrNg)kc@tp5jnq@8>%EEHV>43d-{NnR(hafskHuFB z1)19Fvi+7qv1CH1SwLopt_-Xa-sSot%niH4xgn?KF%$^0&0Nz4@dXb8{(M;4tdvtB zvM$-9h4;uW)5bn!%n{b~2m-i|d4!0K7*GNLLm_HFfdR$~b4JLyK}oTgL-hvq9P|z^ zU{28EOLH7v|MyUr_;*kzNIp|$FBm%ZU&f+Yg8xTY1c#=um|jKmw9EbSqtFB46JG`E zo=brCCRlp`c&Jr4S3$i3;k}AN0qzMDnl-U#u;VPSOF>Brh zAmM_HNw@$cT#w1nhEN;8;{e5hWW50uvv7rcrr&p2C_ zu)tyaU)A@Gyt)@a9 z+snC}dX>zg$yc(c@33R-e-e?!;Ey{_S7LBDJ6;AyUl1l=IS0(QpX7T20U>dz5Vzh( zD+s53IhXFUod6MjP^{>cz8lm`7gBg9aIgE!`aOE^5mZ&M24K z1Y?+{?mJKhrXHFaFk`ywK)zNFA1`tK5Jc&;fIaqyF(PPL({8&NJEJo&Am_8#*>3hW znvoKPRO{tbD5D;XouhMDFTps>IQYV!W3vA1&!V{dks?UofNzjHQ+s_Xob+&35#ue!YQ!*-`n2U ziHnm(97F$Z5UbH_6SO6)iEo?A6-pU~r3q&N%GW6zSENc}9$a1XZhQg*udfy__vY={?ne768g!RkA%r2bcKQi^TN=)<48C`&&o7{xOFB8 z0(Vg7F$2U1NM|Jd$zDB#&X>bJsH5Yp0+?&=vpK0A(lRnHkwdVSl&> z=v5tTfRHQyL6o3;euUZeWP(Y+xjZS@mqrp&VSkpdD08wW&gNvDe`ui&h561L8#2ij z;`JEO@Bl(KB{(^pR($Tb-PjDlL=Pi|5=`WoJ0D|lhRC+@wmFlqmakM;TAhzT0OaL6 zU~8JcQjs%Xd#c6k-=7sZKVHhj%!?3r$XfhpDQ2EZ%n0rnBz*~{fDsAQK{V`Bg*Z;C zgfTJMtcI2-`oWHot-#KB1aJ3(z8a4&THuQ!f@s9#_F~ixMl|pW>CKSq7@89!P(O%) zGg1eR9|v^qfg6XT=}bTv($l&78Ks(7rM-BCBXli-{iJJoik$);#6mU%@nO%Q3V2uw ztxjhB4#^tD*;pkYb)Lo5qITI!@5#byRfqH`@dzQzkFk((q&3c@j!qhV+ce740oHft zLTqCTT!A!no&ZnVWk54g6@qv_-i;z2!52KU$$A>I7vcgl{653Z2hh~o9jXTiVHHr0 zxFA%Kw7CkP)j+r)6zUzW5%$=ooz7#40rpP|zNy-&X49c~J()#B5ATCWb1HX;-C)cj z4$m#no>I~(%OVfqauRQ8|DfRUTSDUGC0Gk?+GT_tDTVW3gh(D>n<3VBzvCiSP?C#S z-;I-4FPbgH`gS~xSV;+_)r-MrsVrjHl`#xy<^GwGKt%Fn2MI%lNR2z_qzYjO0?(+Y zH5vS|b8)`I93gkDQP+XLPQv(2R`4^7a)vq;Q%KJW{@EV=jcZ{-?KVA(ASyvO?{GDR5XN|SEfDLDkl|AmyG`4-au%#`4pCM9?mOnFyIa2meF z1G*^2w27#Ul;9ItL=2E3k@7=?a)GXqcp_}bcmm}WWf3LHcs(K?RX7O8imc*A$|q=w zT?!zWsA*UaiJKyooF~njLOYQ|k`)x*JQGn}GUaH658~KKK`tAT3NvvTEUuB;wok{9 zXme3;F;1%0p#87`5IhAbIfk_mOkS(eNC%mU_L&$AWKWJBg)j^(s=d(`GFYSq>aGyj zXE6d1h~yy@H&cjdm%$`#!BVBss8gPTU-dZ<@w>Cf(a>M8F}=Qt&i7uBG${}026$Ph z9}!ah9pvz!l;KH5z%howOy6WybywNOK!d%b$D`fdw&F^6u1`a=QGgs!Rko$$Re zk#eQ!F{!3o;D*5B!S+eo5*DnHjNHHj?2Lu+C_5)5nQi9q0VQ2U%v1DKQLyp$RMF)j zd>D%EYi`;vhFsvZq}~F#EyWqmC|R(Gx;i$PC#QCgVv=PRD!(@5z~BMO*rXJ8(AXHv zEtW4q(S&#ZYH;^QfsJ|;du)d1{-v>fYE}px*l%I^K1v%5bMq7~Ik5&W+SoE+Rqkj2 zuiy#X2YnKKJe|N(AOiF!r_^vL^sMyM5v&QJkyrF zUGCQP zVV>cxvn$DI#iF`AX(BOZL#5Z@3q>PfIZmVuGvBH*<;D0c*Ef6%$_&3zZ~sTytedtv6#?eYqz54u4=?rX7azW0RJqUuVj!a+BivDxqIR>*mV zY8fRQ!yXv2xs;WYe4OU&LaWjt8z(25-nizQHMR%x4O^RW{O20i4q64_A}$XV%?{a& z4Za@lzMyZWU20=C5Dvkr8MNZ`x!5y4Ef#VDf^VMPMea;yY^?#3nU(@J?;^%A0g{sr z^i)X$?oy-+5Nd_YD+cF}EU-`QEFX=_Y_+~pzM}*ybOM%;t@C#DtV#VLAj;46(@nal^Dgu!PnEWP_MkoCoW#S#`&^LJQ3b>I#^Gd_zbmZdkB7BM)<_ zjMzB)P`1#qu*`Q)nJ9R>RDPJR$Y4$k5u;-ah0{U34!WXJq0qz7psgnunsY2x1`E&} zlp-dM*;9#v9uM@XWP|xtF(Cg-Y^>r-#Hvy!qOOMv2*oR6%>;kY0V}UWovNQ_nO{m> z2d~E6*lgKyHx|h#0knzGo>IdG70qIKR<^J@$7bz?VBP<}SN3-Ph_a2Rv#4E98u#&lbk2_OP#Akms$Gc)@7e@M2=W?d? zXJD=f>rs&yq+qpJbnCnj-zAu?v-2^j>Eb0ao&h9+OG%X=9fpl~3QJ`;20~FYf}S2L z+D5H*<|wmsA<|ebf>ZhED+|(Kh71d$n3$ekt^I`%!!bKY-5!)U`Seo2_;3uc?33ZU z1oR?f)vYi#UXKAs8W1*spCIF~@u51B!%j~f)NsXNrg0%KdH84RDZXr5&?YOk;n3I! zv!zhUG+&=*RweBdbtro%#P$MW)x?$!KcEwjuQ7EQAL~L3p{2$Dy{DWZhKfbwc7NE$ z+~6-owUYb+@pcJ;{NHS|#z-kH`5RIhLK}wJHV{u)0W)^rGFV$?z(@dvFIf-(sRn4@ z$`w*mtAR_FmvFDMM;(K>qJ%k3j?-g*r&|K$!b`Rb!WE)VLVqwpxbzuOyN z{@X_7o%!E8%YWy6@^K0qd7N{-`FfHYdH>F9ziu)9Yw!D?KEA=k=bg@F&e*1NPl=cy z67U+Ohfjk9GU6UksxA1TTkL2-9O^(ZRAHp}QH;*b955=@7~=uC91oIr#UNT-hn%0G zwl<=n`X^#RjCqor5p(`~14LXZr-NIC43lq#RYAS)1UI;6$r8a%Jz7q_po*Q$lgwbp z$C!X-D3M9G5e!u1N`X3{89!1vdKLzZNGL*qm<8DnX3`jB^3dki@}G_VG1@RCOBfXttn{}BJDf_QYm+mNkErUDOJf= zO3|CKiz%d73=Y-L0p#N}7xit3LE;zF)_A1a=rQM!>AC#wEAM02oa8hp1`KHYR*?%h zJM_BbnHWB_!SF33wZUw~;} zmDv$7FgTb@<5-CazDZHdGZ3jU#O^t~}plEZbxu7IezZf?M)@)qA3fDqewaem( zaJ;2HQ6FoKER9DRs}s$={rD3kS>d{Hw6PhDTg{v5YNByIQjSa2&EZ(0q*&h2-kWG? zu5Bt!6gRYO*wEe6g};l-m^5EXlRJEw8-sJ`C}dpO_+EB2y2Kfz@v$V z{P~+xp}9%OQ5(bqmmWxYdjqcxM+e%q3PI zi8MDgMwVkiIOtiS*7`tYWnifLz(&4%tfd@l3T+MDJvAFw#|}5|DcU^8ylIFA&WoCA zJ2!9W?eE54+DSxv+WR`!M|(OtH-jkZ>fCNw6qbl$W)T3)oEB#+w?Vv2bE(G#0I?kASoV9Sg%)5^zU68eUu-9s*yP z4P>5tG~C<@YKk^A*GC#6jd4(`;JRpYU0n*@gB!{7iA1z9o~Wyi#Y5#bLV(-V=AXkF z6^WjW>zh{BbPx1n@bwXC9mrdghhNn#4VZFMBipub?Cb078EC4F)SAC8lU38!-&x&( zKmF1lZtH33?CS0xz+ZjAV_1UnQgn#UYoiOW3}q!L4sUF22sbqtLY{?bm{}wRfOFfP z0A3{{4;3XM%bW44k_tC98=@>ipD}b)9dBxgg2QC#T{Eo#5~6iYXtOdBs2DsH^c5(s zFaw7;X^1x3oy{r;6_@3+!{VBCz3pq`WR2DME7O!Ia~i5+i?QaVMOiJ&n;UD1q}APh z{R1KJZkA!_`dHk}MX`v(-*t6{!{u%xkcz+BgtkdEM3#qbIcP7p&0Iq?urbB8qC8w$ z*9@v_XcD$v)eWLGERk4P9RoeoMH{2>6=V(RIs{o)O+w}99eS^`$-TWdWM)*x8HK|X z(TV1kS|N0ZjBcCdn&U0C(Ym_9hz~Dp1_dlF#{*^fqd{#0omnJFE)Yl~60WaqiPQ$% zQZn2EMrnyGSk{x2H%WTJvLwl1RzXS8oP3uEsqR0lC%kTLw8!BO8(}FKl4@aNEEZl^ z-I7=qt&J}PJ}QU-s*v(TTSrHqvuqG_buBFs{Lv+&j}nQE_-jTLiGeH-e&+xx#3YElYs1Xj2QZ9x7TKC?&DRYs0bx1l_Ld?ddXyjXnL{T|J#0SXVM&Z4LMym`#!|bWmz? z;PrS*m~-1PuiFiTa+5M3wxTf{uWpvngo?7_Q2o)RA$?Z=SM0j_DcoA(5N3GmGGQVc z0cq1tDZYkCLtS-iy_isgECtbg?iLPrRy)KBo1-B{0UM3AgnI`1;tTs$4G6>8mQP9F zp%_U$v265Bs4R&9;wTWB<5I<uYzRj`gs+g){HyhLR0CrTT$6<~$T~SqFHJF|m`j zbSx4#bYR#ZJZp1)KsX3I!5@P4C~Y5%rZ%=TTyLa0=+S;zC=qU3w{BHi`&yX}q-C<} zIVm~Z9BGL*FO0OTpi_~uidtZE(++d^W{^dcY#^&B5^pIC1gr$qZDRyl5(-#`tf)7RP7;askW#=F-;5mOUGb34L|l8VZ*j^0Dvx@ZsoR;7bkmoiPi zZ?i}35=Tvxm!KcpY$&1G03kV~4;U(MUF-}gl=9k0VRK*vHq|v(w^TR8gx4siZ8O%H zCbWaW5LaRWTpmG=F%AvdNSw6Gl5AE)!>ovX_H}-HV`u*WUJ&hZETqBqQU8X{&JMJR zx2;;&+1v{RVOc1A>sldqNq6BD;RbQD1`F=NZ3I=EUYTt;LS%=bjYM|Vf^On8#IhQi zTLZIZ;h3Ng7T7yK!1J2wSR|02)e?)eEREC}+s!6dGfBh!_R8BP3=~f!Or_{DXiF-J z#S_CgN^3heb@%u72}g<3h{?rUY=r{+W;m}6m@$NkTY~SPiA;4BEoRCvS%`=@5u$$$ zL)fYl^3yR}9Q6&e&ao{;ec9-$AT9AvNy3>Ku>Uw@2h3PXl1_Uat78p;M53*KJ(||U zYF%y^i6y=q#u!EunC1MctPGV4I{Kjw7e=aE;x!0g814sMfvF=Y@*(xWOK^0)%YY@{ zMB@^`XaJKB!8Pu?HqY3O>L9b+sPSUR8+wy<%|iK!x`t|at+qe8G~NWht*LLK(M{JI zZH@X#`GoE^(j$aSiP-KXS@A?`e`jAq=lb5h!@|9w>&*jM(Z<@ya&#DN3T*0K*EWDZ z5u26r3`H`)hYDey4aLH1b|^sPSYty}B)l!iApPoujB!koG0$x>=8}N`%MB&O!aWp- z(8o{@2vL9+mesV{GfM^)hHfJ>vtL)5NGiCbi3ARH$CJcv6cOXnYw;FFnD7#+p^Y0N zk#JU;w-?_W8|d61L_wt)XCW=y$1pZ~{IT7e?HW^yp8}%4VGk}Q2h%x&^CT_zn zVQ;~Fad8Y{}XPsn^dLJ04#slyv#TRwz!X z4r9FzqEbBE0rAn^8R_fm?K5i4j_8?y9LG&f+DMIyz())94MG_ydNs6~d0$r4iMz#? zH6`t0n-Vf^IRpUy6^{!6m)fR={;t}#fi_UHs7BjHlhB8V3kqRFdk_SO4p8m4#uD*p zL!_w{aWE72YlgAX5?xC1Bd9L|kBILIT*6gwen5bUhroD}gw0~%-b7Q!Qv6ljEN38T z>{DdF4WnzQkJZ=Cs%}{j+6RYX9!l~9vyKSR$%F$k5MU5yK`2lakXHHom2@Y}H3=mv^Hx*6Oe)>;GA%q2EK;Kn|9OYKle8#WHuOAT(J^#?mJQ)40`OzLxd zE-{Ra&ow9A=c39Id({puiy^bV-_habwgi1@noNMvF<9&BvZCQg3n||nHeC%zkP@#8 zVQlz@-!xhC+oHuO`kQ^+D-A7&8305GF@-rY}aC&RO`jjK$A zHr5(zi7d&gZg210FwoZ1-r3OBzg7h3LWx^P!f|LeBkQsjZ0PP4)t)AhTZ}+9a*%eR zV>y71o$#jP`NQu=NEWK68A22RRA^B6ZjSRNLUC3>(eh9;auW56Q)e#U1?~dHaulu~ zCso;?ackGNht}$DPu#2bRB5R;?{RX4E zNr9qZVGcx!ibOeqoiQGI#;Fv{tXUns8)4Gs7YB=ri%Lt&i%RDfmlYvM9_lOzmE(z~ znnlJeZ8c#E3H5WGlP9(mcY@F)h2*{Di6fh-a7&H6rSz_+Kgj4=kHa2`MDyZ>HSwJY zLM)&y{=P;YI>KvK-iEbnRt=2%ROd5!KgSJYA*lnVw&j=e4?rNfU zbz*%#LPH!>%W}90NjsarjGdin=rzDPWB(khh#lgr%($ohYkK=6$U{5PE#zodz(@pU zOFV@LbNJ)QcgrxLOI=Qvg@#>}3wY4qAwn0FNswxZa0Gy&$Xw~K#4658XR!nBX zvqCb{EIik#k#0QVT1`vEK;#4}jA_kUW)ukshfmVvLPiQ5)+P`)s4ot7Fpbz+jd;(n^k{X;@B z4Q<`)R`qUfsBKxu(HQG_!Mfg6ZR>1l$ewI*P#Zxk2@yh3P^H1SrA6gs<)vj6rJ>@| z^0Ly-f|BA=$zl%uCI(>=sSfLDxl&1{I6SE`O>`TM9qu5uZEOY(N zye~bu?o*`IL>DZGAY6q-UeL&_C1fJgYfMp9w}clWU)ChCALEH7BY+t5YUGrfYRv*W zX}j>c&bGcRS_hmJpRr?VqGnyOdMA)zaw1OrK0nKOQ46DBUt@r|1;N)e1J&9VCcD52 zCByp2N+BtQL1K(^+(IiE$cv{(q)6fr$s|S4FPLbdla4{c!i3G70JCGDI}icpVl-MT z0wOJX>TL*E%9x9uk`ZGm4-Bp=DXJ0jxngPF>-$prIof;kGSZ#L0kCxOH~ej$|n; zL^dojY#3jeSQuSN!6&aa$V57zCX|#XMMX@y3cA8z`&fLj(5KvY*Dj>p6m+@eUzsES zq~;>CK*WuD$5DlCWaq6UiD02vj<; z01-w>wO8ZlJ(G2*<61`^Gbjxx1PTz@&g4%;3 zJEIn+4*4%euQ7C#3c$*AhAzYnG&WJdEv;^m!X)+>N{=!FQOL1|O_c+@6$m2KlcWMk z%~4k%2??e8re(%xN#eiU#y`gqg-=(5#Vp1+S|Zi8D-4+-PM1RA;5Ih3iS1Yt*#rZb zp?W75AjyfL1xThp!UaIGD&>=8+CFtn^-glRF4hzQAtZekM{a_A94D$3_eC)!U20&9 z+*h2ctKzJU|C{1on`~Tj&TJtw=DOA*K$J8Y@xxe*CW{K56{{>t?f`i)cN4?vIXF$` zeTHr&eK?64mRO;f2^oFkB(nrX{+V?ds+qGYZl|`p2f3AveF&5G_Bi!0ZZSb88A!um zE076m&kwX`HMDhgx7*1bppPVodrtOC3?RnKjGBy8*FIt%8&0?As?*cu3jLV=24aWI66y%6q&N&>U`I-$1vJM#kvbhWn^R1~a& zz-(U==wr?SNDCB~&ncQydQhNXefx%uRqe3$J2w}sFU4;u3j|!fuD5NVplwxm)ta`x z4qiaR)f+aI7W8i@=m?eLN?Tw1nyR+G^_%8&7ObDWdPAU~t0Yj+)E_A5ALyv+>e+~a z6|7#5{A*iRXTiG8p00s4RYkaD2&RH zJA?bMiu>1?_^2R{l$&zM@XKH?qm&}84kW(P@d1)%*pQJ6mvM=py)E91WL|aHKxaDw zH^zmQ1iu}Rh((qp!m)Uu%wAeD4LB}7}h9=`oy_!Z{u92hCDp*=nTv1$7T3%jK zQC3`0QI6WV3Mn}x>sO>g#K>4gQPzl>$vEOiNLxtK)D-+A2AFKL#YI|mrjy>p*u-HZ zIl>A-Q@lNumvf5w?5dO^P&d0TPnX^f!MeO_G&HnL1Ym(sy9WzPIK%{aU9l2zHB77| zDF-VY9hRoO%qwkCOpJ2ab2(}!W(L+Lm%_LZu^LYnw3Kt?PJ(qHHqg6aLuZFk^T1eQ z74v0@{_ev&MeCp{gb^1T*pk#8Z%J<;LJD<=wcY(pSBfQsK{?9Fu?-Te?lEclz|^Um z@jt3uB{mUlfMm4GC+1`^dxYzdU&ffONah(Tr0mETe2&5Gn18OwktwpRu8C!_62W8v zB0Xdvr+k*HgZIM~!+7nbq8MU*4X2xQVuj>Vk;(+BGTX)Qin64ZuUODhE%{ik1q{Fp ziwSkFk($;8J5F7SU6pDjs7$U@JnW8DQ8czj;>6QMrxZ9%TPPq8SjmC_HD9NyVy6#{3D$QW*{xK_Yc@6o7hpQ>@dmC zZ6=yj97x^eYF7hwhV~nQAC^I<;S+gO7ZKZBk%n*+S75G&J|SzHQn$s1hNqBGPG+1( zSoyXSX&{7F8eIc-NMOUwsA0VdY9*p9(&dDW3FxZbPB}!iHFF%bhKA(*IVr0n8L2e% zhH5<4GuJ>kIKVB)!w!)tG{<+Uwda_ z!+^PIy1CBG}EfE$3v9T2U zkh++Pm!dWkKz9d}VI4qSQ~xq*{ceN5s+8zk?0xT{Qvus3A8qR1nOlIN%J|_eVOyN{b zll>!YbgsB6@aAX$$4&#r8lva~1@Z>BE*~GSk%Bcdza7-6OU)9*6bw~QnF(xSRTdC6h@nI^ieifAV(Qp(07>P_hZtlJUCf41gAt0L z!FXSH7fNk8D`W^5nMou%jOIyn_kBBSfZGRP7Q_}-*V0ddTTc8eT84I1u!2ik#ZW+j zRt6UgGC)p7&!h6Xs2F9J_EJ$V$WoCt28n&)9#?vJPy@5-Ns4vHYgk1roMi%#lz6iK zbF-xEH|gL*NI1o(DS4HwH;CH-EtZim4sOa1A^a%tk?sm0nU853U21GT>duTytktdV z>uWpADK-+TW~dMoq#&P6D$o#WXfRtmzNus5gegE@?VU9n`%@|UIksOlL<>PE z))zQo@i=Y1q%c9M%q9%me2uK@cl3Ko6dBTq%kC4J+DzLMakgAZB}uS%AQ`1F;ZT#W zo3qel>i`*zb866C9Ld;MdUb`JLj%nx=OoLTNkH84lU(rpEYTA5&Fl%am{=4EJlxcZ zWo_l&4=4+pX1iRsR2C70KpQF*o^>oLQ(CYvx?mwZ z2B6rE9z~F25f=glUf?B{n-(c3uN|b@QtEpSv|lnFiaOU7D0UF?cNC#JURK0-nY+{Y za;7)aH^C$pil53fzh>$>Nu$dm1#Fcn&WHWZ_pa^d@ zC^ZoSs}aZRkv@*B>s*gu2{axOUSujqYor1g-1dOGc67>i$?>>jAcy8U(KG3rUUEY- zMv*i`#qco$vpuSee2e5;1)1hX$|scH94l&pSEH_qx$pjd$$RsKR6P_RuFkMZPIAZb z%$<>#nj=od4&B-H`N{nYWhv_@El(YnkUW@^D}t;{1fdY2AzL83vruU+kC8$y8XGbc zkQCM2E+(>CtO`yW>|*C*k{cr=tw8puaD};?IK3+{O6|n)C8H>?eo(9>Xd}r&rHHU8 zPvxu`^r(wQ>ZRs3xx6&gnSZdiCo)xpqGH)B1h$i?u#pu~$F_9G`S{d*p;f02-cCaV z^42*Ur|O!)#C6Ex!0AN9Hqz1vCuM1b<&e<3&dwlXe?tf`LDFiQ)tNDW6YDoBJQdn@ z>WHY75mz&YdfOqreN2f7R^V{1L{Tz>L5&M2rp3KBQYmR`OHCz&h`XjzR1-(xFw&4^ z70F#CMlQ3stiB$j9OQq|BE=%wipkd0U(-x5D{Cy#D%R(@nS)}<5#X%vcQmufO~E~s zO?$N{bF+70Fw8?jOj1L{P!Jdop=3c-QC6F9Wd@lnX{l{sRU|64s{d1!S}fXvO@Iog zZ&b6D+58(-Z?*mJs@}4T7L(4@4)*5;LI_Whp;*}~ODa(=s#K%7phYM@v31r?LopE` zsZO}X^)Qw$2F)Uu42;roptZ7N(p`wyHJS9Gs zIN+SWI|su&3mP~(mt4^|7aut~Gnpl6Y(hx~!&V$)aT#9F`i;_<+zmc>i<-$vh-6LL zLnbMK=B&O+2Bi>(b_4>TBM-zPbJ+)y<8&(lBcdCS9=FSq7&w4-7GdKobLKr+BBIsM z7GmkH_=p5nxi(Ps9Vlr+@H5OPEh0TB@osBu3>umkwJf#`ogR*5qLFb#7{wBNkcG4b zmSYP@D1$k^R2ZNbd!fwW99z58mTxVa`8tX9nK~po)^me%clIw*9x5%ZbumfO>yfJM zXbTu@DXR9cxd&Pk8czC4D)^9V8;{9v((IHrVzQ9%N>Z_8zEcVTP0VhoAtke&hC!n8 zRMR9zkgq1a$?J@1&fOhM6FZz8a#IgKi6@B_r2ZI+oC<>KNnUWSy~D zaoaA<_>h3TyNpd-!5%jWAs7aHz`04VE(W%Qlo=&rO|96Lm{nVYI2J@-($`}u0&A8T zfVX9~P26*aFay%WBScs<3>m|%NkZUe*mRS@?5VJe{Ua-a8-WDNmJlvxkYQFnq8%)F zb9s z$GBl3mB@B&rL`Zo`%IFbtA**->~X`cBnKxnFu60y`7NPPQ!!heln2K3%bZo_ed!@3 zuo$VeW3jB;wv*0jn8jB$MEKg&Zt_}qjnOx@a|(+TTVxP8#7mq?8rzzH*fo0&ItQFo z1WL>L2YT1bnivG5Pyk;5vGo|jYA9glUOMi;w7VC!Zw5D}D%Q-Ve##F=eN%|DJ#uy} zOBS~EbgXl-`SP(3F;ucp?ogblh%dx1II!v5mnlw$4%brw$X*>3P7Ruze5S;F5QRF+ zQ44c~dT5J?79padd$+D-T?`6m%(amPzBwot}%-)=7w+8lW^&@W2svl@4cap8y#Ssv1re32*FgbJqyF zw>02EsSUR4e`UKua`Qq+HYX$)-;iox%me0D3%_uHQ-%Q>8<@#SDQ08I;btc{%s8LR zkYt*ZVuQ2gWYk=j7!^#T_)Hp*LP;!Nbv&(fi@^{hOx;dgRueYUO12E%zuQ1d`S&10 z<8aa{0|&wh1Sgo(U^1ynG9t5r3` z!j4-x6e6o`%m^aaaqx=mhz-SJN~|o77~{h1hiYHb*}fL-!m!26Y~X2eGt-jRD2%U0 zND}!JMw04k?POrmWu;_E?Zm2e=hDIqrqx3+p(Z0Kl0Xp@NojF3#B5CLTnej(s!qaJ zju070n+RTn5wiQ#!&2I0GFcMeO%)R*3!fw^K*i@&Tf$;!B4GsPKqq6E5{-haL5i?R z$kUxfKz&@=j^^0nhzYQi7;}f^!TjEZEj&bYl)!#)91gQR5;_|Mll;C17Ok(dy|a5$ zXUaNr6NjL@wq}8A=~9kEN@{cP>>r5XZaC5qqORzjqp&CJgm=PCm^C*3lfp&wx_N+6 z!Fr<+o1^qr!Uov-(9x!%5Yrk6L5dcJ&5Lg>B#ID7Gq`ZPg~4~_p`>z6ec;OOEmQlZ z8pwmdom-h06CP}xCLn-^IjaqMOST}HL*dtJWJKIr<9yZtr=%*o){l4U1{!;NSdd^C z69T|RSm_Ni2gR>W_0vX#WxNzMm|PN@8|ZmAEpl3n8S2DC1d8(g1gf!++vMzmZURTzQxhcX~;7>X3bX1P;uQ6`Hd zb-FC>#0F3y4wo_Lz9&myXUtMkdk33&sE*t@R;fv#{&uR@uo)Ot>D+FB35bGE*RRP8 z`;sUcU^>ZCcsONd1;|?te>o9%2f}mU5F8qox;QQc)DVjPT0k-qet^4-dM5c+fkCRx z_R^&(QB6%%6jZ2ev9U`ednBq3K}>fLo0bc^vI`k#sgdptd5Vmt6y)mT3l%O2ZVYsz z*Nn)tciK1OV`sKWXzDAH9~#K0$}~{`$7(X4AR!h=yTuOeh8sY*?hS~*ArnB9Y57@L zCwyWqYg1caj1@uRwqt(SYsifOP`$~RE2Up3QZTm+d7q@1N$q>yftX1(5OPAnt78n; znC}54>)lwx0&>A_oXEa~OXUMH2;;9U1Zq(y(UX8xi|<9CCXOGBs6%?Azpyb%<=PPL zFI?K+*Pd+I(YGnso+TB$G!GmW9kj6Y=xhdYnI4h|w9WgpI)b7hY65opSq9oK*xGA< zBQImOANKJzG}|j(0^ZzVT`7o3_H*EXBsPQ*NzkSFMCkDAUihR{46~x(c4a6Xi&#qf zOvSfJ`v{IC)!~v85l#*{c_C#hihCk;btzHDJvGS}K%#+!lAk={D|ksN z0L*^oWUZR>F%ZK&pkv1bb1I&3$xiS%dpD$v&C!K5bqnk8g@6U7#3WT?Uc`?Hq!(&C z&K-3}Z9O(wx<*e{6@=m*D(Bs|u-OsV<;FHU{2+x{5CBrPiLZ5~e=ow6RFoj)-P51^ zsFBbdP+-@<(Q+VCP-iN=N}`9hhrRR8Bz`b+r=ry^?ZqO;ka0=wpg zaKI$dWs5Q47$TC-+{KqOUk`MM2cBZtL2;0F*}o$z7ooLBjHi)5G-qvgG);Nf7HEsU|vP} z_J7iptw6;ft5{-1Y@w}rp6skyyFk)}BwYX{WO)LGZlo=gRm6g9vLpK{pr8UOf*>L) zy9kP?EQ%N-PgqtvNco4 zVOjF_X-2Cdn-bk`9+VzPFPEcShT-gbvmedKdx-1DyKAw-=>3cM#6b1Y*3yCx*oKiG zIzDjTXF7{;`GNJe!!H*Of?aQs26yZ``0|O59VHO6czvL=MgCX}pMfw%ga^Z}{`UPA zpmKymJ$cV_t9q=Dgch1Jtz*?``B-HMdj#64o3n+Wl5j1%Yo!*x?!_kaD} zUA^caN=b?$66i4+8gnX>Vx=tr^nD<&q7O{YqFTdJ^Fn!lE^`Tm5dSLa>MNIrsRBer>88_jb&6Xv=4#4x4R&x_E3%nW zy-FxB{90*stQN2sWQ(<$=kMQ-YLiy=v!O(D(`@{Lcx79}Gz@e6;gS;2-XPzPM)Rbp zux$E=Z($zXI$C^5v`PocG*<|{i9?V-s#+13)jdi-TXUbQ3DrALtAN9bIpSib0UQDBEw7t^DV;4$rs zV=m0E_r(&IuAaVjj6AH%Tx07lp9 zSy@GIfb=9|&KOn?2F@79Q?v%k)x4h=`hh9Ih;Y4En^8HiYV?24wS%f482|d!S=Lc! z{*~dY%1Ta6lEo^sI1dh;G(+Ynml-(U&u}@xmnVLks6(E9F6)q^rgL2_{jhGO8&aC` zzs1`!`^h|KoXM8fxw_3hJ%Z@LWNtHNYugqz_sqt-&YoxAD)d+#mJvRzGBnl6gJ-0C0iMX#Mk(lk)AD_PU!T7Yz-880xd z4gj{FmaOWXp~A)Tf4d4A>Qs@*2|PD>X;HQ`1D-I`HJ(JU2{IEtHbbi*nYl|+pShNITCt^WgFiV=&TK@a90)xU#CdI*ABdfOHAfyVc zW$EyXwKOg}H`R{WN@VYm0Bd=X>+=~tpV#q3?u)B6hH079J;>Z_U215e-`{`ez$*0N zhL)}wE=}w0>tTfx1oih@AdX{44|fQ=nfBSu$h31FM(F&a#jrnROBLxXwHsMS&{|+LmKwuSU&nH;)k)Uupu6Z2o)aHZ8(AAN&a?>MDV&DmBp+A0a1fB1 z1E6W)Jr>b%BwPfrI&(U`(z2nW=a-Jc#3}uLXBPhbmDE*^w@xIHz22^_`(u+0<}S*A z9klPMBdJs|NxkGaUgYq${KR&VaKLF^Nl{u3g;$BygQbDhovnmda+JgBe~Tn z&d>ptyUsBddaLoMiW38TUG~DAM-$7?7UoQ;Etj(xn{}M^GokzSxAWbDOqFhWTUQaM zJ!n;UfeUSKnb+OcO+y;nHlwl{Zc4mPqdIFvIYnt6`r(Id0TwL7nA~^I=AyCSY6e#* z)vtFd7rqBGGD>hXlBQ|Y0M|>{Y3B79u7E5h*`4eI6D( zvMb2DHMr3m)@1VaYb%RvLS1!~b;~TVQT@?BMy}0(D#}|drxOM=U$*%IK9d==`MxsV z+V{k~${ZT=-n@@5)P@*?rq+;dost=?&0B;~ymQh3_y2hIDmr9ZF=GAf+(l?F-wA~c zKB22@0s~;RuIeAy@}KURY+P|LjSO4hCT_t>%gvc+1tb&ggJ)uOva)9_?q@?;7KpA9 zq-C0pnR=g%jhns2{ut=lKuduI%yEx=>=Ag`>4}?E!EwzpA1~%*+Z9Q0ON>x*st%7crH9GlWsJ*7!X$DE{JmEUaE9Y?`cs%bC9_l#k zlB0eV=Atd8!Fe@xyFOuR)rm(^ zTH>TC{Pxa)wep$80X6m2bRMP^%d8Wt{n(!Mtohv!{Z*w72G`@b%GQHwCI@~7a0&US zRi~J~^t)#kYJ0NEDjfuTB`zOH7bG8Mr1Gq2{I%iT6}x#4bWZ7&vA;bIG- zS?bQ#1(~6l8+D?M$>!&oi_%3L@?nd7oqal5sLfq+$f2;Sq(y6K7&k#un&Fg|Uw?uYhWkL+%x4m~22`n5PY@c(X~>Q&>(jBgan0%#SYilG zIm|fIMmF`kT?r$TuwMg{DRl@q5WothfK(nvp zQlPWBTS*tJOu`b--0A>msk%m3l_Dv#DhL}Twc}HG>u|TG%bH+T)5s)j;cX1Dp5E?k z`hz$CTPLwqcD{?X$~-?#qw+0k563yc>LDBJai@%7RD*Ug`}oBwXNeG+zB>b%Y*d39 zy=OMnflNf}U%FwITmz<^DVp}U-A>qr!ly-mK6xtm_IJKb_jJJCHMlCPkHFtQzJu$I zqOcw|}sC2DYfo>*iSu|6X*mB4AdQ+~4 zi!3M;E$vV;TDrRWxX?7Z6pSBnC1yjeTJ_7Jtnre1Dvonm1>LTkEiu2lvubeN?zDGc zqU#*EPlL~mMl0*LGP`4<6yE9Wxoz&6T8rGGEgESh*7eR=mU^!kV@si%@}V0f@1MC) zC70+{;yFX_Ed5M(&(CEY>$K&I)_z$obGbPLg@V^myC7Gu3G|LbsIYpttsnc&&gv^Q=);N; z*NaH3k7KKiZ2)YZ61&mSN6W|RTxQM4lj*RPRj{=%EF8@I4N4R3t%DHj$q!*gM1K8> z7EZxb-CAr|;Bf^hG~0c1QDf578pbT_7a%|Max+BlLy+~MTa{~Nr)mLYd;%C@r5TBn zldhlS;@roeo+3TOjgA66%=|9Q^})fQyfVwVsHz;;Wcopwx>0=JVViX@-IU%w=jc9L zTY#sqUXATuXS)fRN0C&=1B1bL-<~Zyz)Bk$dX2HNZi87dH7szWEauK)-~tamXRx3; zHBfg2%ic}?82#IsQ$w|cY)D)VHS3R{s`65A+o`i{tl#JAaXi;x*N9i|K=FY@V@Y*J7->%M zqh#iyv_#M@i*>4Xri1gw8~W$!pP;~Uj>J-rE<3EWhpOMqksm8c8wxWG>s{&LdFck5 zJODMaD^NTrCt#&o7K8pnCZzsjc~0s-mO@>4m|qy4O@6W%@}@LdQHL`6V%Tga?Mw$o zChMzxIa_2sDqsAvL`S(9;~qwnp7|zjKaAaw4Doo9W)krLe|^VT(ZLO^4QDZC8Ae+v zKcG}BuCck-F;4`CHEeXl_LW{ZOux(SaKFv@N9rVg?q)1WvL#mN0cLw`(mW!wh>ec1 zr%dzFg8BQ-?^-mUU1Jz2BONsh#95KHcD4gBrZPmfU*;q;Q{{S1epIv- z*v^Z+?I2%gb?3W$nY2q=G=D5k0mC-QW)m|DlCZBZPPDzBRT>MHFIlz{j`{|cuXd_Q zmQN(27Hb8PtFKTymzXk517+_XS$W_D0@!U(5c@a z*f^#Ze(nLBE z3GR&WIWwy~bIX>j)HYxC`DD@JRPgAgqptST9;Ps{1|XZXi6_`*ceiRw$JB5p8o2QQ z%eK}bVrA=xI~W_T@;+!;CS6xO+yc zPo-szC??7ZwQX&Qvl`qrmm9sB6l>qHw8~vS+kcXIqz2AT-SfHI<)4zZ5!-lIY=Q*z z7e*!PuiF?7*tOJNwWB^j+C>eQ;$!1D++oa$T}=fd+qo*Du|64Hb>wit{)<(T*572y z6BN@R1@Yix8eZ#Lb9xZY5->z`3#U>ygiLyD#i{Bgv_;cPxM^@rFpqPX4WCPu5_z$mf@{$2{j&bbFz z4A}vr)rHf!V&%rK>saSXz`y6x(ojV5G(PI+P^^K{gGbgP$rjs>OSXsjEIPHB{wB!&(r4*G#ukrE z-^GTFb}RYS7~Iy0i!tDZ4)>uyhc!c`xqi|Zr+9}I>LicjHP6|Fp(l!mw23gQf@w4n zti?)GO4**ZeRPP+_G{UpOR(ZNT*6s!d#QT$CRL_rOtQVZIF4U!9S07T=b%sPnNJvI zFdyToZv2YJeUDM>a1EtAEt8AuKBi9f#hUOFR^%w_vD^%)y|c0c)nd6wpB1e(&dg8Mld~bU zb>v)!1<4#*nk>g2isM!bo+Q^O#h zbtX=GmM$oFDq5#Tv1jvbV4*D?jM>zd9a6wbdV`C);ul9cF>`r~4ER%ZC_no20$yq-1 ztVMELYGqSJQ5I#wJNIueLg<^om*xB?k8^f!VRiS zgz}z;5SsjZLoVGdIE`F7*0A!YvTG2*dm05r#FuM)hj?0%k z_0H+*lD2LKI3ILqYv4@8S{ykN;cqiEb8Bkbdy(ez;Lc#a+XNvl`RQ7lu<)$+AS4Sf z8&pC}*s#-;&ex?m6W(XxSj>-uZ9r*D;lmq_6K%K3>LH{N`^!GFAvM@5r6HCIuPUqD zIz1eMKO3!OX5aL#?2$e!WW@=D6zY-7w)#( z37&@|C#W2--;9IPiCB)Ln!@jt3`h5V2FN!_zSqO4dT6mRS7J*2%BhDQIyIR2@Ex7; zMw+g~g-2NW^#-GI3|?(_V$>3@E={Ki)2>wB{uKLkvP$8>=+OC;LWnPW=piwKBgAT~ zV4jYd&?%PCHCV6rl5DM}mezMKK%Y3=X&xPOC=2ia>HWja*6M ztDrip^Xrd&r@hV&+9J5RH`gMlI*wh8WXc$fTyuT#%vjrs zLh34DJqNiDn%1uVTTu@>&MJ48A)a9E$ z8`;Y8(G=Y?DywGje~36fi=p95CfOJ&6K$^Tc;tF%+_Umv#w%2~BQ97iFLk3iBsAaB zX}#e3C$0clLzB*7a*my!j~5TLtX{O9cx~Rm3r7dWRhh&|dFbzYv7dNXPv5-R`=g$K zA9iF`tB9k)0W)JRF&lg*0arw(2`xf$3#U^HS2{>hsn{!PPL)Dv9FtjLmiRT^YjD8a>0FOecAHU z4r#|QJjjv~DTu3#W5?qBR@g*=FY%f+nC|A`nYUO?M)`-gvbB;e`(g>aJ%|QO`53!< z8YH(BOe|)bY{+OUK3$K3GpbP!iQiwU7}KbF!KyJYaJu&qGWAyFj%cTZ~VO~Msb0xD1Oki8u=~CUkJok;Tg6QEd0YDyV2*-UaQz7X=BNRJ6ml#2)3{u2g^dc1^t}zf zlAEIR+1y4v>8ZI4iP2kllU$aBRy=LTbA?(BhBZHK7xJ_Z)1OU_jh`E>P7aRp`O$SD zY1tJlNXz?SwH0ZBwhe1(yZ2Rnk?Rzob?(5FgW~ND;Y;Q+TOpU*3f4>ZpCOpvfES)2s@+!eE%})P>IS3m3*ZhE=QWk~rP$hn*cB zH}A9{(;KO?;S^9o+u@BSsF|k zbK;Tq#Ob_SHX~uyBlYNZ!}bPSY|J-hy4K_{7vT+-4VVe6y^=j4&;VKF5bSY*=wNhg4b`wR-&*gPLAScM|gf`n&k!uszb)M1zD?M z#fDV@{uSy_bcS4IXnxaCF<5cT4ySKDIAWs@HGKJOvtDmV?hT%8{M?JFeOT7P!DHWC z7%$Ch#m;<|P|jc+X`Nf@LG${+0YGhHUVxHed@9W5a6>uWGhLnmeMzbP%H&wk8CuD(pw^2nQV&f#o8#~SpZKMr%%Ozo2zE7yeE z5_oGUtF_cQvSB2R#}@a(=5Jo_Jlk1Bji4oZT?_6|kb0hnOFa+yZ zfE9FY==jdXUQ@Zws%wpGSz~72kyf8Y*I9KI&PWSbWQ0{aI-&M()T-cpxgoiGHaCFB zv*8?8GHBA_G=-a-r5}ejy}@>(w!lc+$$JGU{e;=VEgIRn^+T0zi0#%AvFS=TeYX{4 z_NjxuT0Yi3wJOuD`5pUXBOqwA(UV2j2|r-qfwasyeZnkqYC+Qug)tWOw(eh9Xh^Un zt6w|Oyq~EFxO6M)VUJmDl{2|gRn%?Us`z3}6Q)d~gr`D4`03q%H2d~&_~X-;)q2=E z_%EFIE@X)_#)c$+j7kI2n++z>)S*BO+id3O{JGb0OG+sS$ot{rd>q&bRrCY?C-?gr)U~740aD*y=2|dp9=>hqKW@PN@vcSBU zTM%%ii6(-wmGn$HD<_zUZeG6XsM4rg0=uNdbt!mUmLK_Yv=2nf4$L|8yvA{Ki0`U3 z8k-Tdu~)W*2(N3MYO`jWkC{2#A8#FKhC3qnMK&retzEfdRqx6Y9@^W|V~K&^EsIyh zV8N;#Y7N?#&!*NgYI(;*<1{2FmzG#h(-|2#KVG(7MOxRHcER$W%RA#_Kg@279T0hY zl(1QNm&5FNvbqxnX4d}k)x4$*Hjvz^+}TF8cq`eJqf1tpuR_ifsRzokgb%X6|Hy?g z#w}KPa9}52vfhDL@Py$Z_H@WGX_wzmJ7pyn&4*crSoVST1GO}qt)~M#@6lTgf$TZQ z#=ARl!x-!J^D@w?rdxfnuWeNYlgf4Tn^zsZymjf}+7HjFZ)WWJXqZWbQtC1mckzBe zp-sy^>3Y_Z!5l1mQRwBJX^77v&VG<-ovj0tx{gVPc098L(RElTw1k0=VuRhRKh5s9 z9cX<7SXQGL$JTA=gf2n@W~q&pEHawLLu8ksnl4@-73M}3rVf<(Z0(fybZy-|=UiQn z7u3J%rShvFnd>y_LyL_1%j=l(?wyeeSqjX?f@T~V8hD~}Xzfg}f*9X8Gp%(w-kU?g z-7Tz4ZCsoBg5Xoa0udWsVNofnilHSVOW^7qH+EI}oTV!U2bO9lSxf_$rS2dK?rChkWJl_P6obn$uwRRnwL?GaE$0+Q$zjQ~Z6SqT>3Ju2O&_ zDbBXAtxG>)&=ptJ5Ra9DBk-B0r)@y*qAqWh#CdUT=ZUFB=Y7L%T=@Uso1UNcf8)bu zowdNvL0AsQJ-}WSwxn>hI1e`a{gqSyFL!w7erWiDuJQ6CO#hKMuf-L)-k2FC7W)N` z4mifKX25&XdDkvLbdbFPvzED9MrlMbuAqSUfn&vIgf2G6pAdKU5 z$7U46Gj4-L#u)w!Mx?{ohYN%XZA=e zP@QIu=!&Z<6;^B3*%}jSeV8$!rnDRr3XQ83#&pG-Gn0)*G~wFEV3>sT3}&8Dvvqd# zcC;?i6(E(Yi02e4F-9S$YpaH$0=Vgd9Z?N67>@C$O`pcYtEX4) zwO3_za8Sp%2mMz&q^(*yyf!FpGa`3lyj_0>9%t&Fsh=`Dl`OJh`r7py$aCqoBLIX;|u&MB@{gN^Cj|%4BRPupolD?O+nN5Gel|2O;^5a=Wtn-3s)nNL zTbnyxOR`)iKCj(3KbO*Pz{?7LWg0P?nz9L6^!8w)Y@3O=!KQVNy66Q2jt%Ezetv4I zook#RC1FDg_I~@(F}zH)6gu$Q8!@wHh9IiRc3CPHCyD=?#tHg zcnblHCY*Y1+(RsJkrw<`Qi9TcmNppaGI(`2Y>?(U?elvMK$ixV8R)kWY1Fji_}Z&hS}&a$ zFdg93q&@gthg$u2>mcVx0oJCWYpJ;ksC3-m+ci6>3K#cqe&TBVGIprd%Pt&8PT5{%v%)V(M?VIAF6h+&I&KE=O7~<o3?jEwTt>flHdd(>2 z*z5$FZPLFxz`%i$(a3$)s-D+7^3g;bH)%l=gz+$+^ZDl|XwhtC8k5 zeq}1{m*ZiwCIY7Fe7H;zWbG|x<>tYhAMW|!O3N#{t;dP4LH_gj*3Nay)Hy&8&URF6hZzUDAbhP=qifv)ESm~L z0!6L{u#9ImQfDD^F>PDzFz837!YDNz@?*VjF!_cFt)T9+6%uj`9=`v24pFHMyd9a( zKWs&`7XSMDlV)~BvTQZhwvoMVSA5u!Mdh99Ma-{BTk1j8w%d_~zD*w#W)LXn5duOT)9L@YZ@cbxhY|-izqO!xoVW^e`r-zpzuP?UYEg-!agHkF1&?Tp8NJLv|8b$(?a;@#s6vC zh<9U^Qw-hPlC*A(^;mQl<&%@65&K43)0#3z9sDE~6^K6{YOt=tUF1h11H+JA> zt9Pb=yFwSDEbLsj@k^Y)yAd$BpOUC=vLQdAu0y> z$Ct?U7MPl$!ywB`%r@St*13#<``;d(JA%8SoU-9g{IP%vIZ|Jwm3) zUx1e~RX%pcNNfGxh4lR8>-_p)ywD9Vhi<@NwL&^1$)*9aBdk*3*G3i%tac?SNA>K- zirA_s6zZHWoxa}wLPK3$p}(3VL?i~2S#_e;j3UV~C1DHeG0gQDFrB&#RvpM1!S3qf zt#rep-*NyKTkFzoT?=4xfm=3MTZb%5-;EMH(TMFSG&JQVjSl(biAveIYwLh5yhtTf{r$83t3)(B70#~Og81i!l-_;~$ zsfL`A`J&Dn*0pP(#au9ElMtJv!E}0HkdoINm`M?>a#64XlOk73(8ohqYe0@VuRb$r z=rX2fJKdB5RrcS4{kLfUm7Y$nK}@rrc`KaPhTR@fCC!FMiy(9R8B(vbhPh$dB!&ih zl~_`0y%1#B)poucP0=>F8Foj#xv>kAEsnPWzz7?`Ve2Q3pYYAboEXR3iJ8jB&-B1T z1^$;X6@fC_khke%Lc6TM%6VEUx^a(<_i#Ph59Ab;>|{mVD|j+S5$@!+@~m!=V{+AZ z&;hU^RIjyU@b_t-P(zIM9%L^DwTN}SVGh~Ti4PRlJ5p}rSZ-W7S~{fv$bqG6xT9?Oa6<-B z1{yYUDK?@#c7{nzA=?ceYZhA3uk1s5_}q)fvqW1@&JT;y zdJb^~$yTKHHk*YYI$wBkKalXXIjUVWf{fuOs0ro?b6GW0IAY{WL%?wqjp;FVZ#zBO zI)~Yk-wH~a|A(nu?nV8-GnFd~Ff0nBtF3-mf5BRedn4p+$YxX`G)Z%`t0dTmrBzng zG_#w6l=L~Pr!;~wEA3u2e}-)7^wQI2LNg7A3AtXnvN&p7&L!L2u+1vluj(|cHfxPI zt&WFhi@~JzUCPXgmKjCr1wI=)VPm~=;gjH@@%5e65%(V+wr-FOe5p|L7Mr++{UyD9 zUEST#te|(rQarY)$tqDSu9Y)>8^57w^KOM@tNP7c8NbJU}qJARC#d2U+siOb2~s z%wEmii&vJ0U2B}{ozKo6U?*aN1&N3T)8*mnB1}lfWMWQSq=q*(oKcxbcgv$y5c-*| zo!u?Sj&2-};VcaKse=eh5dEvLd}*31$iG|>oF)Zo(e!s(mu4ZXQK4sd>+$Px%R2L% z*t%wPw6uIR#=96E!6zB3PV32HG{X%}<7zdGv*fUGI9CHW-!86)%Q-`|f3|nHMh~nT zuqe(7B^q|VP-;}kuj)!-YC!FGCUD2QMO0|y^8+&0r>0P_tuWr*t7dqJJ$R(~GMh&> zpMlQ9h6?nFoaz^>5rs#m>V|446tdK9Ywe*P6g#!5WLy2=EmOI3F-=oBdE@V)Q|8`Osn9vSTX|V^sX|DcOORz z;~?Y`t18r7^LN_Trk1qn!aEdT{|;u?#WHAF#5&*j80>bYiw@P1WfqF#EyWq(y8GdF z4gB~;r%M>SBp@ANI`e#N|B_QISKFkdY>T|zKL&#^Ey6cDbl}KRKd)&H_?Y8N`C`RQ zm6bf$qWQHRl^gYOVpX}8whXp?sO7_|q`iAlr(Z+C`91V%m&T)9x#>qnkm_X+TVSkN ziRBjl9@Odj-?IH!F>E!nZP@G@Q#VZqztwi@dK03Kl=~4!x`m7a=N(&vUsWPw0bl^Fw@Amzm7OOU6K5J81l5JXey$dB2 zYgxk_a-mA3lWIO;RKG85rPm|x$qZxm<`$=2V-*6ILta;;wis#|Xq|djE|Do+XO|7; z_@2}>_IbCn)y_|utH{yrjA zSCv+;hQn!0Av^sh3ZM!Hi=q`rntYU*p`#C*bP@M2wqljBHUnZ)9*f7>os6mDbQxjkWm6x#OxkPY zNQl>@d&!(}i>v9_wegnwb{M{i<`XmPY*cIAGph^O>(gg7mYX`L(NQpiOyYc87iyi0 zYtT)U!Jm3Ex|a2T{1)@=6M<#q=)sfW28Q;YP^oo5xUebn2 zEG$g&hCFXRHtS>CYyBA3|JgLC-Biow$BDLk+N(0J*kHtWZ`eg!<(3bbeU3K-vj?ya zL0Z$L10im=1gE2>LHFvpIUQXsrUA5N=a~g8w{kBO&7-+}8eBJaG?3PD7;|FBEv~6i z#&8djItk?dHqM`^sk>-n?}xeUuXJ|1E(7L+QBu==rrlFH(+ega zI=J*7~rfeYTBr z;|v`|+q-zJ#($%8qj4}@Tw6iY+hUIvX)%$Qd)Sqbl%|;y#MO{ zHLEbbUAcO+kQaR$XM;2Dk;6oQ4W%WGty$oX@O*QpF)^PNwl!yJOJr#;32(%wmjz5! zIysUzyD;CzypheNtXw%{tIW|zVHqsGoz>anRN1&P6%hqzQknH9f?h}=>nGvpWdlo= z4z5_+KMGeoVYMz5JO*p@Kx}UeC;7$Hpyu?ZHLlR(qtC<~%o1R2p3} zu$0PmjLJ+kDpR0f30!LXr=2Tvb6kA7MjIS)n+vUNRZ28Oib-pmonv1=P2)1TtZQuX zxjv@zpaJy(GL*NkkJ>72CTl7_o8)Hqn7hTpxhW?hV9%9yYt-*vAF`cLnX%+>9O|;M zIV&`*ZS6P!b=Jz!(#R60m#`AY`7%y9VE18Pzl6qn@iF$LOm(ELrT@)wmpu(y5M%}U za1XLNUWRs{)Hq<-V%m2JtecT4T_Ypt!eXa5)?pl8SfS}?=N=;bc5p3j3saEJ;j3X< z-BsDSNpY5gp2g!<08sy>?VaiV?BZB!4{eQ`igr^%S*2uN-@;6suhP6zxapjr$I!t> zpILiM{~c*pJnj9fKaR?}ASVSbgDJ}ba0ZutRC#G}RhGLTdd6-DWnJ35%P!{G_<6@3 zVc#?8qj|l{qUCuT(DfW*r>9-rtg!g3l&SE?mL{sE`4OqyLbnZl7uQ44fW>!LtiP5i zNcrWM^yZh>uQEZN(jCLR8y{j1ONAh-`E1yb`Cp)Op==1Gdd-IJu3F1kC*@}znSaoo zO_L(q5obL~ksaVZ0Wv#_hBrd-8N3@G8Y>oh(=iK&?X0@kkh-U026r`iI;p1SzZ$s% zzQef*wDl~}-^8Z2+$?QZHb79db2Q{Sw_I1AU#X}0E>=ou*J|3#>Z*EgUd&dGy^S=7 z(h~qmxmyT;o!hX>0Pe%BP*ByOdF{l08(NX&oasqH3*A093uj7Ubc8>hzxV~YX-X>ijTOG80fufJS0(h@<220`OZ!X>}O@oNSQLp#s zRsen*jdW1J?RK3u%q;<@mfdAdb92HR9)9N9>@)lBiw%A(r&5QJ&!|~QXnH!Q508OS zv86^d;PP>n27X-X994up%O3PBaR`+v$SFiBktJbik zAI4ST;~ZemW0lLCQo1{q8P7oj#eT-nl2zFI)n#gYrvKE>Nv8pjx;`aS=R?X*g&?0I zh>BVGRM#%ENy}{b_Qg;NI*jx=_iDVsXt2CYN1lJnZa5fI)*oZp5$mJSS++~(| z@Pf!BZ$wwZ+}hfvw{$I%IlRQt(mA%9E8ZEEV?vmjXB6lPQ{FJ0PfUnoJ!sAtCx|Cz z7hM3CA+ST5F*XD`2u`hGSzB#Y)%404mB(kTNmg?4yh~RM9d3p$m=9sUs&6q`B#uK& zi(vzjOp&2R#<@VFa~%$=FeSz#e7;h7*C;l3gk>xg%+8MH|Id~zuEAR)PhzFtf3F9c!-YHn$(5br-pLYx;xL0a6GKHs)fbz#{g%@GLfNlD;7wvU2S0O_McV2t?Ph zLG^=-8&yDN3t_fcd7p3isJ=hqyCY%anc6(1PhcCR;4F+{s@t$d}Kb9~`ys5m~(YJc8^)bJHH^wO98Zx@3g&7yWfLZisAy z0_Q!OS%wqBNIN#^^V?ygFuNNP-JsE0T-IAQm6E;>Q#3fCpUs2Q)OK)B_agHq`W3xc z_Xkti(l8W-<_^cFns42C_w)sFKEm06Li>ee%`L0P^aDOJe1)R(?Yw1HQrWy@2-7@E zmn<(?lK9~*cI8!a$owUB%WIQDtR&~*QY{!nRr#4}Uy%mtz_G_zRm$O#b{-QF>=c2dw0OZE0<62k1vbsCl+v*&a}VGPX!LmO;Dp4!fYhUKMEI^4(fja1(*@cZ8FopEeo~s5Gh0mr4=zrhjxvD>_^EIxk30uU>Qr^e z0aN5=l^Z_mQz5;%gRy(IR_0p#DGvFH)2?oiVIMfZ;H;jC7e627CKgf&Y7H~%rc#gF z9)q#!A&RoJ9Q)CoCdqwsb%ED&kX^v-6UFk4d4uk`y(rC`y3G>I^}=Onhle%~Y(?7G z!8J6xr$;7c_in`$y|x8?v-?qv(8geJ&8nlR=sv`^T*1UpmUXB(!-`h3EAUx${R?01 zFqexm6@!&5Ovbm)-S@xP1V%^MMQqju>NGAbwyFlXg6bsIf_ZgruJ>jR@R`qY-g>f0 zns=>AQCl*X)n|%fH76X_{D+|!o-pvGDJ@SB!sZRvw@yVh^Ckpm>e1HTYZ;Z+2`E6E ze?=m2sf$%Y?hBZoLJOzDL5}!*J*5n86*o_nci+`o!G=5e3crx5*+X?ewyl_bXOt*^T>>h3`^54{XSslQIKuiJbzZ&+v zI|mM1G5R0+=h-oK_pyl|)_Yi?$^&R0LO*gr6kGeW&*cX6HoEi%F8{@R*_i3+Y!PQL zT6VivGTYhgBgWxj>0r$fe)riL$B)L#pk1UBWg+87;{WjT@>@9Eb?Tf)1UIIm){ zHm2UH{PAlr<_WwXQUv9@;Jbdo3Rt{cxB}LFecpsa-stnD^Yy0ThEv&kYW47^DSJGt zODoj^KH;V(2~6B~tDJ`7TiLf_#nM%kBP&KLn@5*bwqwp`7#*}qIO1e~eZ?p`95d1D zZmL_@B$r^ znjUL9DkbD~Ay7?qcs)F<1#)od1yhGEvjhas0u<4Wynm#?T>D2P3 z)0k+@ldF3006XwI)CA|;x&hDGscGFNO($>Mbjn6epWd+P)D4wAkl!t?!Cx3$ zh%)}4^61?1OUwL&hxvPp|017ukGM0#v~I$E)Aw2IUZ)aa{_g?&Nb|#lgI$I|SolsO zkY@+qJ$$D(?K`|%xtlY&d%|P>m6Gt>mj8He%jAX$^V4&~XL=srsVn#fm3T(~cPOqq zUYV-&2Y|<|=a}#waajoKsEJnJAP;ZYbn*sGr%Y`6ba~UMEHiT^SCvnlfM?#8RaCC* zZD!v;*S6&1--qMb_JnOjCBppQ4E#vTUl*%T*CJK=13=d4%|W`fPHyO*j0_*>xpKUw{P7IpF#XhL)Oem;&%%T6g@7hYiBU-f8ozk4Bv@6YFN&9{fSc&1N# z6kmxj|93g^x;?Kt4inJmPu{F~(=e|tMg5TG4V=g{@P9|*M^vBo`uCmY4+2lMG7!Xl%dO*Y*61mvoqOn^Nl(;nJ{U?iiz(l+p27v@@>nuE8D*8 z{bf6pO_?|qSIqx~0TYuyy%WZkCtHSMQl7jolDCTFt&{iULblFH<;gZt{5Dbiwo!bT zq6zN5T@=4vbpG~HJX_c7uRM8w6#xD#62Hok3-Zq&<{HLNiQ=b3=T}DYl~MfED1K^E zfg`4-M>+ZR^rN`rH$#4Nf7y|g%aN<{&l~14#_t@(@2u-Mlqb`o_%QeJ{9U4W_I$Fx za`bTX_n%?!(~%xBBmKo6<;kq*_*r)R()1`7&+_5^*lWrD%F!#$->=Hf&yI5O4e2Ri z3&Hyrqw|Y)KEHwcEBYVCa@5lK`-QbHuU8wz*V^^grB|sV5y*^xJ&^s8WO>pT-LKE?m*vX7@NgWzFgku=6u&r%UmV3B z5XB#0_sdF=i_dbUi@!9zii^KCkkg;|QJ#D(y8g%P`dKUF;HDond=H65pe(t`u9uY;cfHHg^06Yi{}IvskFfi%OpiJu{ly>U$*So1 zRZ;xvD4spt?5{jo6UDE|BJry{IWmgRT529xo*Wg$9~GUyHi}mu+swn=dDE{gw{^}_HnkfF7DE`_g{@N)1b5Z=~qWJ5g z`0Jwh>!bMVqxc)5_#2}5&qwi}kK(@&#eX4+zcGrxF^az_lD`<^3U!0sEcraZv2{!8r}GIKOe2}V^+Vq@nfbHaO1UY)8mWjFa9V`Zja<|MDksc zoYl09C{ON*;_r>*??&={k^Dd;KNQK2MDnAN{8%LaFp{5$Hfr;+?rBtMtznhPmQ zvb1Kz1hi=3UwLw8C?*q=Kjh>Mk`JeC0V6g{7UkrPlGAeX#>rhdd6VSNIeAj@;k2*B z>us8REGKW4T#%DDPaew2llc*YzxO2dIeCkul#}0^T#}P3f^&JPUqtfrk(_&Y9G`m_ z$hnI{ni!p*b_^`M9O)PSl_wj8BF^79k~fLuNs+v1BySeUn@2LzFZe5uTI=#8>k09& z^5nh2(UdEa$MMQc6{bW*vUT!&PTnT@vt-_>0@~aOND>~u(&X)u_ewt4rcEGHZs4WVhtck_S!RJ$Xm+_9pL6z#_hCIy zk?fW1Dw#cniliyoLo#ckiljN|kUY!emSmA+cm1|x2V^;3?_i6coy?WY`M?V3V@f){ z!{YZzj*`rtQ3doXr%UEMUj_6j*GjIk`1#50Ik_u&STg7CDxeQJSoh<6Tm|0hD9KHB zeqZvej(@=9g~@LvkC?nTnTR6C=jXgxMRGv0bx;KPJ*P$TZjsy($p=O9%1Aybk}rtl z8zA#}I2Ts|eZtozbAGJ?`hj~Tb55-S`hcHG=KNU&zQP|QyYD-Yye*mYV-?9zvI(jb zUY~Pc6&Rma1XT>*cgINHHInNixiyj(M)F~id`u*NCX%m=E0;<>z~t4*=Ot59 zR{{OW*Cp>`@{!4-lDkblDtSTjPA0ESUX{#etAM^^!e;LM7MgrqvX$idCZCW@lg#$y&*r)2v8NO-_}}`OAvr^yC7`N8(x) z81G*tnRAmB$yv#*kokwx(L4A;a(7O?F?lp6pOgG7C*P3#HYcB#{3$12mb{&lFHJU8 z7slQ1l4RSQd~x#OoP1GI%*mfk_Rh%{CLKBXf@J@ke0g$cPCh?blasGVPRhyGCuis6 z>ypcJ^5>EpbMm#x?K%0Hg0zx`Ksg>Ir+-u_c{688KOYpNSdjdg{g zfyRNsVpU^pb*bJC!|tTB4xLr3omHrAC{~XY8iwl!igmU1b+seK+Ct;-V5zD&T&k@f zu%r8zmyTMxWDu@XM!6CaXV%QZ))0e@^^F5HHT8wYs@j^N;riODVceoPFkC%?jhp#2 zBPF;c8ZE8D8P(Nz+=jurnqe$oz+v@u)r~_VgVj|dh2g=%NPTIj!QE@vIVA00jYW1m zu~0j!SW{oB9U6v_WNB!ix~8T$G&oXQQ&m%_Y8a|%tgdw@!Vq@Vnw31GYSz$DsaQW! z8g8g*s2Qqi7^tousVx?(s%wU-tA>k%I%C!9VVtBhiZx8Qk?O&rLVZbef>y7)nHArI9yw-Z>TK|+X=KT z?S`|Dm50JF8E#Z;m{nUhQd3UOR1FpfN{uy*4ful9^@AfW;b0P5>L0=# zk#NOX!wn5pb;Y4!e8`%{+8TKGDGn5CY6t48hYLfsb%S;*ox*jbqr6isPAk;a)-)7L zBh^)Pg{ngJKyhTKp}JHYZm1op9&QXzgZsWE%Z7Pg<18FmsvR5}scje@94HPK>xb%K zo?26=uPIhFl&V|~3ZAe~*D$N9gly1QS6ADJgNs$A(ntYGGgw`07^!L)EV+CXr$&9_ ztZJmVX0_ zD=8I+szz|Hp_;+rk-Fh}mm)5c*VW-X z=c9YtDcEM6iv;b``BR(+wdfpJb<^DikIcChg3P63{n&Dnar~X`ki`JECuC`EX<&3U zN{2l@7wYuFX$+$IldBL-7~}s72ZUkxtj-TL!dI_ATj3IBU@5OObZBYlaAc%bI*NnL zC&5}9{=~v|o+k;52S-astSPNp?b9X;Nnag7&C6FERT_2fua}hQ{(8I>j~%6vco8J- z2#fq>11nczVWhcsav}a_`1zTvTrzXW=!!LN9V1Q+U2fx4=PD#!iK~!ewl-HG)nh`i z!;@dXt7C$FX%rHy@l{Cun6nykA$UT+g9206`>(=JR(seqrqlVI^6$$~EPRSW`F*m4 z=Y?>bPAQ z@hJ1a6`qO}b-CL?j<3W;ckwY}Zs%6!MOPksJ9q)hT?%r1J30!Bj~R12^CmXts4;Jc z1(vykwBRy)Oa$d`$AI{m7?w{=3-O29`Zg}}wVRoQ6;XktwQt(Toi25VCLnvtZSaL22|(OInwr-cGz^^`#eFRf(s_y$D|c9=yg2h64(uXrXRs zVChhjJBbh8iS{EG*teF=O)jX%f>h5S)~>{~gyXvX<_;_$UWzy3*S8%rqEmZUmsaL4 z*SFTf;*Gg*{cs}!bSrGv4Ft1?F?blfD$ZLzvLfjmIAqC?JlnZvD)bjtAr3Vc9tzLb zicMgW1ICghF*F6hi^qI_uKz z`=;XD(ZSVT=*tP=1KHxy^f1K0Q=q$^d3y?l^nn*2Uj$vlqXXOak~eun3B#&JqF(ofI5 zhd7(WeTT{Y%90b24m|&K65;od3(Arfz8`p;_^96ZZOL0h&%^kSk+{w%*;|%O()He_ z>-CYCjQc6?2kyr6!Oft@A&Vr==Xalk_uYlWa~Da3+xzyEL8A_NZW%P;U}srEJ^3WO zXC-++8D@C!z6X}MeDrb2Al0ms_E-LaTtgY$N$2_a#geCzxQ{&t?qlDrwa%;5c}0@nhv~Pp zEP08<{cDhp6W($*j1vZszbS)nivJcl)yMFO;>IG=pWz$wzDS>)^c?nl%gSsW;-nFL zPln^ZOkdK{2jsj9W&1v$r4!hraO(9Kf0#%;9p#fmD+iD-m3)KvRq?yv6vR)Xj7((r zTTzy@QC?V<984m=ZBOF)tvno7mVBWM@@QFdJGrVXxtCmBmOMhPK{+OmEK96@I11@W z8HR_P|DANS-sAAHCE{oaxe1uGF$sF36mNZ^LWti2ikWBA5!>JqFo>1Z%StU z!t-_zXNXNA=b0IQ42kGlcKyOfbHx=GXrwBelaNt7q@B;*tFQ?9<7fQLSm^2ue%QWA~DO7hcX$!hY{ zvScj@V}awy(@{T?XOt!D$TRW%$%QBB^U9K|DW8w@ zAum9FAulXTzC?buEV-4u2<-rQG4c_4Nm+6?iNw8^ysRv_kGvfDi@c&Nd6c}eEcqdM zm200STwRttMfsYt2F+#?*n-XzYD`}QTd%)X6trY4_bYPOycXi z4f(xsoRx1JSI6^k+&(0Zv--XRtG;<0;x{7^KZQj2FrJt7%H<@kvjv|I^&)LoC!Cig zSBuw)Ul6|}-YVWEenVWS`&&Ks71d+6mL-)4pYRX24sD9B7w%NOht7A9Ul2|k~EO7VBIwNYLYaOuVD=r z`6sO7Bma^l9pnp`S0R6tBz@$MljH%G*CqJA+P-!=b`-pwwQWELSIiyJ+Q@cK>e&S-~w-d^efAYG=pnc%+ z-*M%c@*|YNt&u+Du*iHs+4?tN2h$6j%=;kUah{F&u8Ksyv->05+8=}$70&i_0#>WB zJWSZ2%q&yLtt4+pA~S!GoLH88m@IewJ04fiaeIqwR~g_QX5n0>#NfA|{$^Q~rkMsCSahAA; zX!S4RPm*l)D ATYU-nF3DC8Lbmz|oXq?V?jY_WS~*Af!;*g~z9zmSz6al%=kF+f zRNPza77r7T5lE5t90-x41aUlrdHCnE#$ z`ZL8n#ZK|#;xh4g@htHR;y1*H#HYmxu-oAEw-jfJdy1Xn$Hish@!}QYm&I?1kBR>j zH$?}V_t`<5Defg6A)X{&Al@o|M|?tjL3~5p5cUbY{#23n6_gi2H;#K0U;&;R+#23Uj z#0}o#uD7-L5wSs>CmtXkE*>X-M!ZtIMZ8!1k@#!zFXBX0@O+Q0#GS_CM~a^o zFBWeU?-IW+{#<-jd|Rx9DI@P&5L?7P@g(u{;|#TUgtiJMd?{lr<~?qaWau=qLg zyW-R0Z^gI8O}BK{{g7BC&J`Dk%fw^E^TeyfJH-3MpNlVxe-q20SYf(!h%3bl#5=_w ziO-22MZ?SU_7Ing$BO5RSBu{e?-ySb-xjyTK$zE?Di*{!;zIEl@ig&b@$=%w&^hrs z+lV`e)5N{RF7aS-skl~LC!Ql-E`CA0O?+7VsrZ8Uy7-p(espyBTptl@#Ab26c%XQw zxJEolJX^e6yit5ud{+FG_&f1c@eL76>+N|e#BIeX;!ff&VwG4Y?jg2_bH({$pLl?H zus9+v6HgM)7B3fX6mJ*5Cq65_B>q*LfDR+m_dVi{;;v%7c!qenc%%4r@%!Ra;%~%1 zi|>e=!Ic2-x1G4NSS>b-gW_kzOT<^jx5Uk%5aIQvh`Wlri~EWPiieBGif4$IiC+@$ z6dw?OEIu#(QT&&<@dw;S)Szqm|1Ry<9-NW5PBn)n^@aq$=8E8?U|cmHj~ z4~x}ev$#MU6ps);A$~@@OuSLNL%d)7vG^YisS@k3%k+*|Av4-}V(M~Nqk=Zn{fw}{^ozb`&5 z{!aX>SpFgRJnt2E6laRNi}S=qVo6*jeo{PJyh8k+Cc)ob8_!aS9@p17v@m2BP;-(*V&#}EYU2G8NhzrG%xLW*_c%FET zc&qqr@iFli;vd9+iIaAA&#|32O{^DZiwneIag}(Ic&>Q0c#C+C_yh6h;w$1m#Z5lq zo?~0_BVwJ{F7}B-;;8sZ@f`6g@n-Q`;-liT;_t+Tj;zrZmb8IbsSga9S#U61$Tq%A+JWISn{F3-h@e%Q9@g?!^ z;)c7p=h#ZzNvsxI#QnsB#TDWS;%CIm#V?9?i4TiUiN6#7CT_5+dye;s9}6 zi_691#WTgr#GAxB#fQY7iN6*9Do&i?o?}aKs#p-4#4hn5ahZ6Wc!qeXc%%3Y@j>yY z;%~$^#PXT$IV!{tidEv?;(YPr;!^Qg@pSPL@eAS|;sfGO#23ZCh!bYH=XkGJDSlMk zOY9UsCLS&xBc3K+EPh_RUA$j>QhY)Dvsm^~_Z(Y@JBqW!J;e_3K=Cl~Xz^6>BJl?C z>*9UlkHue$e-f#1wf?d=MVu+_A?_<4ATANHnS-7GY4Nk-_2O;f_rxc}Ux}}a?}(EN z?s^{(XNbFt`-uCChl)pur-&Dd*NI;fzbpPod|rG_d|TYS=$>N-aaVCSah|wXJVZQF zJXyRz{G9kz@jK!V#b1hl6yFjzt9H-vesLGEQJgC-5=X=};yUqs@mldK;=SVI;&bAw z;=jdBYus~eFHRR5#5v+Zu_Ue*KP8?gUL)Qrep~#x_=@;Xag$ni|82#Oh;?GS*eAj| z+w$e8_(|~`@hb6V@mu1f;B0n_@=l~y?c(W#Se=$VyoCA4u~toPl#uUSBPH{zbQTfPl#uV zmx#BEPl$gM|0!%ngq8!VH2 zEcp}6=Sx0|e6lP#U-C8NkIRx9B;Q6pQI^~(`9bnWn0J@_4Ee*d3PB_D?!iDWvu zp72;%vH^+r*^>ML<`E_DOg>tc>?*mD{66eVBzKUHlqLH~?k69{e5K@3@}aWiD9I<2 z55i7J^2Ou>WyuwizewH>djrXLTYQrIj7-XsXT|3g{|Cvhi+@#k*`DtB4a7+#-fw$x z7qL$9yNP=%d|%03VxPhfmOLyjQTQ6kM~f$s4`BY8#60RH3co`9yuxple4F@966gI& zEZfV;yO4PPI`Y0G*^fkeED#S+{D|bk#1#rZR`Msrbqc>gyiUAT@wbV0D*S%Q4~vf} z{29s5i7zPpHOYSw|4rh#C+v-XNRKT^JpVT02Nk}H>=)__>YrUB*~EqKSunN!cP+~6|WX=Ch`8a zlb0sRk4RkqC*q6ZOX8~}j(>~9@gHn+tQ9**#A6>Nv-ep+;(DvZlf+ZRGe{hNk>tz7 zs}=qw$+wDMSNL}%-!DF*@SjS4M*OA1Uy=Np_=duhcK3V}#Z5>&&sLJR6Q?NrqhgbY zMK1P!-Qog;4@fSFhbjC>$;XJFQ1}^=&lWFG_|=lH6Tc?jAwD2JB0f&y`Ja{iOYud8 zzb^R=@gEAGG~1oGHHq)Fy||;oca{86u}0xdlH0_23SS_3fAJs^_2D6kKb|}!6!CQNY!b&`CiyDyI)&dV`8M%Rh2Jmv zVev7AKO^}$@dbsyCiySon+l&e&pqG9;^ritXFJIs5T`1RpT_eowXeq7;8 zBrg+3NqmoE6@M;?^twplUm%fgUlMOu__rm0Pke;Ld4Ce$vyYQMB({nBizO28w~YJ@ z`Y$BzbEbH%;;)c=jd-hgn|LRQ>)bE-Vev7AKPUcP;eQnWqVRVlm+$NDzcGpD*^b0@ zKS-VddqWb>*Ce(pe1Gw962~7!ekw`MBXRs^#p}fz#hXbSe~&Mbu&#XS_?BKC^=i_1yecT_x1;U|%}-uVi@NW5CS zPQ01Kad$}mrg)$DkoY6M^BEBeY*Xxekmqb46B~M6_BP1VBB0WDTo-1A`-XPv2-a_I! z-<14q@jiwBQ1X-FZ^W0yKax2ApOW7eC-%AU&B$Z1XOHAM63@4rxQ{qr>=%c`)#6(5 zcoO$JP4Z{N^A&!Dc!T&=^0XxR0g3zmNc^??vnQw+Z5g>4vVYBbtK;VO7R}?LGg#;)8eniSHw5Ox5SM;?wKqf z6n}~2E5vIRezWASigzgddy*d%e=0sBzAU~f{+Yycye)ac!R|RWA`!l&&vokBcN5QzLRS=^Gu^M8m$e2cihxJ*2O#BryPc=l^ZT<3c6CdJ<_`7ZI>3je<3$HgZV z{=DQD#g`TSSIPen-&XjfVRzrj;+76@qQB5c}(&X z;x9;C=LN;Tq3}1wvJrRP4a7+#uCt}&ZNw=guG1zSB#w&biQf>P75^npJ;a^gEOwGe z&jlpLDl196-)iw_#h)zsH1RBjUn==Z@pB5lMe^6gZz%je$q$J?Q25i5eb8aMVM&dno5T_}8hFDPeUgACqpD!*V@%|qtk?zYCJ}Mrk@RKE*3i615Lob@Ee)(a#Lka(Yxc$mVElzfc%35A~_`E2n5gIt%}Mf068CvQ zd`aB|UxmWTE$w!ejNphj&Ye?MZdhzSxo#H(tp8pZakBLtz{O4pbN&YE$!)5Mz zlf?IsIRC?9v-okbMDB|9p(LJTop_q!FO+N<2>Sr%FCkJXhgYNWMnALE*QH4~kETFNtrE zxX+v7TMFNNrF)+3NW_0YoT~6yl8a)!!sm#K#5Ll{;<+TQccFNx!fzt+-giiTQ2e>V ze@)^${Ds8%e;3P+aN(0kgijW?B5}Q)#5VCDah3RK@iOt7;^X2A;#=bOqqr`<(^PV& zB-xY1eVfJEitmxUP&`oKhe$qLT&eIA#dE}~#V?V#{;lHI6@I_?6Y*Dy|Bd*263_Q{ z#c#9(`6T3g1Wad~pGZ^VWzLinoXliBFQa&uija;s&b`UYR77 zB<=@Cug2*lj<1#6DDI{3`Qkw&&ObrCSp0_gl=!O1u{V#OD()eEOgx&zeLqP~fu8^p z&vmtUz2d(j`Rn3c3V%TIBjV! z6~4RVy~Q?#cT4UQ_a|}vA;lj~Zj&UZDE@TuY{g$D`6}@`h2JXqHt|k{-!J)L@d*;w ze~LtYdRgJGihox)w%)SzohZJC#CcnhIB#c#?;_SHd{4>EVh6bm_6Hzw-jKo%5sy&# zF_KRZPb0TUlCw#iceTQ=6K_`d9g@E(K0t1hB#)9f?-vUHmH3Ln-;n&KSiaVsw+V^! zwkMIlrijxNUXWZXHj&%F54hqNDf~dOr10gEN5$hwocAfkU!d@d#cLJ*Maj2_cab>n zUd8`N;Xe_7sqmL1|3UmaiSyo4{N$q{T) zZE?ym?)<&PgTxcWYed zUlZRFH$A~!Z#!{Uu|aGXd&GY6|FCy2U^bQi|NqyXH8W-yX2fj6kdbrblw+xeA>^1t zh%gw3oW~(WMIk~Y3aOMtQAsLFQWQm{v(6-?PbWp^ga7Nj*7MdjrLW)r`~6+l_xfM| zeHoAazSq6p>t5%**V=2X;dm9!#9MI%uEQ<36Wyn|-4?)znGy8Vs`*M@O2o`zA( zGK+iO*~E=78(Uy|ycjPv)n7kT>-iYU$Ky449nQvixX@Jp58_UfiDzlwW10d){2iZ^or~C$7RZxB)lfv!?Rw zzz-Hym!(_PlFN&5!GG4&@6>wPOY4t8gvdcjG>^bKaIO9joEF*wJjF z^NTnNrCm3?i}4c52b(QDZz|=}@g~X_;!4Wz$A>82X14LXw<&)Qzoh&-Oq{NInofl= z)l`4w@dC5EK6lam66}iua4cSdQ*av2#hY=dsl3ZgO@{|5e*~YzEw}@B;hVS@KQxu+ zh}l#3HJl-Bys!+Oj#aS+*2l)!3|nFcQ+d0Z8cr_dc{mdDaS~pOGjR^yY%0$xbA;zT zN%uM`(k9|x{m;N}I^6|I`cbjWn6DLfz|PncFT;U21cUpP zX+A6@z8&wv9k>f$$G6d*<7e|R&JRt-qSyeNU^WK#0aSmJiKpNVI2&)prMMFB$IZAE z-!Ql9`VjmGKfxdH7xc71TK#w|i&v!|Cn2Jd-aVX_uX5n@2M8cW9TP`u|5CL z%8O$Lmc=S~Cf3CU*af>|AMB6AaWr0mlW;oD!uhxmA21haI^bit2|vJn_&M5h5v{-P z@kg{9Yg>6d7Qs|3jpeWs2KO0MfAxs%xrvtNJZy$-u_IoN_S{6PKLM}8>u?6%gbVOa zya%7ar|=DY2S3IG_$3DSHPrBbC-!tq$l8;E_S{yBD`7RPgY_}E52EVj5D&n?I10z& zB)k@9;ElKlm*8@|7azt)aSJ|&`|%*!^Al}6zQbSe4@^i2yC-9DOvkdAg$=L?W@8I% ziyg5a4#ewl2F}A;6{7~x8ZKwg9q^o{2qVAW9SzRr$ZS$9jjsutdEVc z3wFmo*dK@D2poqK@mjnd*P}i6(B|9I_$=pTMVZ8}7hY@eO<* zKgQ4TOFV)<;W6~}MaSk(I+n)ZexNFEO56cEV{l(kbst4M8|UG}_$a=E@1vg<4!01V zjg7EB4#E*Q1}EZVoQpT(efR)Af{)>5+=_4EySNWO#Z(<*wdqs>t6@z%8yjJBybya~ zUmSzu@kYD}7vU1T7gyuc_$f5P9e*lA(+)37v_!*lR_ybv$K&Ugv- z!TvZDN8ot85~tuaT#onRT3m-4aWihmowx_z#Qk^>Bl;q5(<1?kVsR{u<*+hV$GX@6 zv#|yC!+|&)N8?1CjMw80coPQqb5%Q+5Z{3taWihi9r!A~f$!tT_&I)wNAM?1E*Var zqSym_V?Iv6TX88qi_hb?cm&Jp7`sjXEIbF#$F|rJ`{6*m60gQvaVf6CHMkkK;#>GG zevdz*9}U}A2uoom*2c53Eq27-*bhhJIJ^O8qMh@#=~x-7V?#U# zFTxI(i+MN;=i)+KjCbJ*4DNfY;cg^;2j9m}@H6}xzr&yLcl0xu-dGGz!_rs|>tRDY z4}<&Ys$K1fJ7FFU#mVMe&zpib;A~uhtMDOQk5A$jd=vNL$9Mpbp2!s3jYWT~EAHz+!6}RJV+=KfuxbLs>{6>5X z6Enl{D~!c49joA(*c7v|JNCkSoPaZN4&H?;@Bw@XpT`$*559><@F&bF8@9g^Hozv> z4m)9Y?1lL_0dF?1(eGw)87{|FxCVFNE_@x|#(nrHeu>{=Lb-5w$(V*E@l33R4e=c8 zfSvJD?1T9@0k6U9@K#)k!F`W4{`V1YHYe%#Kez*T;p_M|evd!m9~e13%u@tYF^Xld z4%WwW@dE6IJuw&a@JhTIr{gTV!;y)=$E! z<`bS*1M6dBya02s9d^R**b4{Z5FCYLaWYQ9JMeCN5Ff#(@mYKsU&9Y^KYoqh;U5^u z3db|sT&L?juq}4POYl<6#XKC2qwxxygxBE=oQpT(VqAtRa1}m;>v0o4joWc2zKU<) zd-xF^#4qqL9>w4A7$#N-r%z!lj_Ftyvv3hE!R2@_K7{LW6F!YQa2LLgZ{t4v6u-o8 zF}TmQ=I0;8@n?kXPr}nMisi5Z*1+1>5YNFD*cv-x7rYE}aR?5_33wGw#pyT?Z^5N_ zC$7e|_$WSs&*JmA8~5OQ_z@n&FYpNdgnwdO#c(>NU>cUfOstI6u@2V9^RYPw_x0BN zYEK;8-&=7n;{G@YN8>o0gxBIMoQn%_G2Vms;e+@HK84TV3-}VgiF@&5Jb+(ga6fU4 z$IrySV`3%NCoE@f^}GsL4QpaEbG+xZ#CF&TgZq!GdoSYAI1VS_wKxms;&Qwf*Wkmr z4R_$@_$3~}pYRy^mBV%i_b*rbQi)4pCRW6%SR2pAbMXSa7`x#(oQT)r^>`!Rgo|(q zF2{Ru4L*#IeRd=EdugZKp=#-sQf9>c_{;q)qu#W5YLnWOZa zK|C89;YHX1yJ1fpg=6t5yapHGt+)|4<96JMd+<&C0Qcb`{0fia&*)VP$0r_BFby-X zEY`vLcrIRmo$(SJg2Qn!F2fbL3LnDtxCx)e?YI+P#W(Oh{0I+Xa36ckx5LCoF}->? z{-rSsD`5?+jScY}Y=$kd9d^R**bDpPARK{XZ~@+mci`Q)8iV`gYkVFhege1PbNC{@ zjBnyz{1^}5fAAYjI8)PSnCB&98kWRNERR+2Ol)EH((wW8h+Xhf?1OnY6sO@#oQJpI z9e6jc#@je}c=L@L3I`LUp z9~aomnO@g000zre4taP4q<6vK2ZjagU;n_)|A zj~8Q4ybSYjD2~DLcr{MNSvVJ0nnOJAeq4tea0@<%FXGGixtZ&EU*h-pBmRMrI$^ye zOu_P45zoY0*b>{|#n=rm!(1GJV{jJE#YMOT@5Yt59v{b7FnIoj#`8VmkMJ}65B`9^ zVEMY?cvr+4SQ{H*@SF_gZ%%w6UX0zaH}=C}I0`4=RX81I;X+)DD{vKV$DOzb-^33v zc>adkdx-ceJc2)ATD@@mOJXLL$0~Rx*2MIt0%JQGaQ~XJK7zj7>2ITVV(6j6Lx(9Ed~k zHoP5!=ZI+d_Ypsc!E;4azL9t{Zo?h;3cil-;)nPt9>Q<&2>yzHVnY3Jx+G&7mc&df zk5%wYtcwk>DQ06A?2dhL08Yc1I3E|{GF*7Zjkp!J<8Iu8d+`JO6c1tW+!W1+ zKZ(;Dgwv-qW??0)fweJsu8R6Uhqxnl!Ar3Z&cGY-b_|}gqC6XjH{vt64PU|6@pJqV z|G-GYa6F<|1}k7?tb_Hj4YtRAI1ne9?R8xp&cGY-W?Y2Ja5+ATPv91O4iDj1coc)@ zxoEgvqj31~n1X4Tfn~80R>L|NJpV=c+7Wlc{x}G)!Rv52-ivE-9d5+UxE*)m9()r& zzA7jUV?*h7*4@yI2-5TQoIu%#V2sL z*;e=C!FTX|Jb<6$9~e0&>@NvZ@C>YiXJK7zWw!FXw%8ei=jy0@IPqw_0w>`uW;5MS z5bwl$@P2#{UpLRw^_}=3?#D0jTMVAJqx!!R`{#!J7sBG0j=}SHR6mROOss{Cu_@+Y zE4&!HVelLtZR^KaEGOb*ydH1ByKn_QfDhqz+=;K^8~BB(&m_TfdE`;zpE0$my6ad$ z2`q!BV`Z$4b+A6R#g2FhUW&nUdX#?%@hBXNvv4jh#Kjmqr$_y7AP%0_qj)RvPTY+j z;{p5+euKW|rHyYPEQY6HX)K5JFnErS`a6%f8Mebtn1{i0dsKh2#X43y1#iIFcqiV2 z_v3@O4R_!x_&OfKuka}TjK$9nho6pRF$=3=4XlU3bAZ(D3y5>D2lmE19E$lk0cYV{ zya(^Y2k{Zyj9c+7d>4LSN zj8pIioQ*5-eq4tea0@<%FXGGiHGYS`;2)Tf9ZrX2Ov92`7PGJ_*1&q$5L;ne?1uw! z7>>fL@EW`YZ^MmdmgjB8ZMXwp!PoI!{189KFY$Z)5&yv8IY?QaS48^~8(u0#u?*J5 z2G|s{@gnSi-LNNKVV>@Jlkhs6f%9=8-i~+SefR)wz>WASzJc%IM|cRo!Xx+-rZx}T zR|3o6=~x-7ZopmmD!z^H;iq^A zzr`b1BqwZNDn_vkR=~=54xW!Ku?=>@t~ksrrRym$cn*}};5kroD&^C04$j9_xCYl_ z@LVYMzm<49?!s5`Abx>|@hBE*5w@=go`zAZfwi$Ao`Ws14fetQcm+u?6%jEnFA zdm!Uf350Ves52P5<%4SK>{$09WA} zT#t|Av-mu|hace){0aZWxC_JaDvHIi3Z97Um|cB38w^*Z`YiHeQ4sup9Qo0XP^(Vm?mBDR=|U#znXU zmt*ieE46zw@mAb{yYMZ17r(;8_!Ity<=ceQqavP(wXg}Ehpn+4cE?^g2rtL+cqLB5 znK%z`!3Xdmd<-|?tM~@Kk00Yu=A3t?Hz!m3yU>tRD|iyiS2ycBaW4=3VeydH1BrFbW<#QSkGZp9tA3qQbp zc*IQCeSYyzjO!4VXJA>Zh*j}CY=*6|9rnjTI0DDubvOf;;+?o2AIBZI3%@bX(0vi` z7yJX`JBHnpFcnK+Ijn%yuqK|3jqrSIj%~0#cE?^g4kzNZcseyf}?2m(R zG>*ebcrDJtxwsG)<2`sEK8TOtQ}_(Nh%e)txEDXc&#-Xku>Hj_9ZO?Htcta;9yY~n zY=v#H8}`J0I1oo-KF-5ia4Fu2t8pzpicjFP_&n~$J@_7egvZeD5>AK0SPV;HCRWDk zSO@Fl`PdxWVJGa4y)X}lV(`2{ElN`|YR}Dv|VM)xy@>m6f=MSoW3*y$;*VJdh0eCr%#PN6~PQht-8{UrhVDS7w z<$c=X?wUzgw86Fc!lM44zY{;Z!89ip{Vk2G1>2z2Lcp@>0tC zU>**|>+uG>2^ZipT#l=74L*b0@NIk#_v1nQ4Ub{sC5$(oj%Q#4Y=YU?0{fUfJ+D6w z#SwS~PQvSO1}?{YaSc9lPe zj_G(N*1`tZ1aq(z_Q2kl=qdl7+76lty1$gE?}Iud9(=E@W){`{-%QnW?#<$!mu;5N z@4n4+Z4b;+o~LF9$9wykI_^Eh%+meTOnr`>XjansF0-n>2bwiJZ@#I|NsG;Ty58HY z?|G}uMxM9MY@**Inc7cmHFXYar>S!rdrTeE-fL?Au+P-?`jDw(GlxxWPk%P`-Or0i zeHTbFJ8Aq)?He;pZ8Nh>ErZoeO{?HOo4qvt7UydG%^@0pbC|~8)Noxx742{1zOXF|O*7%!qHU8#2jla1-<8Ln2_?vfV{LQ;G z{^s2pe{+S#-(0EjH&sK69Eh4V zLHTf;h?8*&PQ&@Q5EtVzT#cG!L0(O&zzw(+x8qLSjeGF}+=rjyVLXaIwO;ndei+HgI8LS5~ zg*aFb6qh9q)(6Fvh=cV(>ur6DWw2hzro_Q|p|~A!C+v#-a3BuB;W!Z|;}o2R^G$6J zg8S&o#l*{SHLk^VxB<7C+Kz0;owytK;s>}7KgGj%6o1CwG09hctqduch9xn})OMp1 zR>PXu*wp^0DQ276F9rAUm8~rq&#~73nik7CrZ(#JF}UBc_Qy>vmf2=k z&3|ldYWvU*JDJ)Zbj2Q~_Se0!pQ-hCAPzCLlNgSp&0(7VIME!T`Hxe~QJVia)71Wb z4$e2VpI?ZJP3`ZO;c`>^{d;k>IaTu?*O}LA{^Ledp9ePMR&$o-KkhVVYyRUNbFSt; z?lrYt_yG5rTHim#L#94Ie1(TieU3PaKb!hI@jH527wvOJJSLedH2*QpT&ekw8KypO zl*KGlpF1jHHB&p&npnrw=aBl?*wjw8DQ25bX#QhsQ=d=TVJCC5=0El@^?9W?_A|F? z{^JmHyXHTRHnlw(hg$5txcEqT-}n?g*VW>pdhVvF``=f?x~Nsniz^oKv&ncv@7wxYHuuWoC(pH_%ibEn;3=$%v;#N!y=@r$xkzi$*-n>Y)2AW~qp` z#LS3znk8Ob>4+D64k;7y)?1tz@t!ivMm&v@7gsLgy=p4|TlhZi$ItO=Jc7UAF;t2m zPZ89p1hJYFs6hn=_oG+k>cq9N0iKJ^uobq)F4zcDx%` z;e+@nZo+5qdEAAs;XC*t9>6c~Tl@ik!-(x4HJu7!Q7nO_u{>76v#>s%i_NhO2A?yO zzdLas%){XGg}RR=z6z(}Oq_?e;vIM|uEF)V34_lS${*avU%o>5TNr$vQ27Dk|KN8R ze2!4}W5kJC5p8-E#gdqbXJB=#gN^WfY>Dl#3to!3I0Q%G1k`3BXh#v$M~NUVh2^j! zR!8l^gL)0{Tx^EgWd_~bV;Ag+eK8NUiwf$G!7K1;ydK^5L%V>W{vx~`??!E+gYFOF zqqqs5!RK)ozJ~AMhj;+Lz;E#f{0$?l4~0;h)}S5QGzMxD7Z^P6Li4{eaSg1Cjqp6o z!8X_tyJ0WP#lbiN$KsWEEl$VTcr)IHci;-VA0NiY@F{#2ci_wT2EL0Q<3aoqzr&yK z5A<1Yk}(z2F%v6bRdm~zvx%GF1=teX;>GB;Gr{vdG@k}gJ`_jcc$|c8dvgQvT)YLB z;9a;9-FD{@;wSKF+=egWtLU~r?-TFG&+%(Kg1?~K4kfT1D1ybY6qdt^=(b0-i5uX# z*bG}?dvx2Sp2U4I4~O9xyaKPr>v0y&!$o*I-i@p9L3|W9;WPL=?!wnFcyb{Fd;FVu0^momcnva5vyZuY=GxtGi-(Ju?zOZzL6c~Tl@ik!$=|4e=Le6ur!v( z%2)&IVj~QmW25oOA#Q^mu^aZnTpWxea4cSl*JALz8|9x(d^6sLci;-VA0NiY@F{#2 zci_wT2EL0Q<3aoqzr&yK5A>5*|1lNQF%v6bRXhvN#wK_Hw#2r0F?PqxZ~zX)Q8*qa z;Z(c<=i)861n`bgzKb(5+7{uUn4wF*ca5MX@Ai;u+}H z%TwJRy5oPB(tj=v!BIE?uf}OO8yDabT#l>oA$$yV>LeJSZTJ$p<9xyI7qr}bO!;T{ zH6BHGd{2*T4)P_VPK5+go|() zy5n~b5I=&!?-4Zq&k(I|OxqpYq^2x{ALb4t{^2*d4F?lkxGLCeg{9ogZLG?<8QwbNBnTPNy1c&qC4(ZiMR&V!zP%G?s!`V;%?X*2jJ!CjL78Xv~s zdCAJ>j(csVd>6is@8Ujm$Gg5E{sDhSUpqFNK84X8=gJ^1k5%w2tdH*aR&(Mu7(7Q= zdAk$$L3dnhIPqA#3a8>sbjP!T=PE1T9hBdTYj8cf<5*jXcVO^*W%d6S@dxORU;T&p zJNy}sVep(~_3w^bl`Iraw@eJ4yR7cjiR+*{UUfckOKgW-@KSWgsfG}b!U=daPD6Km zY60;QT#l>oA#}&3HWP2d;JM6d|7*m1(H)QajQDFjioanT$4`NL`^PkoIe&Thg&1|rJ{jZK6Ris{Zbl*eV z_oQR&Qgpuy7(zS>C*ajM4c+en77#DN<+utTLiam> z&BWXAC43Eo-!p6c-TD8|DE}Id;%^wo=Vf=^KaIE)o{p8VCZ3JwU^8ru9q|%$=lKT` z55s)C5~rX$zkd_)B3yFA_$IpZ`JWJffx+*SHT`}f{uAAK{1iSn zm%uVu0jptcY>4M!3v7#>(Ve&NM?4ru;&_~l?tJ}?#5dz&ybJF`cbo&~?dZ;jzfSxv?!(XV8+7Nve<$|&yj&QIV+OkO z-&Kgu!uohFHb-~fyAyGD?1OnY9NqcutB9xKOq_?eqGt2|iq9{@XvY}*|9=M=&X@D} zJdlHJ@c(niP5+0M!~dx0+}c_q^xK5}p?vFG|<_9c+77O842+ z2^qVNs+9V%>!->WlUce?k$HxmccdI~l|1hwod}Ps>Uk?OWDQ;SQBLYh&@E;?&$~hW z+VxNAc?=Sp*~?%U8>&hxwvFOoX>6WqsVspoy%QL(d)_zZ3%V}IlRD|6*{S7F(~r2CSxDFY5NmRT*ZC1^w1VYq2=Q=J z%g#jN$!03okt_cki?#f1q`R6HEQkAuKQ*;HdJ(Dm@urr`EaFP0md{SaT?4)FdTrGY zzV~J6x+}WxF|{lO=Wo~42j^v~s=dU)c@{0t!TA!^55DKr)_kV>UbCK- zSK{AIO`NiRm@muJ^4^%Zso8|54s2EHMAZC*EOj7a4Xj`Hk0mi%w}Ad zsP3yR&e8SdbPujK)Or$ppHTNVtz64o@clvYVT-liq{K_bX{OenI>hx&tw%$Mhnrdk zgU|P>KiOg}YcuIS$JF|@mN@tvuk~yv@orPgTyVT!{Rf}ZwcZ7vw-r~?vSsUE@cCJB zaQ&ASo?yFV!?W&MAD5Ymmz!EIHxh3)N9j5^;-5`hPZPuX!Ex>@wLTFC$F;TI2A?;T zZ=98D{ar}+#pYC9zfZiuyk6}mK4i|&b#+C%MTsm-i^zfIL@mzFn3(8 zSF8Wnv0g1Js5M|z-<)P0>bB|7wdKg%{=@VBR@`Ff*b~bK<_#D%Fz>=q`6F_b&m|c& zbmYK}E!vD6m^bmS!ohjtI<{!pDK|fNM7z9^gU1ayp;L$PBl>q7)Mb4Cpszf&C_iub z@q{t`cGeK{2f7ReD&>sN&(9kzp?zKX0s>7TaUT7I_m# zj~Y94+^GD%ZAK2r&l|z0ovc!eyi=$YW;$7O{u*MK?7yxzbmZ7^x#RP5#|<4dvPIsY z-0{OTM^4tl(KZ{}#PsoBRLvPRa%^7ygdq9Js}8aW)TQ%ZGj>Go(Bb_@P3)VWmpkyU z(y@6X2lgE?cJPUbth9B@W}Uk>Z`rKtiJeC0j~Y0BKwj&--28F<^G;aOhUX6Mk{7$^ zsi1S-SSyMh_aUy=?zv;TXbCxaS1n(8Lnq|LG6$zIudx^~ByYelE%`aE zn-^%VjY)_01q$=SynidV%3WG?Y?+@wD*wb*skCorO}Gp5M~&#BiJzzLZVgkn{Jb&a z^Tv*|8vj(@J%8vpt-!GpK|M7aIrfUYd`$$6=Fq&qMzizK!9&J%88URxxS=Bl_ib3e z|4>b$U|{X?2K}u=Y|>6GI*!O4JzBlB8EHMmcC#@E+R=5C8-du)Op?FG<;1>~`R^%X z*F{_0`sWT9HaLIO_>r0jvANZAIF`)J0^Pdi=Z+jZ;`m5v!#8^LfN*GT5^GD?w`-5S z?ZZX*@7+2V=oUK!W-7Dj#Fi=V-$tvhwkriEUgx~Om;E)ieFx+Y9}tuH(!LsplPpU? zH=7p)m!{)QK3?Nwb1SIu5A!RSSk1fky|B%N9sA}C*ILG6NYGeAx=owMJreP6E-v_bnZGa*jgRWcS6U` z1v-X1N87#?7^0e~`Pcd4*101G4!4!`Wcj*`%Nu>Nu3aY<=-Q?I39X6gPYtO%Vr;<$ zK&9GCHXArFwgF*b$Nrb+4H(yE`5d}2wsEjgjA>)%@4^>3}V zk`r5PB`3DpN=|IGm7LgWD><>%R&rvit%O#08>v0pfV{C|^9BYBqD|Rxc_T*m9i@%^ z6}AEIJ9hlo(ZPBhep;*5K6miY0rp|Z7Bu_(=03Fbtvgn;IM|4c3d(c3bnlwex>mg= zb;4z5U|#?6gZmB*mV)qoZvX!Ic@tv0YE_I4^&w&8VE0)p?C0+#BXS4iYr(RGKCCi) z=twO`;d_1F^wh!;BaZKL!}3A;_@PS8I=8QtJ8oS5(Ej7c*>G%2K3bn#Px-aJu;=Nk z@bQ;@$4=4Te*Kk?=sSnBzk>C$Rp#p1_u`Y)YZp_m!oSq(5mV33)1EBfz?ga!|D~Qy z1lKi#V(QiUmwHEI>ec?2dY-zu@wM~#u6>#6 zU!k2^3SKD|#JqHZ-4m|7E?Js$>1c4%ZD!#h!bgQ=nck z_2jz6*3;pN6Y{00o(_K=f4P3f6sV`KyTN@FT}4+raC^KK<;N*oBJS z%jG+ug4lc+%4hvszSH$*%Yns(lq@!%{Z?6rQ;)w~K3|n$^JT^4%TjHZ&$czO`L-&7 z9shDKt7k9UX2#~LrhJQ4zF&W5=+EWLE|71E7M$Jc?q05aO$+4P8q>Z?s_gRR7074D zfc`08Zh?F|WAasr$#-Lcd>NXkhg{>NYu}6l`SvJZCw1SiziRq(?OR_UpG_oNHr&hQ zd#FIZEd9tkTa_%|nfi12?3xn&JHEVZQ9k?qhI_fUZx_hdPx-P`X}|t#opt#NsfXBn zn^ScBNyqiv%jNU+CU*W#Q9d`mI;?*@U%dkPhM%V6u{JPXE?=zz`SvJZW7Vo?Tr^|O$fqZE?zMcOM`Q{g>H%;|s#?*78WWV)~ zZC^@8IKNy~bq-$l=uPbO%U1ieXa(bI>!)kqvjy@sR6g5YxR=Xk_wiJstW9!XSy)yq$&+ZKp+rCa}pWFU5Reje! z`%O`7zI&9f^FQRXYZ+qm^;15LN-+J-kI8pIfqX}mPltGqzufpV8i_r}YyCA{ zMi;2pM>|?u-rdXPvvUWr?VA`gKbotu8{g>#^374c{w|qx`KA`gHzg)tig)pbGAjIYy~_&JYpr^=thtxV*HiUk+qYHiv+dq~{dLlxItSZ_D+}aX zUP$LhAcMUVdZ;4iow30~Gddvz{QZ+Tta zr!%H~u3mnDdS!JE{-3tHBULYUJeJ3dN3MqFrprwQ@{LwL`yHTrx#8YeAm2LWv+IKQ ztKtCtxqK@M^FvGTe7zI_LD^J74Pe7`H7 z)pIX5KkPS;vBNFdJY2sE*1NGly^*Td$5oOp-<<{O?N+^u{-NGe1?oj}!tK1P>hjsO zRj-&LyYrgN&k zU&Xd>ney58+r3=ABB~eLzO6C&Cabc`SF=FA@0G8EOD0`DJJ%nZZ)Z%tYhv=*Z#-k$ zm)%0=*R_nhmz#ceZCPx-J<4Z2?pMVr`g85;Um)L`Z9H$Qy1SRlXTKpmAz$2I+l}i~ z+2xyDAm2hQEdR7zO)QXapYpl+J1r*P(gOLuSH9Tw$W1@{jcRQB4#nh~5tDCYfqaAX zdzED_iR!tx8w%t*tbDE2-KO8nn0&7n$Y;-%8}24rOuknNc8{u4$!GVhI+c2M535tDXZN%^m3nsV z;i=TKdtRMNJ-Y|isnoN3Vx3C8-%hb!QLU7xlCS(J)~kDp^>R+JUbj=MXV*@i%6MFP ziuGonV!b;~vEC!6SnpNUv(^8vQ|Yf63SN6!Wc%$@k>H0k1dQNHFbnLJs(*2>pf-S_Kn zxBgBx{dz0kW2dnG&R4$1DPg`>{v}`Wfx4fVK0CVC$=bK`b>G{{_G-_+{se%3=N zQnlZ5FUw=E;`)oN*Xc9g+oZO*m#e2AmUV0~Avb?)tx>hJ^s3vSVckac>({B%I4i4; z74U!EI&~U0Y^d&a>eZ=V-^%+HzP4q%3nLMi$;PGH3G+7P`k-4v{a~QgbR4El(7n9k zEd5#63i>;P_Z4L&-dC1Ycwbdk<9&5`Chu#=n!MLx+Tc8p<*cngTORDa4z~us2e9`# z1R6|xd*48R4fSX58|kkx@0&>5UR$|sXLXn^c(222-ub-OB`IDu@0-cy`m@)upl0~~ zpa0he<^Rg-|5o0xu}3vAYSjyuLH!?Ds~MG2sk`TWnfTY(#6=Ph=m20`By=A06V73gtek!NeyF z)z7=*;tM^X{ez!dMqO%_u-TAst^V`lXQ-e~$xc=Zgv^j|yQwvGwb0yU*i z@*UQc3$;}HeZ#6r8D5e4&nfOloaPm|DN}K77^hjP^cDKAzdt}dCs+oh8l9XMr&J|0 zi~KQR)xuF)ogc=LbT6e#d(R(BSW;n*=Z_1+xYN9p7V0{lP{Unzxspu?W8HKs9HlGh z9`6NnVjjx=zSnO6o$4_w8X^$Obh@ zYrntDpP=N4HiU!^!r`q=PSbX?$a$&i{2=)>3xc`*P#9-e|2IFP{~q=~v;M7*gtGci z?cJ0--}=96kvc#5SN|PuR{T^LM@o4`wrTC~Hxs-0@^ly{YJ4u8r0!ejU*nT&@iW9W z{E7OM<8Sq=*r08Q8uaVQ`jA0W-w3Owl=O;BxKlOX4C8pE4i?0>!Z=uZwoFrnxBa^< zm1R(>eaY$CiPSrsXl{=@JURci-)Ms1HN5gmtZ}p&##mB=uMI7b=2jXu&S+1 zk8M@_EwR?7`qLF3Cf3?CwTj~Jh_yCV9;*0zVy#WVppOuj@ltYfT6+Fb;?iCbO!%~0KX9b}``Nei%?Z}xqVaxOB>C0^{k*MRORWXPBVlE~ zoR>ORJ7WJd3L<5_)X~#aP{I{tda1A3=#_K@WxUjmEmV;13QBvat8D>}x`GT1rJcs0 zlq)Euf{rT4a0O8>HCUZWyMlBtHJAuxDA2m)r9IYBSu-R4ej5#IyhfuzBsocApITCz zY`-D3seJE6DItzqf_Fu`4L)rD~h*`Au9w8bdsX0$W(p{C`Ae|j zXozhi$#yS`)a8}ctsS*(!UYX(PeFo>baQP{I#8hXAT^jT9VxIGllFwoxlR$kj7+e! z8bI$zvYikq*1U5k&%cb?iDkTET`ubG`F$ve(l4+ z1raxn{V52>an?<$G9cnlvL@Jo)r9epWV@eTvCg(|OrW;5M8&#V!4W1BnqUJ~6K;wm``XhN%ehcP zoJZ|64e^NWN#;}F7gZB%vACH6UHTr*hy@hrK4qy5o2kYvt{~Yk72IpRN;}{)4VS%lka-&b2dOE!NBo+Vn65+LoohJW4gzxf-b&jqNIU#1$0t zQh(a4g7vOI)8;bU4?pS(QnWzmv!lPk6%^4dZm)&(F;`GnOIZtT2OoC@$tviof+t)- zl2@!nJB`am3iMl-)WJ5CO|HPE-T_-OpN#nFns5m=%{28sh$P=*Q?GeP<@=D@!9vwh z3;IW{AWieUTW8Pz*cE7qU0SyD{C%##2C$*72CzTk+hZ9LEUgCcofa9b0I5H`1{21}={&@+ORs%?kOYW?9#hPi7 z6^aYzlztnQ`sh`vn?ylG-%*0)A(;a0G`+O8byTHroS&}#6D*0+MdOkmwRA0-*U`q2 z+BQL2G_R|Tqbtw^Y0`B$pdTvZS?u1 z8I?6b6l?3=oB~adVx2m-@%$VLf(f!QOX*s~`Bl_^f+bP9&T+}-6x9suwocu;xZcZa zLGP!6uCCy8FZC{46}q_sZG3;wcNzZ@SD<-rzx(vNy8`XCN-a=94_BbQ)?_W4eot4R zy;jG36e8P|s_tf}yTJ8|p3HRB*W~Nbpj>(U(Mjm@CkV zA8ewAQ=kd%rOm0KDkI|j@itp+W@@&sj7z?xm}YBbnb;C9lJm3m6TYo%91#4V^X6rRJZPvO1&DQ7ptKdObpxL@kE|suq)7P{nHB8xq@`9Z*8!TDTY5Kl5R|Okf zflZqS&Qi%^aeg~ZmPDH(2?O+Bacvpn`~`Y@;!4{szO0f?zen_8 zs6@W)alW9^mkSj9C$97aDt)C@(<)s)Q{`V%scvlr-^7*vg-SZ{-qtGZd`#uvQR%(W z3cimkW4|`A!5xkBM_Z+JD^&gimA*Yg!H;pJ)3g%m9wZU}{kY@}s+B%M&G*u6a>S?G z_$H;>2&JT3i__ArNhQ;5m>JPv&H6bm#d<3ne(~L|x52mJ#$MV}+ckt=!eOfwzsLDM zs%we-msR`+tvH}_b(u~h9 zSDi|JMjw3}wh^l8`}bNU+p|=o&ZIG_Q{69hKXq#O{)<-U!WLR1YEr49O8m3@j4>Lh zS3JwFB*7ZyHrzx->X!-U0(q|~}3fb8HsX81-NwoS2RuKGGXumR*Q$^Rg zsNN@7fwDL9{dRg+V$(DwZ0wgvvfzd#3Yz$(a}{`nD(L%SZ@qK9Tm1wp&{&@5`?K|~ z#JGpm$N7xG^f?MH@H3aGN2}D#_t#ma9(`5boJvb<3zg%S{hUfIeg7@1v`^;;{R^pd z-h2hE{L&R{6H?Nv<5%#LH!p$N!WF2BAAXKWw|SD3ZWBEv8f@2V`zcmAt&~k< zFOm^_maOlmJf$crl5y}NC2!ytwJd#m) zkiw>ZaofOcjg%UsO4}o)Y!d8@l(LcB9m$wvy|nRDUevJnL^5{Sh+gEEdRL(rmoeSC zw)IoKurNNO@nD7R{OGS1riB{;>oJ(v=Z3NM8N@}rLbidhUV~USo!12Ntl!caiapx6 zkS*bbOH$#Omv*hKQ0>EstD}BB=P4Yg!!7Z3%IcVkj?&zx_jRMzyT9{(y{}iIw!Lq> zN$<}tI!5oyJg@C;Iu@1K!oO8TW#{zKe~GP<=B6wALhH~b+3I_lyPi{UQ4qvsF3{qb z*e(d-GoPBQ;L;#S%skRhL2eKvWzOHDATJ0CXZF?7nm9Q5Ol3>SY^?1|;^je?w9FkT z3PzM(pkbEG)ZsQSaa8gW1sPt#AF5q0-dcNlx%kB@^J}kG_j~GC1IzBMrJ0quvv8fL za*p*9Ure*?c2F}V&r5uX=yWe-q?fp>XwXf!kxJ>|CGHNRNT!!EKs~;k5_I%+Jf&Sl z<$ooNwSy|Mc%IG>Oa0nQH$Rt_Tr0_u=qXKJ+Vk>i{E$M z6TPx6dRuEgD(vYHL*}Mc>iThz-OGH&f_>qjGM~3#e-OlH?y}&MAW()rTFjFY4;HRw z8CJAbr_X}1^)m0Y;PY_Qz4A9)X!ZV+oTqwOqdf ziC?GN{K?XV?q1?IX=^m&yaY?`zpUApc({@!s8Fn@=k-WDJCdY%;6>kmRb3iHl7dAq zdS4qw4Z|od+OM>tMqv~m{aPOZ6B~z7VzjSKjwWH06g~Y?MLMRFp_D1n8;dA9H57_$QK#towu;V+B-=$wUA=?}YEhxf^`G_0wmU&z&b%|ML3Q<}V(?!hz0=}p zO)eL2^~=SVbG0m0P)mh5dY|@sCk-PzQqgKx_*_lfm)J9sG*V*|Et{`SmqrSQqx<@` zih4!DIThV#lcIMR#aC+SCF-b<)k}=tr-M+5IwWL^Zc_B&DvJ7s-BO}wS69?85-b?S zqSI{ja>FPsdgW3@{Ue3PYS1O4=haa(AdE7icIVv0fssVpUX_hLV;@%Y!YC^`b+MvB zk(3@9flASbmM9t=Mw6o}a}*5;hwx_ff+rOX4WqZC^IlSPc^K`DUVg5kVUb`v@PQ6~ zD_OaC8=ZFblIFS_mmMRUTwnhq9Mr)&Q*nHmv?;hbj5bH}ZHM!87;TMyov&z17;TT%y+YA5VYD-vW;@=kVYEAXkL_%q4Wm8L zfwwDqE{xucPQ6RfwlLZoz2PxM+r#LC=u%tBUkIap(JePA+7T{2pGMEL-Pg`A`YhVI ziJ}+7=ukANh@zLm{=SMXU!rJN*zIui_uCZh4x{g*pAS^@a#-_dv`KkIuY}!xjy_UB z(W_zfYqXv%J$u5Mzh~(1otOAp*v->tP#fLX!!RzA(Z#j`Z-jN@BN=l`D||ETniRf(wKDzTt+Vh#QW} z=(vpgGU~YR-}9VXTX(|D{NC?-|Md+JnGSKWK=+3vaL-ntv;>+0qmHS2_#K;KYT zEzO!$1N3hS-A%LZy8|e~n`GlXH0yj)CyI&)i~?GSuf=S{Xn6mnl<7cpdTvqV9jbA0`wz= z9;R8_PXzk0LMt?D)Db{GQD~KBRi=P`s?ci9x`LhXnL_I|>%+M~KUZi{vu>l+`9h&h zniXjV`cH*U(X4+_jK5UqQJQtiwLrg8Xsc$uO*M%~Eon7Fv%VyE{Y#-8nzh}nK)+Gw zEX|roE%U8Hdo^pX*+9Qj=v>VjLvH_Gp(kn9WfbQh6gp3{=ARGrM}^J@Z(IuWCxtH5 zEap*$epcvW%{q-D{fj~`(5!!u?7u4X67=8$Kz~!{63zO9QvJI^m!Xmr>pv8Fjb?p= z;Y3K&#q6#GUmXfmSLiCu`homxDD(!+%A#rxD)c7J+J&g8&^4O1KT!moX&TpR)>QU> zmM)~b70oB<2B@odYStnqPQs_F(`k3fe3Vi}{bRp2e3Vm9$ zdRWP=6}l1a<<)Hz`T}~NSGQH@X3g4$mTo(RzNT4w6Wv~+Z)#Qn(H#`}j%FSG4A31F z`o3nJ+5~hbg?^0wy%{K?;^d9bHLEHI=q?KVO0yo~&6YyH)vOh5KzCKm{}JL$=HE@B zKWp$}fbOo)Uo|Vn_U@t3-!+RH(T4U^kHVnxfop*NNnH)<)+I5Zdnq)eTdQ9L8dm54 z-CD8%=-vv=)~#R3WP%-CDQyc?{^j3f)$>4mW`Ar_k+nYblNPP=)TO zTOVTJ7202+JL}d@w*VccP)oP=UI=u!LU+@xqxhl&6uO6Qh1mqe`^hSQ(yeN;_eh0? zb?ZbvDo3?DCdsKu4>aN9xw}5}>&X9i>|ns)6PyG*`F2quR_@XufW} zM@?9u&_Yo1XrP4(E!M3Yjs;qz&{EynZZ6Pbg&wF|!91WP3O!i2YOexXs?bAptLkB( zV-$LrZrwZ&=z$6?*R5x%>JL(Ag>K!;s|PEzQn#L=`WmayD&1PZCm*8F!*%O)*6L7& zR_oRayo#9&lCD;_o+c&B6k4xaZ}DomLgTunZ3G%oXi~R!J`HGvLK}7KG;&Tbqej!t$*@ry+S*6>p@DfB#$onBG1LNCy*-}&3A3cX0T?tcNJI30nJbgbh<*9>DDk_ouSaHb*oDU+OE)RbgP(Gk5=fly7fu`=rIaisayB)YKKBs z=~n9#KxZoS2Hkp!S34DY6WA;av`e9D@F-rLrO>qySbB5ED)d&}`UkIeEA)2IY7WpI zh2E)KU-N3OLhshCrqw`aEA(F7`h!=GQ|SG=_4-Rd=P2|+-Fo@YK#y1G!@9NYQ$SDB zWr(>Bd`0wRg+8HMbJ?O()Xh)p*3q+p&Qn)6LSTuWrqCC_3{(_nD0H)KSs|eF75bWP z&7*61mO|gut@d`H3l;i~Zk`I0=rVH7xeEPCx6a=V z==lo$R<}0L@Lj0X=8xzUq8BOjSBOR<(2Es{+1n%NUtOwDL&IWD}=rV=wVOVd`4qmO$uwnh3+IzV|5l?@2 zBG79TI?S-DAl0E23LR-!O}hiVPW3{rVg313peq%cZ&*cCeb+0r(6E+~u&WeWY*-&0 z0CcrNOAYJibwF=W=z)fnoDcLyg&u5Jqi7dyQs^N-X@G84=wXIcOs{W^Ldy+n#Uh}8 zQD}u>{pBH`YZY3F7tI2Ci$beF*bbn#DfDo|nsyz~+Z9@ESVuhv^bUpA8rIOgfZnOl zdc)d{wYp28al?B40-$#*G-+60P^sRd&_*<$%y6$hm@%Fv!)iDi=mYBNQHC|09^=Cb zooZMcUk18Pp{<5>+hU-PDs-A*Jv{*EV+x&NSd#|>eO#eO8&=1$K%Y=(2dF_y_oPBQ z4eNkE0bQ@qS$Oh6K%Y`*H+W+i&{b62=rxzE-)m`Zz=Rm!+LcI(7!A6bHn;4DfzZSe}&)-0s5Xka4FuqRnWR@8qj|z zbjP4ImRa7_@d{13y;i!9lBxyzz-b zD}vV3>w$i*(CVP|*96cn6q*cL`%o7Csn97w>jeJxONF)ut*633zfx#N(0cwPpkFJr zH)y?0z40%Fo)okeJOcC^h0YIJ@09}mUNwJl(E7Rv=no2A7PPiL7wC@)T@$n(AS3;x z&)HqR=4t*2Tp@w^nF}Xb1j7~ zGp(aiKzB7{0CbIM?LHjn9>%~M!J#WnYagO}8e&mzFs%_p|6~lj1y|RY)~aDZ_fl7H zHLWvf*~04Tou<`A-(-k-(Y>a%ZUoSM6nejD9j^i1SD_D@Rs(;#pF$rttxF<6hbnZP zY5n7Np!+NIG1I!S7w9mBK4Dt#Q+W?p=z7!ofj1wZ(5FqSj#4#3q0gXC=zNV-=tk4J zlai66&`qYLu^OWk`U09T6zFJ$zGPZER07Ra=w{QJ$`|D+^slD1=}DmZ3VqGAj(!|y zfkNLft({osLWRC*TH`53MGE~pIF!^VR_HsX^%AvLi9+8qtwyp&sY2gJH7I0b6#AiQ zU3wPK0~PwQX>BH_9Hh`sP3yj~Ko3^v=V%}aJ656pG_Bg>fF7dIuS_da2lP;d{tMk5 z1bUc4zcsDFv|VKi{ob?=eGzE6LVq+Zvju2Gp+B3}`VBxU6#A=aJx~R-(%9uLa1Pk- zwr5d}Gq!&KXfR|o(`Zzwn+JrfqxjyKLbF5G->F0oSLjwDYbiy4yh67QS@k;stu_We zjYn-8vd*CytWoHWA?u?3fz~S23Jt|Z&7nGD`%SoakB~Lw9$c(9c3qA~ghK)IMZ74B zkpSuqnSe3Wyd|Z<#`g>s<=>TwM)hgVLZa67$%?G2iWZ!vXi#|uBv;7j+D-}st2 zH0=&legB;_Hh-8!4k`?c+d*{^a=Aew{MYdx3?ijd1l3vCRB%!t%NWcr(%^9a0mi_A zW_IsN9B-wWq19kqV?egK^HE@DV-N0ugGc#GWAIiAHMZuLo!qPD;O8((2qLvc&KgCg zg3C32M4eZz(Y7{s-5;VJG*)Qbg~$D^eZv7JvQ4-3Uof`jm)QA>ZTRU#90b`gGY|=} z9Q+{54e&9|z&&tj&A^3CEYE+D~;yuvtdTffVCgXO_Nw&4C`P99tSzi zz`5{}%)s26SiW-u%ah>DB4ZJRH3Rz&WceyQW!!TI%afjAdB!T1Q>7-mfqG_OO%KbG zJy|Y+e`E%}SjzGudE*mM*Jc2ZNBP!SEFY8SJaQV3&!jvD79PU#2YF8ULLT4$EXx-b zu-pfnX9mu?nPq7;%L`$}%)r2hSWcGrUK-}{8hIl(oG}AWwX%Fd+W5drJU(PMmP6&q z&mPRZL89$y9CH3Jnwv4%z-m(FH+ zg}nEZ1dms5C+FqN!<{_-ei6%kFJyTZOqChv$YuFb4a=K_@@KU3c#5=Tn!II070+zC zf#s6(Sgw~llXH2z$7q&^m9YFVpXJ}Cv-~2;^88a-&X>36mGXED%$yn6`!bd}(^!6V zD9iogET7+(8YVo+s!ZV%!|@Te_P1okEG70K#I*k(=e7dJ#TuyLRB21B9Qy!PvzN+$gj9pTmQ1KceePp(QI*!LPgq~%CdHjn|X8i3u9&#N^Q+|7f)OotpBv*QQVlA&$NK5hQ z2plh!T4_R!XAb0<1w|~UNF7!@$>W9dS>7|7<>ykv%eUq6j1yU2AiepB^hi>uabY#j zkCc{vFSR{lBhT!96w5_9EcZD@?h#$I{c;`;9M1CTb69S_ndMJHlW$6RyyNvOkGP8E zGLh@w&*gE&y)3trdoEbaP$+#qtdTqI(^G@kiG%DJL*R>}Q4i)4NN7hdhCWO-zO8%R{9fZ;*H0ay8G)8pd+4@XT9Nd29*=Mm)@8Zf9r)R*3dE;94HP zB5yfRq->1b6I;#mmu_OYK{#rP(C0X5>6b!*1w(nYO5Qc{L>`w3|4clc#|wqRug&A} zLA$d2LEiO=Q0)D^dFGYzEcX%q8G06vhn>LElGZIam&b<)51b;>_iKV@hU~`j9jVoR zEj*qjPskS@zDM}^O`Hz}Rtg1n1cxBdQpj>B+87Gl+sj|g{xgrWu3&lR5}tW@3d`1Y zJku;3o)8NE?HZoncNNcHBRq3u8P9BU6VKG`$>W_LV|lFb4^HsRb}YBQllLrcpofJzkT;WUFDA85Kzv<%md1-y;3L#3>}Md;IJzDj=lF@1bo;de?bk;&@Q3K&DZui z1lU5YWEWs(Yw-txEz%z5&(G2JhP)u(>Sd~%<=Xq~$se>Q=K=htMcFrJ>hnPcbCJFm z_3EYi@uvbT)i>M^uv{O&r`)2yTMO`r9%KWa(KnuA*Jhht_Q#3czI_7a-Z$QXa`fQK zP>#Km{F>N@FP-@?sA(?NUO^?zRob4@0Up%&^|ijiYUr)7c50t_j^6c$+Pe-v+ZmOWM}a}l(QF6C7p62t9_={elx%Y z+88$L5^Wps4aj(~0dSKxpPYP$_SrhrXTD@6)8p_iL;zQmI&V z>F?~FDHl6w&!XJ5pc3WoZ;V5^_f^yz`d%((#^VCL1ZaRu-5y<={=3FX+& zSj|Iwk3w0&?U2pb`}}QfCADQ@EzZlEb~$1U@I4#Yu)^+@T&d+x#}%__U!s7i9*=`Kd(y@r{hig!d&F0;814x(p+7QYKof}au)XsOfch@go!in30lP(5$ zG&mR?FOS@F_I#XJXUx73;3=c%F97EScY&EOFAeVhG{A$w$?Vw2gX1Vx?*)&b=K3Uf zXxx6n4cc`_TULD=!B)+t`~7y2$vB-LlxY_9TFFjiX4o3yfNF%7w-;Hvn90yvVj+Vq8=K zaG5cfw_I-g?Mi^9#y*1pt}y;`Gr%(A^%DTDGR_+Uu-rJK3g8+eG6&#VV-u-hYsG&Z;!B|6qyU~cSt8X?|Q8?Ea?F9h07>(qqTaB-_2DrmG?=XNnjqR5K z+-=<0BdVn*7Kim&+R`746{KDWKWQIk-CJOaAL2ij^o*T@%7vQ|$@SOoJ3=SbLT@-wZ z)x9KG76G_4_&^W9<-tCh-=RQW zAM79{Rt3#%0d5GMtpVH^JnA-pn}atD23QmPl^w7)xSIWUOYq<_fZKwjDap47v&a)q z1#g%J@O1Fq3jm%CPMZs`G59KbWmE7;_R;gfvr7S942H{_!}#55cX;-aiKS znF;Vq@Dwu2ufd`G!5_ihuL787HqHY$!~B9WHs5@Knqz^vo=rK+oN@xd+2+su`66?d zQ2-B`?`#L~klB6!z&dmLM*$u+W9;e2%}TPy6XrzTx!zn!_4Jha0PC{Byp8?$jCsTZ z02|HG?C|Hzqxi7rO=}Xs3+8p?>zB*~+3jWXs}_J)%;RzZ{%Y3l5Ad29F9CSn{MROc zH_hM3J#U$x_X50Qo$;fcMSk`GXJ4Z$<)qY?iU@pP1+K=bxFYngKpHCzHtk zG^4u!d}%)TBEXW+)9n7Gp$~QhxH7ae71FX$)AImVhtBT?SRT6QF@P1JO~nA$hB{{f ztPJfs72x{NNOIlk(39-A8$umqhMPi*%Mq0nIm13VJio!z)D zw2tikSZFLO_;~2#1prTmei#I>KJ+v-%G03}*8*$^-9rI-Hnj8+fQ_Nu@&TR?t-T%K zh0rDC056A5?f}>vdT1!XtD$oy0K69ZffDz(&~B8KH$#6S3EmFv{uh9ELM`HhY3T?%j{T!Ocy8Ifdr5ybhik%GbN2rF3IWOzYH2^nd z-O1M8oE1A7U~N{2&%7mTf2x_=vkp88;Et>#A^>+~jUEPYch=$S0q)JZjE%l8>l;eI z16l19^arzUBOxEjnlln$T~>Vp;IXXt?gMx{>-uv6)@Qv3kHCB?YhQBYGg&31?z36T z76Lq%wLAr|DeJ@s0ba-ov2S0@nsyq%%UNGG0c_4{ehJ{OS*_;*yqfg^S>yGrhuF+F zvaUM>;LWUiN!GWr+RFgm$yz-F;N7flKJ5LhzmbVP$Z8A&e3bRmz5pL*%{T+#)2v1{{4p!1)6%HUTai@YfvxE*kLJp8+l%@Cxa2*?`ZV0$4JjhyAy7 zz-R2S?+5NmHvM7XjXe3&z}IF1{5)_+*6i1TS^EI|HgLmOfIkLyQy%7J|8WDr>DdWl zXJii{x1O18l2{9}|5XdHFnb-9$JyDVy8zC~K7dbIoPB%?zDaCwpa8_QrOA8?r}GEN;v`iLbpmyJts$HQ65=53n}-0?1Kg86oo~N4d;h}#?$7>>)O{fP={*4+${sfW;Nk4? zF958|e%%6iG<#1n-{aZbFVlP?`}f%Z>$5js3-DBS<2?W`XE(9!o3l&UIj>}|nh5aM z?CZ&SBP`v#%cq@J4o+LiuL)26p3H*>Btr@b~PEe9_z4@81mYPWJlS z0p86HuK{>3`%X6VAK5QcfIiH=a}~fx*>7$I@LBd_tiW|s z`WGn?6D}NxGCpiF%ET@d>BjAEK{@fJ4Je!5yaeT>MSREPiDaL)YuU_cQ>#%&3&wS*W+TJA00JX!gC?Txhn7igVF0$iva$Y)-ptvm~0 zx%L7{c#U@9D1a5(sAhm`wcA<&uGhvM2(U^!{4{{oS_|KBgBEWCxLsSvj<`#EhmCq% zJA+E=3GJ&=fG4%1NZ$3@=M>eaw7b~WXS7eR0(e$Co^;%(eNECor!6CgZPM=U0C-(H zkl;;i?mB=EwUD`Prtku;52=Q zV*yUrf8d>G>Ia?!us~l*c0Egfgf?=a&aDW{v-Pv?1z4oN8v{5;-^6+@*4MFpSLisNeQCjB7R z>}LJqs{z*NJr@D|MPEerS*v%R32=-4+EDXk16+@^0^3-GYMAM5#u{x#WZoqjAI z{iyyMb;1++msJ2y>K}yx*6T&A=Tmwed+cTXBy!JY{k@X_Ue#rbo!9hFsSG~UHy;h~ zk^U{&{A0a}EcJ>0@o<1o^@BD6e4*#FH~*=J>H)sge;f_)mHsTj*Lqt8z#qCnuAgVD zCrh7ZY}F2My3suq;0)vbbpQ*Dd&dKuWo-R0z(QjQ+2(9x@kW3}M*B2?rN(2|0bF5R zcO<}-#^fA;WyaKp0Io8Yvg58XPGoPcFebeSaINt&DRG@Ky8&ROaUjX_kg+)n;9+C> zRsfF}XHpBSGw$gEc+~ij4|~jbs0iS308bk4ngHvK0+Qe zWrJ}C<#VI4e1CxFjO?`ln~d*X26*0hJO=QBu`PwgPE{yBgTjmI^BkBm8c0(@#T>V2Z}$!C*Uy z{FJ2GVBBJD4Qxa3=@x*E!QmwNbHNQO0X796BrARuT*PO79h|||{wp}}e1LC)dkzKo zHaK<=z<0rC76E)8{F+VqA$Tu^>&IXxJK(3_(W?M{4!*{R{SthMJn?JrRZ{-9VDmWu zzXwOJ2KXa5_DFzvW&vAtn)w2sa=Q8BT7Wam$M*x6Z*E5`b*8!1SbzoQXx8j3^TkSl zMdq87m2=E7e*#!+KEa2bYvvsSaGv?xZUE<-CG4CF%zD=4LURSX<0A8BKJ#Mp{AU3! zF@GS*FEuYd0pK$8Br^2n=I^BE67xOw=2G(~p1i`m&;Ip0XCR_xf0+R z^NGCyo;45Pqc@rtvnkJ+-yH$4$=vTHfalE$-uZ$#ItK8fc_~T$l6k-$056+e3jsEp zH&doxG5??x|J7W|4tUjkZfPJOrg_(|C=&a|N2A>DK2~(-itADCzlxH5z~^&Nj#$7> z7`197%F*YOGWiFsLRs)8^-JL|x1ucSxfx~Y&;cmNyhsWicsXs?*rAW2Jmk-Jp^RL| zZm;;2vKY%%Is0jWcJrA4=V;?di^bY~_XC`(y+w{aPs?F-FVfzh0dTQ4cmcpA+JMIa zF4f*-<1W*7+#TR@Z5pexOv|E0yh>|42jFULt5E>UwfiV9tF-Ti0<6}qWEb9`UBs5% zs8yd1aI>bfRco{wa`Rek?G%7pwD0f~VS(~-BzeV72cfKbXkV1E&t{`Md^VNC_>E-Z z>f8{@n(bRq)-F5B{^f4_kVE&mtqkRUqsSh^^LXZfm8{x`)5=kf+=kMYbIi3UM?GGL za`eFz!`xA|DD!WMqAXas31#6uY;)1;WVzz|PC;4n?S3drH?j3&Zcn0Iqu*x$tku8D z1Gq&WLtS&Le!_VGx9Ojdiyzb1lg&2ie^6ULudm?A7xbNT0bbJIUJdZFo*++c)?Z?` zyrOT|4&bl)+HC<|)t9i6U+L{n?uwY9BvN@+MhH?K73 z*utEd%|~~2Pr=2U&aTe3oVMnv?Ni!2TRLX9woRGY+%luRvn}wy@$8=Cdjin|r!=;; z^mcVm?CL&dN~El|ZdO}os=2c@RoT(pGov2usbpKG)W%}bWU408Go?CKp2GQ~@v|QH z7p>jLrFcO-EQLJ>ohJNGUeRbbAHN;#Rd4i`t2f%M-sr}j?w0>ca&@#%oie?pC8JA9 zN9B*ob6fSl&>?|9sXXzM;6 zr@)34iF$R=($(FTYMEK+V9xgXGbrQUZu>2mb`7}CgiyQ3S%JW`w&vd1-STR@E!EjJ z2ee2X*Vf(B-qnc*aW0Q7 zi`Q4w6{PZNnrF>w@0>0~s!haG$)>vTshXZ+@WWj7R~o<$wz1lJJfJ~6y|O%(Ymx$t7;pGr$B;=SRz&5)e|lZB1}!4b7ln+k@8eUCCJ$rDN9DGU_w!_CMJC| zDz~9(Jb&DapY|ldzxInN$Kg%bL{@$XI{Thq$mge073I~wULH2AwQKg&j<(_Xqw@L1 zhvMAAG5JNg1$hN|Z8>?x)x+_N%Iai6ep9NZtcjg9s$@(_@fh4tSX!K4kXKaFHliT6 zw6Y+7u3d#h5*?ImicgR_l(O=w?lHIb{XJ7^_e`obI#G05G@gjn)rN-@jLIFAJ0ws= z;?|QL1GP!^8%Q`k#U@v@O$#K;Q<1s`T&Sp8)lLxszl!oyN27fGdt3w^P5U<#b8Iyg5_j;h8g>r#o>4wP%#lC zO2(^GwGB0qx|(|Fg8Wipt14luXe5~g2M9g#JYu9>6gq&?`Q;s5EypCuV$<5X1M#N% z+6p#sT6=d-FTNC#8&GUtok;rG4_g-7Y+hNZG=W^L1wml7aIag-Xj3HGn2gqzIsIeT zsGl3`zA1~>q^LL=E9;?+YU+gFr?&Tkmcpi~s*A4UMgJtTuPKUE)uU?~i}9GE0J(?~1I~;_ zs>|Zhif{lX9dD{Yhu4?mrjmetkKNZE#?JPXQd!UOoso`XVx1XO>hBJz2syL_98gzT zUluQ`NkGLZO;rgMRvC{+Vb-ADpq)Sts`Db4z2@#-uyX)R+SUvC2_%xydS1uIWi~^@ zX=$yiNKWm@55y?l@mO7)RL;vCk2j=JiDX4YNKO%|j@3rP?VTNTr_{?uFT|S~>XmZM z4*{Fkg|irL>4HDt+>n=Un85-d4mNF<=YU`-k`{zcPO6Wh zZXI2n(^WCMv!{J}XIm@!jKV}K!RqJb+LVNjr?Lfq=Ye(kr1qX}_$u^fQ*gplZTPlJ zKjt!0HQuq8V)Y@vmC>?f1N2@D4}%axhs2ZI=G@VCcHJ^+giiDf2pR#`Au??4@UZA> z8zB|I&IJ{1$F=u#kxtcYNJVTMd7(%|I#CsY_AGBmRF*YVC&^Bky0GsZB30lcDA~Ho z6#OGTk1Q|53=iq(7~+#K>?<$Nq$89s3Xt{ktU?*Ou)1pwy(2gbN;i^+<4x3@>~Q5a zP}L{u9buLGu-|Jcp*mABh4<8&_D+upJnMuvQ^E^9A1V<|DtaqU@Q4VuAR<(Xkw|!V zMWQiMt&B~62^wr0tjdPkNUAC##kgplSiEboe%3sjSrp~mk(6*3Qx$r9wF0w(GuDUr6&T3<9m|rEyqB4 zP_S!Zf-8mU1>)XP%Xjl@+GR`a9(2-$tp6WxMzGH+;va?Hn%$cSQ<;V&umj{Ru29bx#RNwe78m#w4yZ_zDfNc&f^>KGraIc1dwL;Sz4q{-RSf`G z<2=t*CwpaB8xai0hjN+=1*Z%F`(YfMTzMG=33Tbii6&>#$8e=5mrjOQsqVI8XSenA z;@()NW9|Fe`kq;BZLPQ`*$kJqz6))D+fq~C5FR!Rr8te@1BQorTwa!lhLua@z8oHC z1$$n9&Fg82oc(dWPi`l;#g-SF(d0jRct!x~N;j z!*V=Q@st>hoNyk5khFk#v|p2_IMN*+z*HpTWww78NIE`?YeA|L4gcP=@@{bD%oe4j zbO9TgXZH;R4j~3rr#-jW ze~-K|nQG{1>#k{=+0}h~qzn8tw-;VqMYM@hTIU*NC7*E2^U$Q4d?6jgy;4{arOS#u zwplR|>14HFk)Uwl;#Wi~CzdzZb#qI?ooVIQ2vB_cnuaFrq&^X z;&^+^)Q>XEOBHy-eVA!+`F!KvIG>Ag4<)i8k&474DR>w#$7qb>+vnxk&b=)@`JRGR zzD*y7!Huo(8d}<--Q8W?O6A*u4;7=+Q+uar?KTP-fUQV?mRNyciTbq&dI zK|o%D$N+ry#+tIkcw2{|1$-8W3r*x87~sZLZ^3@eL|%NvOzpGCp&@URoZv!S4AUc!h5;c9qnSne7=Qk}@RPvko% z3gAlM9_MGnhw*ki>X1Xi1-_fA`@Lx>bb;fBH&hQli0??$xDp#4Hl$}}M^8s?$+{YNN@bA=khp3Hgf~E}?Zzm+r7hMu zYj&^QG2k0IH*jB7MpoI%~*-V0%o@NB3wPa$8R0HhtBMAY@ITkGD63P zk8I_jR0CEeX1=usJ|P`Wc~V|Uzt`ali@4dM)88YMyDWCs39K>j1ufxuJ5F%Kv06&s zyXw=qETYJ>u$2)Cg911W2OWdgcyxm3%*@yc?8~@W?OnE`GOo4(4m*Q+)zL=y_wf4y z{TO{O#$<<@rd4x9L|3IA`V&zs`JFqolsMq9oZP0odIV{!$9qRU2Odr{NgBg=g|&ty zNTtR_z#@uMB+yh{7a5PBKr|ZWRT+8P!LROe#jgd-Bw z(P%xp*FA99!XBEC1Kexwfz&8fUzdnAr4n@wh!BaAt%fsH&ln2aXOf%)<@)he<;nk` z|Io#@*84YV(9v1LhRix<#?;<4O$F7Jp{?-9|EQT_&_qgyibBLsY|Ua1b*b>xNEd-O zn|VDJNKAqqjEvth2l#GK^rDxHm<;R*9;}At1sq5FLdw(eBdwA9QVD9%h*uLi=viYShOy5-2CNR9q_ zW^{E+c!z@xziOpJ0yi;It*kjluZi-B(KIi}iEzpY%Ns)D1#}roouLbb9*vC*YZ)GH z2_&Jn6C6m%D5`E&FD9cHTdR+kjjJhxX@O&kfjEXa$=b4-sH@JL7@kcVFSNw*s%_~- zUn>34kQgVU2RFzi@g+M>%V>XfS95E9GeS!}mEB!4J+~XKQM2Rq6ezDp;()e;=9neM zbivPiXtyIKZgzOu%$ii)`MSrAxZjKPl9HaO8*HO{Z)Ob$jbn8{I{ zMI%?s5iO!Qb&c+OWaua(*Pa>8tzC1x@J~#F%XSyo!#Z?5pW{qw)YMflfL|Vsvz=)n z9>$Gu4!!4?;wY#gl|UWvMbpf2RiS70(uRDD{-#nB+-QJUd5J|hK?fB&!xL*T60k#P zFw4SAG8#@|e46XF81ji=m-jZr_LIOo+*b3!vkL&1~+T39) z%{&zkrbK#fr)!kdDY~8g|GI$Zy_Zx|y3QScX7Vq7ifnxHOed^k^07LQcnkhL#$VmEG3vt>qew@pm(ketw8KHN6U zq_QEDQ9BYP6v%MKGtZGMnH~}5D;-x(tlAbFC*N(hp0)$&@G@L|jDSXo6VE8|D+*wrtyliJ@KN<Y$>C7bi#wf1(R<4yRBpCUsScVF3FdQK>5w_#tIn6Lq4A9z>!O$A$6AZ@eP!u^v zxR^pypoAtlIaL*#Eb(#N%L^smz>{_}!j~n-3%7{m_(#`i7o{Im6r&Ii#FUFYgoHb? zr6Ht!Nq!2ddt+ocu90XWL5D^K;p)*e&Uuy9mc^CFgy@8ic_c=jK!D8|wu^djN7v6`QjWARYesE5X71*YAlO`Ea3oUGcSFL zjeep;uOjs^JNCw(Vkkp3<0K*!+oWT=V;E(X<0tueS3Fu)F-frmjGsrFzV`@iZ1yUM z9tTg8QDR4#*qS*lib~h1AJ?Ch#bk!({%5)+m37t5TwP_NE^6yCahDuTjGlKLYFt-p zLm3Mx=o538VsH0`&F&UTjm4J8@ksf$<$~S{@&b$Q*wzjMuRIgT3H$`xD zID4$L9(gS(c^_m2XBw8G2iL?OXmv>E<=^Cu${UlPJ0`z$Oi@v8NoihwQCm(4qL%>- zD8rGwys%_QNm^T8eqKR%Sa%!a^=-q$M*#9k%|SxkSQw{Pp1_UMW*t|U(=#ilHLnZ`$PqCPI{@w&{+GKQcvg44t zroP{yHJE}Q6;D?`Q;+X$Yw4P8kKJU#%N{Bxq7zb)L^51tcPzUQA^J2INX_-Z1u91r zx4IglQQ)g@DqJwCFgL$6zo4+VxS+HszqGU%sWYXL14L6%>hUM^ehhg=$YV-I@fggJ za%vE{W0;6a^>R+gmjASjskCVnXWG!Nf|I~wQ!STn2HshmuEHEH^bOC*^5XK@Ol!}P zke&HxaYE>=_4RP5pVd!&-XecDMhvN)^;FP3hp`!0MA0uvcRsvW#jn&PS8t-XYu2o` zRb914>|2U+ zIckzQyw5&!@gHerGS!pr6oU@%q}{Xx$5dmI&`E8{2==NgQVUx<6?su_&iRsZFn)0E zQ9YZCbb~mRpXOi*`#9DmVjCA$AjW((K4M(FOad+>JtmgD0kIf)WD`Zp8<2dIree2z zm(*FLhVwhgh(FjN0VMRGO$hX$8XU)>kyKI97#SK@N1G%l(twFbk6=!u#tt$&qATuZ zOHc1yHOvz~0He=Tk`_d$;&){7g*$A9rCWyyUT-FzMzB;(tTSp4TP~0Dh{r&^U829%a^qo$aC`s{VXP*j*^IMxUAGE`UW?A*rm zXXG9uzfj!e;a&qd`BXl;$D1xKu_eJZmEIj91g-!(GeV^@mF zysjxlcan3b2)H^O<^`Rx1l1j`s;Ol)l~PirCQ<;02b9Z-8=Zi&FRm;~lp_dL1^W3a zolEs_v6qeDsd)azwq^o9PW%vT&QQAc!Rd|g(oR1<;O!x$$ zbTGefz!1$TuIQuUJ^NMyv*G3oBmZp@95~kAwFgQ|p|bp=G4#JQ*<^G;IW_P!=rDpYZJ91_Z#biuA6Os_^Xq$2G%Joit*fVnO09rjK9}Bvm09YgGP#O0}=4SMH2zi)#^F8>g~RUDC)*68i)Tinx}j ztfd757|Jgy%cgQ=gq=ZJ%KMZ}_pM6sO{yg&9LV551SuIu8cta?`io5#F=fB{CK}vx zVoB_o2B=Ga$M!oCbO`NaKntb8?{>J@P1bcaX{k?>x@qHHV2HjCy?J-o3~P%F5t=HP zA_(>*df2W*>jo+Mxj`hD*47Dn&=C}qU}t_pika(99sn%@PWq=E;6y&<5avIr&^@bV z`(!rDxY0rtC5#6W{Uqh!^&H^jd!CmlQAmv6T@p#-V;ydE68#;nlu1}O@mQ$}EK9(d zxDp;2;WL-U;Z;X?9L>f_Atws%3vDza5g!w0;9Ezdx)~&He8YE-kkk!*N${ArrBB7W zonu?D{_k-0DAc5+?mEi7$9MmVNTCH@ef;8U4cVq}N5)1tYubcy*Dc2K}eJk9s=b?xjw@tR%D zNHd`3bkcJmc!O^_4Rt{J4UP(Myi(?1sF^u(U0HP$jw9|tJVpF6d8@cHa7!3Xkf9R= z*dNQa{Vs^BFO1>SGtMF}S0!PpSG1PADxZ0+4gb}|1J}IuU2LF&9q9^Ng+D1M$PIUs z*$}03#2?U+esKbPwh$8;=|U$Sb7c*tt>Bw7lb{^&C>SH9A$)GB|C%e#D#01iMqg&7 z8ohx;uxzc!LO|#!!uS@##hzNVEgLEgi{%f`ig#cu36CYf5fbe8X2Ua;C!X!j^K*PO zX4IJf^cOA8D=e(2#y~SY!LhPFVlNJIby`0+2o0$1%3^VN4%C|n8r$lXY~~ulJdfe+ z&;dOm;SaIwWVr&*N#-*py+;K}8Wq!Gs@)|G798>gr2))b*P(mN=?_r_jPT*!FV@LJr_Ff+*_pYAkyH}QfC@gX+{WLW?a(0 zWW`>$g4KZ0WJL^a6WB?ultjWxvbN4)8jS4hab4yO@@i)KBF4=`?;J#admLA1cmdOoO2=75sx`1Hbuw?SC_O=*(87Q4MQ; z{T#0X{CHnj%m?I!Yevww$Q{ShF1*c|%C>Dbv}l@`I{9}FHT<-7W!bq&+J)qDq#t+p za+#1_85!-@Lq5F(6ScIG3db?AMO@#T8MsX#Amhwn`KkKv?o-sQs?SfACaciBeMAxJ z)FYCsMWom4(IfNu)h!&!B`WOcGbhyO#O+G#->AmG)3C>ecBi@iE~gTlnHoFG&!(qC z&Wx+l1pg|Qbk*y%-j`398?C6cqnQ}<`4aXrbCuEJKDl~cYToRgW`Aa$KYtiMl#Dz( z>rQfm-Av&;$plVuVo-AM(6exe;#_)!LykBLys-?#$%pE4?+tU~6 zDq(z7*=Lb$R24%8X75jE;1(IR5LRZ?lG!97&L8lP(0S#<(lgGOuZWu1;SXQ-O0+gD z1cI=D%XL^m44=$NVc@U1@C(};MCAptY@&R8eP7k(U6ID8@u>>W`~2vPtMUuwA~Kf< z2D+{?hE>cZNW(%>MMek~O-&2eCB{c5s&=Yb50ZzAdi`=*00Zs#-T~nl7(f4#WnYiW zbWuh5xU~Lo{Ao}7IXwYBrtv0YKq=rw92kSy{G-fB9hwy3%1q(!bW1K4qdvxIJ!Di6 zWXOEq8-!r&aHi5=b!jRW5g6MU@|lzLtMVhTp-&PfAArtDhrmDzFJ?43}$s+){c>_?RW^*IoE)v zYZBNZrcv!j0t3mYEmfJ4_6%MSUr>eQ6Ak4Y(6KvYNQZbK{~QhCdcufJ{QEVU-VMSE zva+ndSy&{;t65k#Wrhp#Wl1pz2C}7lKa#`DxeG@^J@!>2vmy>~Y}xSn1u|)3d%$T6 zTGaT{o$009fK_JPzQ)$rHj}gE{oN(4qXrd;=AsoWN2!4^#RaB&O1>}(%IE-jlCkN4493sDAoIEN8&Dgqt0kwY-E;hO_f3%a2(Q*9;w4T_8+LZWvI;zcOwLep z`a*R|bg?(ZR+HfVHR9#qUOx}vkqjl2dO0|xmkOvQlCBej{1N{3=LUmC{tGwQzDsC` zcjA@twwAW`b%7kzFL$dt%sUXy1ZlKQ%n8jnX%YBarWzRIo8!72mWJ z*LsQM_!B;5ODg5NfH&yLS$S4wa&p=YHY1=(bQ#rlA}T|ddYYWz&H5Fpv^js? z4cVSP3vQN7KRm?WdyZ;S8WfYWql)5E_*S=JWSgv`J`~|X#7LN2sFAd%H6+#{vwd<= zWr&tJV+72&$e*~tlD3D%Er=x`2Mycx$iUZ6LW!UF$)}ivi5k*j*b~R@0eiKQuX!N7 zzj-#pm88W9$2DQQAP^GU7uCVuH$XXIcO82x9Z!VSA`jA!3svki5xlCQ$~E$0Wz{UJ zvOoZQejmA{N2 zS&`qjfNSfHTd=ho6G#N`0cmP6uf#VxqzCUQz)XdeeicvR$Tz|L-MIG%_kjYhctcr# zvb+CLTewA@hYnQQ#oe(EXZ$0G9y;oFH<$Xdy1duQ*x0v328nCV0yf)kXdu&iS^Qe_(BGpOn6!3)YEqNh+k&$|kue#h315s*VStUQr4nt7Q~lv7zTv3v^yI_HuD<+qLjhT4V&wvzLZxr|1`zy=LX+J0 z4x8_sd87;{tGIwu$SJkC4Y$(5Qlex6F$vPiU1jPX;9=rn`Y7RKqez-%TFl$t>8S7c zD2(l}Y|bt8Y@O}v*>m7q$WlgJ)A7mu(Ibu+m~@3TuF3NMH)~wmr>Qlm;jv@Gx!m80 z%k*W*YwuLwlGpwMYrbGw`XYQTvTy6?Y1`t{MuwYvy8quTpjB=jq|8oi6K;V)QE~Om ztHLQ1OfQ=?QloOka$T1*?Qzx^|e9$&K}y~-Tn`EM;?t{tE)H; z8>EbC0ZHJI#6L(e=dYVt0$lal^ zI+6wh(Hc~uZDz~ywQX~pt!>;i*;JT8tNwDG?F`892;~|`09m%Z5Fx}?Q1trz6{0z1 zh5Fe82hE~}lV|uxDh2onYnPTb%Yl!q?5sjJ!X;-Ii9PO3??cDggX+G&hH~OsY!PcG z(wUe&RpOjVs6_!IC?Io5sf<-WNUU*v2R4xV_JHz^kYm<)GMwfV)F_l1MhQw6s-cB2 zFj)@Svm^%o*c4H@j=gqGuy0>u5P(Y2w|k?L`BPs}kG@qq8ixyz5`gD1<_h`q$Hvm8 z%3w0xtza6kd<_EyZ@xCdx@9;;NI+Jr*T{<)k!1|VFeFVicXu}*FF%uQ39-|FFadp5 zpHJeik{h%0+#}>5#jxv^GXWzDrTxj3a9qSch1%j0UsolPj)+vS-AqrET^~Kfu7V`y zIQ}3S*-t88qC9OwTQ#~7E{;t^Fi0&>#Rjvsv*n+vuq`0Qg>Ej1Z$1uv+&3&)pF<0V zuEhej>E+mFt6`QftB1;?JX98(d#G@lKOYDED%A2~sh&_Ee?nveo6_`AluB&;cQ{%P zF%F4h^}kC3Hnd2HAlgcVeWMZ}WQ%FV=L|InpG)v|4)%zJ^UXOA3A*`b&1_ZNXW_5^ z9#t`Kkd(1TN%agCZqc2e9F5nZpDAJfo~o{hV~r70lvr(tD;(*Aw~QX4YWKTEzLASF zWr=tRwimbk4ZOn+d^+J^*}zeSPH0OVR{)2qj$}{9?coJDld(3+!3t+U>}nU}b6afo zg4#;M7F`U3%bFO45Q*>{L$24(AiQjn5y$R`UESCbwyRTiFk>ra!bn^NY~LK|nmH3+ z8gR5Ce4(^Wq3q7dOP>MCyi2-Au?5|oQVhyla~`YFQ!aNC%(PeFbX93A zMOGUT*#kPHNxHlF_dhS?+qGTtnEUKdk45n?HyQJIHIW7{K}D*TKD|i+ki9Y}Wkv43 zbTFET($`=aJ*GpWNj$jUpe=rr?%k#>@68(@hK+KB%OAs4%bThh3{fK>275_lNpnV; zo{t$A>?oVv+l3`5=yxP|vFn`Z4Q9J+mL|8MgZ%CaL%?!XX3Zt(lg$Mu+MVwkSNopH z30ylMg!a{x)%VTP$Fv>RD^{0tVFeZ(f;^rk!2a@4kkkpXsr3m;#>kG66QN>8TX5wn zB}m}v!%}yKL;|F;}j_69tz6W|4d83x81al+Pt zE+RXXuxBJzTa9cq-&2(zg1C+=_KIbq;Ih)ZKg_l z!)6YcinW`hOfz@3=Kw5yhjXwIGnL&*WLChLL-y?ov5=Z7`%)rrKZ^yiL&AeDtaO551wZ$(|nDN zV~f3F_&Z+(ZRO)k3{Zi2!AuX6K&Hr{B>cFWVo==N5fU|*DBysaZy90Fd~i67DVj95 znVJs2EEhdj`{I+>uktyWEnT8&ne~SMlc=Dy+a`fsJ%@g@v}K!rR=`Crf3M^ z%w!CEvvXVQW7sXtri(pTVpY|qP#mlgBe8v(x7s0|7_B@i!41I^hzkj;`?8?D9ax01 z-N2hW{P%7U?uLf2o9$UlnF^P7`|}7hMn*zKOxP)EiYx7NfDp`u;b*}$uuh_A#w%p^ zMvTwOydk`#XxM4Y8F!;Xj2g?}{lCc@ryT*I*b!cejx1_&@+c%=<8CDB?jwoyk7}T4 zPtUr2>E?*wIt_*}Dl;j#oxiwuzTbhz`wR)w1fPWSC*s@uK!1&_D?xn*5S8@N*>D1N z`CACodH#m|sT8%(c%GdH?u;5_=%u1*Md|(qtE4QGz0H(x7c4w3pesohW=qC0T=?U-+0Klv z&zz*)Bhr8u%3L&sk}~M+dBxb#Y*}d7r$$&vPj{L_lHh*IIgc1vW-H`82J&Kk?`O8SwrS&UHgQBcZQQmPVP zsB--|9nfPQ#oatg=H{!wn*9JgyMO=9m$2qdON;XHB~r+QjCWZY&5A&&_<|ZXri>`Y zljYo?ob^xNNUFf)0VH?X5rNEnRWGt->%o4<-rikOBPvNZO9v@PDwD^pfVVndzP~^! z+oK$8R_l(;$j^Rv5~iahe>X?vApgd8N=X6 z=*=BOsR!62Q#JL+b|_hPLK)nfm}luJsRS2fM3OGrw;x;nRBejRi;pWCUv%USz za;w0pv!4|{iQ-fn6FlW9wZz|{hBJGt{90M|I^GvQfXJ86o|ZU4sE*9I5>LF<*VNn_ z6dhP^Zp-3#q)NQ>9M@1eEi9s7 z-Ae4(KdpT_dRiWbs$?WTr1d9<34L#orufvSJsFNce%#r=Z3`|tmtx3GiW)S_aFKjg zne6R22|kiz7esWLN@BqserZ>nAj4GVe32aB1FizKnZ%BUI0=wkRi#pHzrsB8tVkp#`p)7_WDd) zJ=v6V-8BFDP5L9Yc)ANf$2bX{_E6u?{yY`C=5&)C`{sz0|2FA!)rZQ46gf+`5MpEPSPwe^(9!Ju?01N}e8w&!pQz!y zj&e7g7mJF*zQ8IRBy5rI%;os@9aZ^@zSuvFcLK|duw@;hDJsC9t9Bg=ARQ@=iI2Se znySf8$d99kD&$KcE5l9ZmdrEZSG9>%iZ++K2d3SF&1d;CXLhE>%|j=leOuPn*1@yH zhMo5Q$zsa_OU$c*|+hOkQ>E_&jH_N46@HF}t@W)W@B6 zNMwuL>xE3ny^)&CoML1OOO^?@r*Rh?+iI+zuZB4}BQl+&KBkEH4fPZQaK4oXE;$r2 z`nyFK(p9;AoOA|nz-&%T49mBr!`Kz$;L|xUz2)pu=ZXX6JL!xX>o$^tqbSDFmL#!tep^!nkk_zk^L^Wv77O2=q z+H{XJ!d5*DexzNL`hyb6k9WgT%Kqa0{`u@qd<~|*d2XI}Cc7!;X*)uvZ`84cYihy{ zs)Bn6aTy?~L5uHvAH_ELScWX$Fv1mRTzA4jM(N7GO%H69RYbV0i#Olm=xgSI>gOlp^#+pd}X)tG4(CacFgHPo9i8HjIiFC(o zUPw9Plp9#K_gHdN1-Q_cj#=pWoGM{TWlK5vvYf7Sj=gxC+M7XbIuwgW9S4hwi{JZ` zZnNWX9COMjNzSU|BRhA(*)>T%OPTQj#U3vDm5z63*c~}h;SlaA#SeAhORsA2dkmZ^ zIv2q*e%Fl0l8zyfwc+t5r>B`~sT4r*mQo+nIV;WG zOv{gSmKND;?}aQ7yHcMic9R}JXJ^3Rm;yKF8IHC3GGF*ae9X$->u|&w6igx%emxTiF&GGsS|c^vWuu2)z^mEeCCI$=?|aO zVxW-rrEtdxxU)C(L#gCd0NYLcaZs^uMd|hp@s_g5EB#wsUaDgqx}0-KPh9G}#I z>|cp+I)rq-Mb7Tdw3^fg4#(yy0rb8np2o2Oi?g8wpdcWfHNnqaSJZRyJ!+PSBaEGokc@WxhjFFwyomC#?rk6~Wk*}XgDyLe<7*=)3hogl9(|QC^FJEUNIOWGAtm>-W60jz_MO>x+sYI8x!CWbi&!mY0#p(?1Vn-X&as%F0;Oondk-o7T&D zY2BPBYmwYLWr*xzY2BMAJ2oL-!q(>eg1R>t;Z812ciVaDRDFHJy=thQKAOdNzoKng zGZLF%wDE}>-;55Y2V_yX6D#*(kTMTjBD0?U357^}Qhl$sBWFDh$VITa~$^MCA?sALoH1jhHUZZ78DL4GrZ@bfP zk)}JJ)pRCG>m{#_YBf?7MN$$w8F3i(^{)hXB5*t2{ZNj)E6szpS;M`<&%;G(3mDhJ zAQBE)*^5YdJ{?Ht z2Y!2*?ZKR-Ur%8GD^kc|Bx=NOzA3&@!yMQamxx?A=llFjKJA;m3z!pH;TQcRU!D0` zZbG$tj31vIDgMxVD88K>tEi5S?0W`bg$B?B z-<-v+?!&_)!}R{ucTD3^q!J99*?jcKneCm}7z?oyxsc*VYV(SRhew3%Gnm1WJ<<-r z7kl}G;ocp?_*?7_js??P`3S{033I*mD!10%;0ep1IgXwrE(2+q;X_BshAM^E_u*}{ z20>DL{ABM}h(1F49vO4HH;Vz{}vX$##* zT4=?xi0mRF0wMwhWCuY30TGd11O)^{RAdtn1=&PI6#nO&`OUi}sr=RNdHlZTyHC^K zo%hb2JMX-+oH=vmjI*v%JC16A8NKW02VT!hR)5h%$dt}DWJT+Jp)NG$HZxh&OSG*0 zi0rltB~Ou%d7^ME0DnOPMzWvK44WSonTv{nq^7GXTb->izOc z{tVT4{a8&j%SqIa%beB5J5?Te<%G-y^>8|~`7kF@QVrDLBWj_({}!_VJ=D$Fc?!V60<6n zwxP#7+Rhl)qsFABroI)6CM-CdV=t_K(pnd@h_LC8JWw^PbDqq!o~YHW8*ZZhVi5Cw zEvm3Tl#a(7t)~TeDTZihXHg+qu#*DL_Zu2z)S5khma|IAiY8V@S8KJ5v~jb19go#r zF*fV*3X}TCDv8UkNe0f}rQWerlUOeqshOm9=%P*kjgoRpkD*?r~jpr7Gr`XSl^ zMZZ{hg3PwH!OfV_%Dy`7&c>YMZy6FGKHH^#Jt&DYGZ zMOdQ-pcaZkx{x9zVv034bG05&D~9<3*XQ7OklV?$;h>1MmnjE(;K&0U|RRU{m9Y|uPI;6*kq)Z*1Ytk{h-CGK1t8`mx6EdKC#{bR}{!cvL zXdNK712f(f2aG_i_dDJ?Ylr`fM-Hl24SAk!h@tt0U6ZQY)q$_~%_R%5F%!R7#+qAA zr@h*t)^EcjlHGw;G+R-Vi(%iVvu)WC=6h1rqz!ryl5U4vm0<7OvYeN05%DmRvVz|e_nTRDld+8i9+|uGlV)F^2{<-Q4a%P7d+99!8TRK`M z&WS3#_G|fczos2tt;`FQqv_#tTu`sLI=!Eq7ln|-@!jF*Q5s#6+I#O>nVE!v>#AyW++L?FUVeQm4Cy-FmfC-9TrwXrnYq_ z=|8k|u@81WF7*a=t;#w*)vmPb)@D7sT%>4R3l#FEDT)`V_`lRMIZ+-Vv zh?{x1pZkQ9kpZLFJ<21}XM*leR&Tpy=d!uuXE87)BDc*rNQ4h56RWDCs%dSKWq`J3 zHRN$;1E{je4rG>_&L#_A#vH9n+CNEAqLoVMqGB@^Hs3`DUdLxW6K05ncAS5WXwQVYnR2~@>l?)8QXhQUeoPY#xU}O#6Y-d=9JF%wiea+xn4{kzb+Le@@P99^!V6Fl9bzZTe-5y ztz2o9t{I#qZ)RYNG_%J|$gASJHCCu<5+Cm>MdQ!L4AamvtcmTD6lPKh6mAg>R3RWU zTbns)+OBg5Re4g76Q|0~AEr{Vph}K9cUH$VGdolk)Fp6hI;umGWMxH2e6yy_`$d+x7)DImJ)rE+U@Eb*Y-7PG?}{(7mtJ56W9nKTFBVKjjS)nx+SyA zjVm$f0tSgfgT()n7=oq`v5qRHx95tcOez$*!HfxXXrg0#Z6=0J!pxVrTN{;vwFy+V zR4gG-ITBjb|>RnAW`D+-aTt*#^-7OTO$X+cFbnAJ+< zMoU%j%9eYYpJX}oyRMHw#UcHfxOz?;w1gdL)(*TsKx}g5pSs+lQ_4l|OI>3Uhm7I_ zrfsIAHLGpvq^Wr5l8#)yD&kh>q}HZM@_l`Z2Z+BX^=A=nVl?xhF*5g#ypz$HP8Z!~ z?5QzYhi6s{uz58e#p=APx3b)>p5$D`U~joB@aYk4bf^Bk_NDqA)5YVh!0MS!XZ*R7 z;f6yMx8oaRtUD70X|(Yz{;A7QKj}j!1o9-3{{Q>mb{Nf)(M=3`0#v8CwP~N-X2WOH zhC2>W*CBprDa9n{>Eb-ciO}SgenaoXEzL(U?1!|HNZ%h@Z6YM)p(7q0Dd#B21CyND zRz(>=d_7D!-lui4P#x=7toe$QYpbnl0Z!5r+h>W3Ua5c$Hbh$Ifo9EHsGD7Jt1J-@ zw3;-r(N>eB@*ZiM|HMEf>|jETiavA1pc$&JjY}9(VXRXQMJqFRkG8>jgBW^8cbKeI z8XbOTMNSlx7DCO;6ZEl}5Gz}onrDb(O)CJ^MafEP%>IBz!I7zEN}}d@(wt(ZBdk|NPHrdwZ!jRWG{DxR@HBU$dEf^>~BKAei{81a=~-Zsl@l;X$U*+P)~gveL%F)W`@i1)H?zM`*VQU+?L`WStg*$0!A)oAWnyQnv)ef^t1@>wHu?xL4x-;o8W_pl zg|^Re&ow%Ik}lr5*sz6Y9qW*tCg~>|pYYqq_E6O+r%1Qvo71m|Mn{T_HkCtCx$Qz) zc=8P8tNJAUH}!qEj+%9KIh>UAhR40jFY8kqq;$=_>l~ZD(?0Z!iP4rAd zoYxpcq|wf9wQ^OmowNn_C+MgTJAZJF3X+p$kctnBZrkoU9uj0Qw*9Nx z!z7h$(i?>fg3k- zRLrGcr}eL~%~!5_m9N_?CXIxv<62{LZUUs^r&K%1Zftc@?0Te<^)p7oouF?5p-kb0 z*2D)^v7Gp!iFG@xSlba`smCvV z6(iAKuISV)A8T21sb4w7(vW9q`pE%=DeLUDq(zw%8&^YLG^>;OlacH$Vo5L~h)d7j zt}LIMqk4{1#Z}2#YUG60>ElhRR?$T!eSV{D{L!-`SxhH&enG7W4-s*l)Bz<)MeP;T zG9f(gMxT_)d?Kia=OV=fp7>{WN46yAmjiV6sa4usEpZ4SRaYCTxF<0Y(s{ygjXPR3 z_e%uMm^@}0St|~l!^USuU8_HhDjp@QJAHo7ueKjEUJWP8P9xAP3V^)KjHRx4>pMM8 z%uK?f6-9Y0W?dIkSZH@5-Nb0uOK9_%v0U7Zh$mB*>%_@`T9w3S-%L3uV3f5qEPnKT zI7)>Xu;cXDndUR4I{|El7zwC)5S6Zvh>2jjL79LW``pSyAM${%c14$9livP*@4`t> zhglPgD{j;5&6p$BHEJH}%qry2;-;pe{z*lcS3a`ZsVRAPIx5NFZ_24)y?vstOi@jA zZPyO_K{e1keRiv^p{V~f+=FW}rO0zBo?FE)G@5`eabUb`N%M@@Sl)lNz1D57Sln%W zS;zd(Rmp($;xPk_ur~=Mu&DIhnv|Z9r;k;9LJwF=?KAVwpxsg-^3RYkD{bCilqhn7 zn9N0Nz|bW|+gc+kPq!TBcOm(9!l(8`P0AK2$T?|=_f&pKX!asoFL5SHq9Ky)64u8^ zp*4?{vu^Torn&Smvvfa znyDIcEsnhG{-4k`Q!0rYrITweGNE(zBN~8XYnNh|q?3>-zUMDFD;<&lXSPqCEJx<3 z9T>ZQe4K2*(V-!F43hI`&Z)zpQz*%^YAu^1TwPeUy*KXpEz&ik@y_TE6UYheZ5^{( zom*tnk*!Y2C^x5FhPTIH4Z`_QQ9(p%oVAo_7pE%?_YIv=#I_3bZ>fFNrAx(ouVq-% z$wf^?QVwSa>YGu{^jdsmRVGIRJnl#X8She78_{Z_O{l$Db7G^jRtMQPq6YH=X+tLE zO&j9AuV*aC=~r4;&=`)Fp-)fy(MxeL-8XHoQ&MR+W}NDe(M+gILz`W{Fr$Wp;!9th z*UGwgvt(5N+);%nd;GG7TUhqBT_|!_LhN!oyqp9QwvMo4h{=w=Sx18X0Mex>{i3Fr zQX)zpEKk%g;AJzRp9K}eRJ)<_+WbY;ZmH0ACD5HfZPU%xQ_o5W{qw8JShoJiYL|7I zZfp>X_sKKbMYo_u&hfCeuT z#H@qm21Hddu;p*oPA6ifVC~NNh?F_P*vy>lbfGQvPS^dYz00-Tt7|}gf>?IwgTSOu zlz;Y#nVp#I=Rai6pc9w+3ujg#%&^k?VoZHec0<`FLU$0o-cPG+j|sJCrh^ulKnE8; zbJh3A1p3x3&qW$kt3NT(Ed99@uPnd$o<>y;(bOjFOJegI6GyZMk5=mJCr}y>@Ui`Z z*$iuSkj-o{ImvCe9Y9Rdd7WuJtOHDl0AbIU(0+z%t6Ei zBJRGjId!KN>S3d$itwa&l`&eUi(1v{H9pD1#l}$5F@x@yjyD>2wJ4$nV1<;>t-G;1 z8OzE_lW@xH&|rjb_tSQV5$ub4e6n9gDcA_-*YElb20DZ!HL@Z=nr?b#xE@w7de_dF zSC5_r<-U1tM6~Mf-5hadv&=H1ky=lTMRF+AH5M}U#ri_ALC*Uq)E5h~ik2&=8KUkO zwB9LgcMxvLiq`_^tm5~PuzeXXJ}lZ0&TJB)e$MsLi7{5x>hv5%ElSspwXsT;MZp~! zSBRJxh9rNnj??#>(viz{HFu|yq5l1td`G+WtTWPz1m)PEosGl_E3wY_VaH}Hkm}9j zzV=i$(@HZn?p(v_2eqT$hgLTvTYhdJek_*sF<9DVm&J|ajdSk$ibORgo}Y$mCLu|KPjt{Zp0IJ`l3U2CaYRw(~U`VIiZ1t zDRT5_iBl#KThL;& zEw8@OIuNhE(I6I&VRblq$`j)gmiV^^iDF-mv<}YqY@{jD5>gF`b}!NNEZU(fbvu@@ z30NI&6jT-)X6i&vyeahCna3? z&v>fdXzE=|xIcOABdLCAoCDXiLLaN45!}TCP#4-2Nb4T+uR@ zVJF$e>rfeP_DSpv6-ms-E4823-c1ycvW?n}>-FR;+*}pcUdB`@I_OA;pyHz*Hrd%( z?pqkIz`pUQ0jRHqtQ^Fuc|4Xc>9EmjA7)DLXwL1om`X>kKkOBJrRG-Cxk$w23p6Tgcu}jRDSDe@@>}RWa1cRGwz@hgCiSCH$1zpJ zZ!PXny%p26xL9^4>c%!!{5s2W%epq>G0R3j-iH%$x9LPZ1gN^hAB#t&rcNVICt~o7 zWPeA~|FQiYx|T1`LbgSGqMaV;=$~lMNBRG%Js(j$6z3^sTda?tb*ZF+Bx8e{IqsKT z`>1zRvbV#c!+Mf6LmVeI>5R?kF2dHJc8%C6>JD}@4-1EhME5@Ev5|JDlrA3HkEk-B zxowKmFgYhbp|VUhfI4MD7c@y6CObXQ(ommZV}UAFBPmNe09C8X5`4#$CK1Sxo=mU6 zd?%E>brPXsmG-@KeX*eSduFU;Hg>Y`9@E&wI#xeg#phPxDt-7jsz(^^>iXqBX>T4)96q~ z(xS)ZSv3(e#ExZsOT<2^+TDSF4?j5jQ6x69A)&d&S+Vc4?tHuvuz z$Fio9v-zQ#*gSsLWa$zUH`f1C`%>(FL$#YNSIVcgYP6f21nE^%>_?WL6UAqbR6A*# zfzzX!1}WTLtjadCxQO=Hm;qYT#ECN^$8(W-Gc;+4#j>2zT%}IO2B&OYA(PEDHWca$ zqEl$dma^5cg`%41>iwovlva|s^&jA4R~~Y|wqain-LQUyQ#_-6x#nV==V*e0oaHGZ zny5@obYo&{Tc=Gjk(I6Cwwq9G=|WY5Y2A~C!&*Toa9NVoGq2pQOh6prGhN@6x*Iua z6lJnb`qhA5n4VCjJ__$LG;2)wtZ{Cz#7+9V#l1_dR*LEF^eG+E)Uxqe3>I|B${CyG zL>6|YS9MljxwO@n8FWZ}G1n^M)LmLmRi--CBLg#I)Xr3Oce7?r>Xbe~m+rcj^{ucI zNWFR?=KeN%rfOLzJ9wOcR>W=YRJ1dFs7ks2MEKUHkZeVvj#}0&m`e>3$(Mo+y#6p_ zw^ll_*$siH{ru#?R3asJAyq)Q{m+Tk2Lv>(^%svZ^+;&x26 z75~g~>x9ow(kpn~Xwl}vG0BrH_3<_>yY@ALs+C)k-u`vGiZo@(We%D{%z`>xp^fQ+ zE!)0X#wN3BJ`!8@OX)jNAo_7l3^f+_E-WwAAyf7N$Q*xan;c5++|FrLu^G79B}G%T zSvoTd=Wvl$z2q0xwQF$-JeiBz)6;U8GQGgeEgv{n(r(t}-)jeN)mJ*8=zMd1_O_}k zKRD5uP*Ou|WmYB{1^We+@_knwZ@2n=8C|7GsycOI^~m{si+d&iQVwoIklbK=@rsd3 zJ3;9(V$V_^Shz66tTjB2VER}&u}s_*`|@Ho=?iak5Xd^=9<`&S2G`D9ym&!hZO`J~ z+NR!xwap8=s@)=R)QUf>O0`ciCqv^{SzKrsdqiQZxQJTZJG%B?bTJS#H3UIWu9myz z2Q_u_c1`JrmR6UKZ7l?A4O_c)-689(wdoq4s@c3|%b{D0TMKCOJWs5{;Xs}f(yiF>+Z7RHdDm)<-o|p>n zm0Q{j9nTug;asc>T|yk{yrE*0J< z6>bVPPF$%8lD{w{s3txi8eEhJuMs?+2(KBe7q2kETESk4@Y=zmM0lOx;zW4e;ORto zy!!l%rNZl{!W*Q*$<{eE*f90^MyYVJ z_6!X+NqxR)a5K03ynM1ruto5Ig!QiXl3Uv(c<19sV@0B={U#OuLn^F2dizA(El^hp zcJ2<2T3D!)UBo@*e7V?N>ZxRVx(fNmYGZx2Qf@4Fhq12 zp00eRC)?eX?I~3&4eqzZh(cY#b}kj2t$s0EtjiTj)ncVvMucjmoG%n|m9Cy*Aydd^ z8Y+dxe9?VThO@q9OY|F=x=N**EA>>n8ww4DN~WQl&-WB_xlF!L$!EHAU3{Z&X}5fd zZ{!MEa6S31O16}#udmN_brp+^`Ep~XRF(Bs`;G7mxqMxBF`p@v%JmIBg>pkNTPpQ5 zWV#BuTz4^7YA9CSgdJ+h$Nl`B^p3ylrA z#!SA{)#D1TB8zmL6?vXgaJjnfhK5XiuF@?Jvd~y8uxCaBR;p`5PbnjhzB}7kmd9Gk$q!aC<$~q0dHPWcF|N@XA-7hj z_H;?DD|O||VoO)7<|>&U`K?N!tGlPZyW~p5Rr30JiCxWCd!*XP(s@^7zM-L9=xXdK zRe z_a3SFs;}#j+Mg{*Tg%B~X{cm#`C_@DUVf-rpU-ynlvQp^xud8oW|xHbc&ASHL;qRk zb3Y83%l%-9^bJEM2fJJO_1z)$rc11?~?!VGmpgkA}y=v*07}MfeUJB14D%&ZbahG0O)W z4?EyOxDuWLFM_whAHy|eDAM#cha+JTHp5x42ObAk!5iU^;N$Qus6(9o&L%Je_l48p zp>PR24xRikZ5uOKcg7?9v;4AQbxUN)GO@Ab;hjZXz@G5va{0aOud;^XV5kb@23%0_~!X@xR z_-%L>da2-iY)7u(;8tw^O;304kJQjWhUIM=h z?}bmom*HRF+9Hza?`{Q0!#&|_I1jFXr@;&0b?{F3Gx!{Q3)YCpr@uD>7GN`+4NrvE zz!G_l5_+3cLc|4}Sw+gEb;7YI+;OU0@zggLB{#xDuWNFNNQS z55ni*>+l1(mJB5NyX~+Ko(F#bpM)>KoJ=M3d;7p6;4$!Acp1C{{usUrYh=o;>1+W< z!UEh69tc;$FTo4oHE?~IvTJ(Vz#ZWjSb`H^J3JW9g?;c?csg7KuZQ1<55gzmJMbg8 zz6{iwudU!nn1lPk7I+}+fqn2exC&keWh!FnZwzZ;7VZt(;Ai0?cnth9ya;|9-UT0l z&%jsUyRc?UmyZqMws15&93BNvglEG`;0^Fj_%M71z6#%i2a2ji%eMzEg z-~;eU_#%7@egroV0n6$Y90lv)L^uN;3O@%=hUdV`;CJBt@aOOa_$K@ZTwhd3nvbpF zuCNFv!2Mw-TnLYbr^55#XP02hN2@!V}@w;AQZ;@NW1Rd=CBz{sV5Xv&+Y}@YApnPJy#w4_pSn z2+xL>!tcNz!AIe5;T!PpaQ%@kAKSpuumMhn2f!*^3QvGvg_pn^;a%`&@LBje{1C3U zi_6E>a1<=TNpKeIhJEl0@GQ6r-T;3He+qvC{|NsE*WK0SV=K5TtcT5TCal0-cs%?H zycm8P-U%OpzlMK+AHa1+xqNI1cY#GX5q7{XcmzBSo(V64*TWychvBc_Yw)jd?a?kD zTfmX904G2>F~r(y87_gx!Y{)M;dSs1_!IaH{5^ahuJvh`{^oFJn1|!x{_s$^7#;)9 zfZv4I!tcX};4k5;@Go%9F)kmUf+JuKHo@tz6E1=);g{eA@EUkK{4snQz5?HaYwYIo zu^Ai=vv6P74nGSQ!q3Cg;Wyyb@HY4$`~`d&{uvG(>+-QF+zDpjKClfQ0vEue;c4)E zcon=AJ^-JBzk~0>A$2Yvo4{JQJ8Xdm!^7YTcnUlZUIA}`_rWLNi|}n2?CySlBe(+` z3-^N4;6ZRcTn&-JDBzN9Cj-7^`d!WJOiDwyrG; z*AIeql*0mBi663|=qWY4K@dpyW|ZWNjmnKg|DfDBu$9aqn*>3dhBpm@*-Fs~9HNvt zc(+p0S*Vmb^D?E(S&vc59P(5?KU*ntzVnqb=ek%abDisyGROF?Qe^r&lp<5#rxclX zO{JtSw_ud47$s?=L^X;yVU%vtD39M*gnPm!I2pFW4tOB!gjIMrJOUmCSHcsZzuz+n zp93#|m%uCG_3$QmJG=|t48f1@Fn;fd=tJ0KZG?ku3XlJ!{BCcYq%pE3CF-J zEWvSb0-Orl;VgJCEW^3buTS(5UICAVC&JU=S@1k~A-oJ;4R3(Az&qgG@Im-f_yl|g zJ_lche}r$t_u)U_&>^l|*M%EFzmBpk;ho^Fa4gKjMz|03>n+m=?+<6gLtq8Yhl}Ad zcr-j7o(#``XT$U1#qe@?E&L9=72XN&g%80;;ZyL}@CEoPd;`7xmDm)w>0gr+!;R*0mcqTjtUH~tFSHkPzP4ISj z7rY<(b*;wM>rCWfmv9B(zg?GYx;Y09I=+`rUP51@)DtrUJ3qOD#!!<>avGxx)fm_1u;RrYy?hcD^PuK(} z!&cY<4}_ht3J-@zz@y+wcmg~Xo(a!^7r;y4mGF9a6ZGr0cM-lHJ`5j+Ps3;7OYk-L zCVUTm2x~+p)bd;#4uhM)t>KPvB=qaWS;8ea4o-kmVLO}!4~Atp7cPW-a0NUTo(NBe zXTkHJU!T5=@YV1JcniD(-VGmwKZQ@gXW(=2W%x(45z{U;cR#atibtjG4$*0M-x6Co(#``XT$U1#qe@?E&L9=72XN&g%80; z;ZxABqHS5v-;V`%v z+#2o(N5U~M3rlbuoB*f7b~ppKo5JQps4%i!nX3Gg&{7W_Iiy^fUs6@QU$CZ+6)eMT~vS;Zznhk z`u610_4Qc9Sc^XliVD)g+rr_{x64o3AA0@YL43aq=fTDBNVpPy5uOge3eShD;Fa*( z@D}(3crW}3^m@Ku5`GT80^fjthF-rngnF?q+!$^NcYt26w;SO++ygejDbVZl4j_C8 z?1qQKUg-6B#}Pgmei@zvzX`qm?i#}1f!;p(F2WB$ueW=W@UP*E@HO}r^!mDw2(O8L zX#=2S8Try?{KILY+6q1 zL9gf9itvtb7dRFcpx1AWCp;BShqK{lq1S6IAlwH(2akuRK(Eg_m+*z~Tku-=UFh{# zKO+1f{26=-{swye)gK7I4gU&1hHI_u%E{}kK1Fz2I2?|K8R+#@dlPPkEwBR~1ihYW z9^u9CNVpPy5qka9R|%gFSHUZx-$&u~Qa|AOz3?aSarjH<^--@7egpm)eh76hQ(OC1%Af!~Ce!E2z`Gu=k` zF8BcaDSQ%o{nCqsUxRPK_u)s->yx+KN^_Su6@Ll*f==DVFtmn#S zBe(_J9_|diekez{5$+2o!#3#kLZ2aAfrr5(;Bx5oK_?MD1AYx&0564C!yBP=v(_%w zhlA;lM)3J)=;tARp0p>|o8V;F3jI97&#S%ur^@FGU?2P(JRY6`&xGf~|CGMtH>CFx z`~!R&{uO=<*Fs(%20sP2g~Q=!n1Lm@H*AJ2umc_hyC44?y z1+RqPhTaa~2ZZm1KY@?KUqZkB{|ezZ;Gf}#a0v3UU-#db@Ro1~I1=s#^KcK?1gF4u zcmVY4{N02PhrMtG^!qUV`u>->eh&O5ybN9g{kr~bgzth6z@Ne=pa`QH+L8NLqRg@1#7U49+p=8d4=x4J#yo#7amgN<-sI2pD< zzYhNy!WDQJJOVC=_z3jt?Y|=Y0{lIE6aEGI zb@nxom)D1z!mVK~^y}+&go|)5I05bl{kr-b!kw@OE`)v`uU}990@qK4UxDYri=bae zzmD)t@cZy?_+#kT&woMqS@=8nNB9o(>*i|sXY(z%A>15p2S>n9!z^ro`@l)iuanOt zd@$^S^WhTc*T;_`d?Nf3JR5!k`gL)?fB6Qke-GXX?}L6l{O5$9fzQKN;h&&i2md?a zp~%bY!A;;+(64{*LU=4Jz&+u3=-0ic6P^wIe(EaW1<7L6tfS1Cn;f?TC_(OO< zd;~rLe+6HF>2e9``c^DlTJ91q?RA{z--)ZXr9qvY-dxw!*B8|FRu@>XuD>T0_gS@T z*<5jL*Rxo@X79^gUFruj_G!7dylAc*pcA{auw3a4zhUlX`L<*vsFRb87goh%aGf|~ zuPZNI+B?5%nV!H?H@A23vL$j`pZN8CiK+84|0>8E5w(KJ^0%Y>i6~%y>3I9fbsw*m zI2tz{uO$|5r`5!p6N@)|HSxM*@kXpBo)&`7-_EOvr)#V}-pJL&(>bD#x65kcX8T!Iuy}#=^*&xE7EjkC&V|fi>G-=r}w;E^Dn&*eQ8;Wx+mCI{`9q61~L7vwznUrIun-d6JG)6@3lzawvh9i*X8@P!fk?6BB-jaROB>F9fX`80au zef)Qin^|M|*5B1<;D1-wZ2foSZLmVpdsyG_@}I4ca6G+JB)uQWHBE1O`RkV+d7mgo zH>Zid$-nxgN4zOwRItv5$$m}CIm{pNe%2HO!+m1H!P1*9MhT5Z1Z!P0wvLJ(-3^sm9vyRBLioFb7lJ>Rblbieye z3(gnUPaPV zeW!m7mfnrA^s*9pu=2Y|($jvxzXnV1uacg|)BNS-Z?N>fC+W!}4qt<%xAFYwepQb< zSbBez^lteC?RSo(*B~9f=1-dZpy^#NmHC3T!|V5q|Bk#3j+XT1`N1>x*}1&eu}@zwb;_9cq4BS{MPqJwJ}ER6Hr5CyKwr|NEVJpLb{9 zY{{0hw3WZ}`OMDDGtWFT@4WMT=b4#z-*@`?v7YAmdkW`<(_K|{)j12Q7gQ}=6b@JF zEc-VcuBtj`{z6S}EL1AcpwtC%rRow&MK&w7{4S*~dtRyNl}fcB-Cn6w=PIQ>-mg?2 z;_F+Ky6!hAzwun9Hvd4W+iq6sjz22(nP-*S{w1aEy-2CAoT=0Uo0R&-HZ8gRe82LA5EgeS-$|D!-zlG0zDY=*{w3uro1=VZfLTT%k3rtwO;f%bC#3sr`;{+~|NOPe_oWKszq(QR zzCNgY1Iv`}k-L=dn~?F(`;_lV_@}Qj{@J+lJqJGVKSkLW?l=Db4k;h~Z?9Commf9$ z)#sIOc!u)*1@$=IAM98DP_6M}hm@awe2wvw)+s-Ic%t#|o}v7+wq@@xK)JeSj9+?% z^3$)_r~H?#QvUbfYJ780`RUt-jbAfc`RPCLV9MVRR(|@MK%>76<>|Nn!uajTqyJ*R z@n4H8Km9|G8vkgu^3y-D!uandm7o5H1Ij;GYWz=^l?u?$yH^EjDviHjoeIz|zE%a6 z-kP0n45>g1%G0;sXM7jh(mPuP*6vq7kaOa*VgRt0b0rh<2NsNmgY#((~!DoB6dH&yWdkE!5;|EPkG zOg8?pX(~wnZKS^o|1USVKJT*%KPbuRNf1lRNk-aRo@AT98vj~eof`S zFN6Q+=T&~w?^S;HWyUA(RQc<`XZuaBsQgRl|LO0H|JDsE|2vRP{{vhz{lEOH%KtIszW|>7GmQU_t5p7PTU7qb zn^ped2UY$bLn{BzD~x|*Kox`zru?{&DmXQ0{FL)m!MplZLHR!8&zh(T=;weo4}Rel zs^DCt-*c5JsD}*kk^fc&7yYX$xa1*KaM|Cfg7;sd3O?MV3L59Bf@b7(%uxl2O~$Xu zR|VHxW_K_>lwPu4yZ z{Ik-&@Ruq?Upm?NQ?F5>$^Saimp!CHXMR(KW}U1;b8k?g^M9j4bu(3H$#W`n(Wxr5 zYLg0G0e|HyDsy?Wp+{8cA750Vf2vTS-S?}|llQ97_XdoA0rY|JWsZnFzlQh2Jpc->wgBr8)RyF4GU#Kx3K$^Y-Jhs2SUyb?9 zL^bAtJ!;I;rE1KthE$1LdNwxeuki}5{>z2-qxc+HS1ybf|U zY*dAti&f!m6I9_A$oUNN>A#3_UjYyOgPYU+|Cy=^zqwBp?hdNLCo7GA8gia_R22@Q z+)vI|g+HrMh5I3&{>6S(c<^ym_}amg{}bx?e<%xIG+}niPdTWH=%){b;<71{ne)JgxDhIIdRrHbf(xFy~HW}hm8 zFD}}a?%y3$#q_h!H@+&Nis={LYy5eGs+hj6!T6<9RWbdFVdF1*MitXviSqOxEjGRx zGh4M6w^zlQn_GKXBGwvfYLCW}lpjV8Pr63MdRAY92DZ47Xm4x6NhA`jT~0=GcV8E3C3AC6E2^^NsUj_{9j%hrx-Quh zYjz5?clEZi*%Z))924tlO?1SX9a+6eT=(ksw)HC3+nj9g1lfeq9uC#xQMHM2XuyN70zAoMnlTuE1#**D_h1L<-HNxLVEGBI!^yJNZqjHtHeHA!5XYIVZsYDB=qU*_o_ zldXB$lxE-$s9kH?d%C;OZp5PIdUdp~OD8}zLsUmvyOKTYS>~GP>ei%*bhh@aZZ*-K z*3RxVPMjkuL9ueDTixq$V$AI6>FQR{HME^Q9Bu3FxtihHSbGwoQK~k%0VV=2O`z`f z;Np095GT1SNm8_}r5oDAOdU~etr$mbsH~f}t+%bCuQ#swB-W-Qs;vzg-G(b`W?6ga3L3G|ec%Vc|( z#**H)guWxuSo6pG+It*ML+XLD$9gr1+#~o>#1yA1j-3@n%G~3q?!0J6ds8#VD!{C# zCkF6pOAS(q;!=8>V_m>UC!(*Vt$iKqk9D+0SNC-HC4eMRDw*!;*lKnW08ws<69rKy z44q_iclXup90@wpq>$wThZ7^I55ta(I-;+K6rE%4U!qUnKLq+-Ff_U5W+AO_7DHjc z&58m7Vl5QRP(?d6Mno~1J9)7L2q%>0_q6H@Xp^4Nq2}prZRKcgV~C;*x+RVA07B9k zS|&zPGRA=)ZA-SA;my!V>at9;Y+skuZ(_Q)*R1VnPn!0vjdie22AKMwxJ}g}sE$sUG1kf+O-mczc&x|C zKrBV_6e5?9O!b)S+B?x&z&X%}k{L*vjWi@_Zby4pE4jK8NhiRF?OJWequpH{oU#p< z6hr~dIU-GN5Rp%r@SHFZphXNY*&10+-$N<~83X;(*TiDII?%kx;oQ*O))J#!-Hzln z?Oko%)rJ<-^zA=zN7gRJ0nRj|D`*3s41sTd~WF^0X(?XYt3rvn*KMs#<3Z%6mqRu)*@6HCMq>RK4W%3^+Rf|g%-E z7X|@r(6k~QVq|r+G{;+M24Y~q?!=S;Fd?jWn1(qLI!h~LmCcBeReN>sMi{##>o~tq6rO`=?HW`D>sRr`~h8;UW2sAO0@t)S+xE^Lg zkFCM-Li1oQLgO5ES_+&}Isxarat1otH$$V#Wd^^hjduI)|L? z32luey4NmXl3cy<_BKX3*@FnUocN^a5Rdt%9U*od78Osf#ST5n`sk+MhaxlwY?k$~pV$&Zz&xIoHi=GG8=aV=J<+~iniN>JV2$f`N{YtOBKl*GT~i!Z zP_)w>%Q_-*X>+Tt4h=R&`?}mFI5E}TrT1@?Hgc$QKS;L4AIlMp-Ap;~q;nT)~a#7qg2JcVo$ zWoz5kgb>S0Iiwlz2eu)9op#VR)JeB0V;e>jYxHs&GNj7jXQ{iD4-tym!I zb-UR=(6TfhV7iV`?@S0fVryxTvNlFAVtcXZ)39h_3O9&07e_m95>~8O9#ePQ5->4) zd$GsWLcCu`rNO9T_Il3hZo-PT!IS|HDGXbX)XN+s5w^g3pq$R`mNrE?46}|V=#@r$ z%!tNL(*YYF?QL$xn86HY_H#^x6DQ4H6JVEuG2Zb$Y}=VzZ$gR?8sZ>+3^>4L3_~Qj z$Z;gCVJLloy${_9ypB{afXZHQF44V4rg1GMtt0v(+w@iH%S2Q4b%I5kv_==$x>QV$ zDs#=ilAf5xY-gxBs$-R9*Enn{dbKkca9b1Yywy6hYjq6MthEs-QPnHLF;Ia=?Xg>i8LTcUaRZxvKooF=InBsBG=I+l{3QbP4;v-QW7wI zn8wl=x}5BcuE*}Gv4udDi{!>Pl4b^hG7RITVmW!~__IOzG~`5y{sZh&qp; zVj@o96y=VJp=;RD(LR^i^mVek&t*f*Na{;yf$Q3OX!Bti#pwW9(cU$(MW$1IFlP0{ zK&BMF_38ma4vcGY3LzFCLMH}BT<4}Fr)J(Y?rgj!Z9upQ^pT7JEhIG> zQuFW{cOqV6=3UL{w#Moe7tkOz)hB{(YurAQ7zMeV=wGaVzM zr(+$Ol2mFW-Feu=b&Yx+)@j44CtX&;1wNMRy2X;95Iq|s)blPGZ9Wqx8{5i&voAt3 z`6&{lFkcEc|wK7jz zSaf;Z!X`NgYm;PNO`{p?wn<(J;fo#Sbdw6Y8F^0KI zWKozj=h7C@(eo5#HLv|_Tmw!>y;P8}uC}OHD(D@bG!h15duJL2ofoz49)#Dd^s?q`F^yAi6j>B~nrK(4PZO~@h%>$vn<4hKc_@6K$3x;do`=K}I*VjZ z;p{5qY%0a1DLAA`qv+GBG>Sg9N~aLm(mH9P7??$RSdyT!)+@StREKC`FMSSWA@Ni^bDR=}dYD)~30K z1s0#26Qq&28tNTMv0E?40~VLPXPzQkyS^!6`u1&#j_ppb0)gaF7ugfFikWqdb*=73 zXNn0E2=_9r(d|&IV!ct>X-k#sCEQ};F^%HxK-yI7E8?iko}zo5-NrO7z2Rt6V1Ht> z(W2n^4ln{^!nz4a0s672Xz}SyMf=}pruWnNWj>~wp<#Uw(Qd= z+L9YdN$dS&kGA~NxM1=d!zqm_D}Z$3$XfMQTN;zuS4$&d>&(*(>~+94_b|ca9!W{# z!eZDv^Sg^~t7vL9?IG%gT^cQexRFdF=3G>2%xX*4NT&5>FV^B&-)nZg(nxv-ES*AR zOru~1#-^B;gtbx{$!wFQk@QAc8b$9`rBTdoOd3fqB2pCDBeN)&EC5z9>yEiwR2G-B zSCvNbOiyXMRVl_kXU8c;N$m)w(MFo7shyuRM(?e5cYG|a5$li)BMv0b5Xm&&NE^X6 zq6xC^Vl`pJ$dcU@i$^v`(n#LgGN6#VAz~LC(J0yKu$e|&%ZTBQ8QIyUNRNGs=TM|fyy=%UN%C4L&0UVhsYin0+%R^Ta~^mR1pvijw} z0+7c4r{(|EHHcSM;?LFY@51WpaCp%<^PKf{W8rm6Rz!S0pAzR&_)D)O5DuGoUbPM@ zRIwVPLc8Ahum65S?JfrG4LG0jUt3Z0RH6=lKxg1Vo2%iD8kS zRCDyBcypTYPlY*n4tNfUbId;@bh-uSg{v`Bb4Phj-DMZg!H#}UdlQVOUfsYff2M$s z{lV*@GyP!V{PjE0=?KXeaME5r>C<;3Ka>R@{>VO}UX~LVbRx46ju9flN6-NB;orfE zJoHT0!b=+vRp-N3Fyc6oN4hQVamXtLjq=zBBJX0vk(EH8T?>BgYnHlB0$uuqjQI1u z`UoSA6F!F0m(1FS#2$o2@Nz9|2iuk=4+-8QaUxIB658~jI{b#v83xjNhH1McOxraw z9Zc&Z_6l`@?K4hBi%A9C(Ie@Q8iy#`M9z~@{uGm?f3+Mvl;{#Gp+zccT!sv8?oGbap|Mo#%Taic79>F-L5W;#u5{K}7Ps2{53j0z)~(dgbtaVGp*Osk zMEwxA1(6jcr5l1912+PfK3t-neCj*TE>2O9e+;oo{=bzoxH?g=ss{bYz7|LPq4Q$Z zg8-8-=%U|(EsH_3_4R3_YvIL_kM6zjHdZ}@4C;;-t5$&q4Nf4?E(GD(VAc8HYjnym zkTx;25#m}19|Db7MbGxJ9bT;JK*j~2ixYX0me8i>0;{MKDHqh(v(6=$G}~+3=-73# zup(r+cX`sh&%A~$@Wi$So_wBTn5}yk-kkp$wwOnj&DMJh|C=bRh+xf)r~TmOz!#P% zbuL3(+*M9G&QNd>o$ume6$~NEjgE`X>u0jS#RtvJO2fsoe>=4Fj1_0Ze=@wREtq5eGI^zRIBzW4dz%^&yuS-o=FV*i|{5dY3_=#FWF z{>tXYhT(9(3O{jh=%xwF0}ro!?db&3Fc=x!38_`;-TenQtM5R5O~hBul1~la`f)Yq z*Moxxo*%yTq{78WPygA0ygz(3Nv=HyRt~*UNonXJ?KmcE+bwL!`u9Hk)|Z4ghHfm_ zlz&s+=HRCSHy>j=4o|~*|I(T>nAG+HZ<~yC8w=P0qTACECm+;XJ1?KP^-BFuY&!O} zIKYE;)E^tyh?5-4UYx`WiCj!#!F}*{8%5qlpxg4ELI(BLi<2J)&Bn=MT%avauGeeR z)gt3+locm@45crbcPoVNN0<#x)`Cx*$dj~$HvR3w$$O+S;23Q-_M34sdQ2*ljYphh z8}EZB4xVXP^=}xzXIp747hq=&FjKfVQV+~?#+m+}^M1%997#wDC~j z&B4S`@$j5Q&Vq4tJF&ssa2F5phjry&K7OZv8Sra&Vkw&9I^g8Ws^uF7ro`3Oz#s1G zy*^SB@oiN*emuPFh2h}6*T!3?l|1jOE;zI?xN->Ztl0Vdu&R2ve&V3-f~%+A zcQ_dQ!``yxy*obT^4zMxW9DE(%%DL`_-1EFC929{>{j{B5Lk~d!Id^cFRS1ag}LtybrS_f$(|w z`jQzN$J`j&RB%)N=Dbe@Zw}l7q^&Qh{CHu>jCv@_v9m|92iSwddcdrMyxiqCYis>H ztNwe}9Be04R@y6W?~4X<2h%4MPV?T06I|uJv~l%*Kmu_Zrir!z$w%9F6+Cf3=8!oXBnh!It+l3P}4XSL9ufIOT~8Bf&O{ z6M3Hm!Irll^1`68eKI#u?(OjQJd%LCYS6?W6EIr zh@Whm^f98U8tt<;dqf`dY-iJRF^{lKDHqiE%Q`rQ{Ag_%!eW;}de;y*k1#*w#!6Ez?Fn8F#~fZ@q-ZyY z3nS7f352>G&OdVP$t@jau)|?8VdlGk*0!bHs_tJuCSca@A8&MJ zn$vM-7C37LY`U=D{HH24$Pj6Lk1(*PC)`t+!4T;RhQQ;w3-HoP%Z)a7&acXTj|FeF zp>yZX3AodVUHQv{k<;Ux&&nc!h<|!T!PpfKz5a(+^Iji6eR8DvDpJ(UKkTKHqJhdM3cq%Cxqo>21$oQ;()G_j0f)I6|*JZ+?z-1U}bP1 zu{5w_(&>RaO2d=mzUj<=;6PxpYqMHggkNH&S=7L-DZ_leMS?0g2 zu%x>F*&qJk`%iz5Eh(*g^4s6qLxGTW?CdM^oFvXL@O+$QKpkcu|1T>P~_po z!fEn;hcw5!IFW~!3#ZB34|x^fqdY`ic{d}@;&Oi;M?}xdpwWrE&mnH#k7vLqc{bm} zNLbBLf7Y#;G}e5`K|JjOr*fp*)Fu*Zzl#pzqd3K^e9g7daG z;j^!md5;z-)rdC23{cbISud}jZL{S~M5k>6O`OP+w1hT27xp5S>Xr-Ywy};dJnhBP z5vFiadKW}E+KcJs^L06v=a}{*pXFD<8z73$ zzMRjT_odAgFpbluh>;V61^#KckEurgXG$K>x8L64)(9ip{Jjbd;+-v=ZpNCw++gRl zGH1UXIuv0((yI{q0j$JL@^NhVF*(#SgpxKm;W8&&;e@&z@^v|cdVC_h%E@nZ!WJit zJ7I?tCY&(ogzKE}S|{vx!i`S2*$HoT!Yxj?%?a;CScvP|!w|;6FP(76q37d%@p@M< z1YeVr-oy}Vf-MYD?yFAzfJ6Uhht4s~etDW9`so>lSZqyzd_N9N(1m)9QRAd_KLV6= ze;~h+bSRg;KBW7ZMt{lwAM}9;p7qH-`u<%%+6d>aLB?Xd1}j3lCja!w zg5u|EwPncj+tS~c&Mb0IWkXN+YG^a6GUnwiXPjrdp(g^%1BdpgEiWs?v6`yY(%qk- z_nN5CKWOr6KW)OzPu60}NV7B9cj7pn>W}?1CeA^W*j{*z1)fitv!Hs>yxf^uC)C~- z`&nGjiOfc5&+U&RqXIPA)a0QL!M_KdL&^_NN1Y^}IP%bO@7fGKom2w|Y(A;?GSKaM zUqnVJXsj11>ekzgc)+qL_90yjFHY)$I+4$HJo6x4ixWPEat+Me%t9b?e2Oi@c6e=y z&1l~|(8Y;7NlR$cb751kKTRb z$E3}ptOPs}asY^s8r`6JR;`WnU9_Co@EY&ver4U#3?elyIH;Kd0aL+MNAl|uLsLgIs9HQV9EEjFkg zba5h2(h}PAT;LYAS(67(`|+Y#r|g?^ z-VODEL)V{FJa{s8kv}x+KY#k=!?EC`*`a;sIXSQF<&JPDg45mdg9m)&zd5krycZAX z^oVDK!?SXA2;Vv2vvKNq;Dz7=jze6WT86ldQ^cQaaEgt%61?K1O$@y_H2@m%Q7~89 zfqGrH2MO-$h!c5|me8i>0;h=mDHqgO%Jvz@o=UlZ@}>*4y~Q?B2QX3IMql?igTuuK^PGQvnAVF=|GxS2{NUYzJV_Z)0_FFN|}wM#Ar zpRMm5NN1z(_k!;u@ZzLR3~hbikHjEov`OSzc>P|xWB`qr4!SszCus?7dM@nKG`$RQ0&ffvDuqO_h#=3YxdqPz_y1TYMv6OvduVt7P2d=mO%+1X2 zcm+%Dkl}dY!ff;x$Fhtt>Kyw}oaiy1g|^2$^*Ss}2!(GU;`Uf>arB)udwySvw5{(~ zA)SrBZvmgZKQ3)zXzTmENDP3c$1Xy)kK^8}@2k)Vu64wTJV{Gv({rKk={p?w3=}HT zdZ{b)&gb5Afj$#qn|QCx{NB`SX|vv9I)c77^Yc4Y+0pbB^Sk>_oYDTrH^X$0tFN5j zOLuJGPQipm0=(Z7ubI^M7ailp zjJfU}fU)#P#|-`-m~Qkn!Cy@K(l8?s2}LGx_j32h^+2(8J?yJvhXJx->^wyH4#fhy ze?@n_STG3P$bXaJUYy8V0)mYN`yh{F(~AW>uR&Hq$~PjC4Hj$zUz-#{ zC~abBW5F+w*aO;VSa1&-aXijfw7#N!#s&2rM2a>#7MzNLyk_<*vEU3NNdIa%W-rlx zWR`ye_I{Jk`XZab>S>uUqAL9laHC-azRhkRA`6VzV%qIuL9;4>tvK%;$1tCM=m@j{(N zy{-$RkjNm>j=M~r$Xodzyeh=w2j@7$MF*peuByuFte-}B&9u-RU9?&`_Yet>w8CVM z9Q&Eayb&^o3(gbD3YFP`w?pFInTHwK%se%a5vCx=i9GMj6G8?@_GmK?cay1Q;$)jt zi+^cnexwxV_7n8!{8@2@C*?bQjN zfT=H;xH136yiLKI0-KNR>An6kE)OJgW)mN;nY9xA$Xh426?MKAUYy{F7nf!ugC{7& z5%SOzrxwGTp@0Zn5}tL46M1|@&9;d7BtRxyS_M9P=D!c=Y;b8G_!{BGNt+njGyg;g z-w)boxHJsDDiMZI9+TlHu=bKaAA+BieI z#zr;_Op2%(`4QjOOCukP%#EvUzHRz6?(UNw3q=A0Lr=_#SH>p+pGY<6^tpriw2$!C z9Of5?^)If$ww0(K;#MG1S27{>ToGRTu(GgZLS2#htuL8y3~ed7U;4Y>??}92e~S}* z;r+1jg--@$!mFj=vvsx~=~{SkB5yGWw!9=VGU3$~-~&`7r2HO4vcap@z}F&$5K5aE z+IUryC0=XugDUg_7hyC?t7 z%i^^TXoYZI9L=u?jQ}t`PJmw;w~EaQG9!M?t2{b;s#0DNIQlMOrY9ha9-D}#frfXD zi%-S#j=!Fi7g6y^ji+kMsiLtGc2rfQ%(0_}fm3(}a>Sa>wxPJg({S9LfHb(IU(BC7 zGwOs|-`RREIO4^nQVU1OLr*&@0&nYP9O+7UaUzd8ZsStel1H0P&295?(RF7P(UNThDsSS|Wq=kOuWZWVsRCaQmh&wKjFw?uKA5-VhflQ`o&eN2Fs z4KCaVzHCk(`LEak@N%6fYei`Xn&i3;Bos;#`2?^6#u3mEuboOtD7YF0& z%u^dX9^M=|Es__xJ`&b8!+G%!4hL8I=1*+!Ev#u&vtQNkwJ3-@J*?EdJ7-7o4sFW6 zH*$sZ=7c3v_YJGkn#fFD_L2Iz4MTgmdo#R&yEpi44C9R&2+=S0Iw_2_IF2DetD>=D??p!#<8N1#<`@C(>RH`&gV{1F^=o8REzYgC_b(zDzdAeW2UeAo9F6 z2>+c$9iqH9vqAQGKnMY3~vdoE2&sfSQ4%;^4IDBEXTmka^C>&T{7ov8|k>&Tb1Z%4kg>(8bDf{V4D{! zi(wM10+SajF9OZRix-hzCc+Skya?hp_Fe^f)KxE5@@Y@NSptD}vmx9bCsLOeD;trq zS_&Z)K87|{-VfoWAdZHWkD}q1W{_u*bX4kLA{SU`|NDdzi9zfqn=k2-G6QEhq6~1pn;}(YWml!ADy)?alV{ z(jRjhZB2;>Ub23(J;xzj8czEk9^Pf21q(OvE}Lv@(6g}j{{1Pk_r7Z9 z?0E4`{+E|HS`CX5J6d5p2@eV`FU_vBbz=qca5iZFv$s*dmHxZmd)7mL``4=J80vhj z`kjfN?00d3ce6pT@h*XkFlfX(^3Z3pHTyx&gr8npa|;Ae|GfC=-S2uDJoXq7yz=7b zU%=N4FHZOv+W1)u{2T&pH2kEk$+fsRktb;hZF(;76Y6fcx4z%Sdzy`{S!vbA`$5bS z$F#vm=Yy$fwx^>KVtYE@#+B_c4T&gT3{Q-k#t?~_41sn0hX%251h&nuI=ZvP%7xB4 zeDu9}e!&1P4cqvvLow{ner@ylXOH`7^R&eccpG58IsSMkI4O5m5s4 zUle(5uPXl@-j}>|ILtT5U(f5a*U9$YPc8C}^Ro`lM{RSrNIsF)$n0Nn#3Q=d@HTE0 zBZD~Q#VzmoVG=yHE{MFv9(faxLA~(e))k-uS`rAfyAQwF;1<`?EvAV66+B^RSl0bja&9E7Q}g5RYB;A+g`Yl99RBWs$;7q{ z|4^W=h`Sk)#rCrgi%Y@{`q_uIcniUIV1XU;b*uUGcJ83-gj%!SDjkndu*QpBdyr9q zd@pu!Eo$rU9;9pG#fdzx&2p(7t{vy0)8l|Y~! z_d~M5p9jI0&D#{70vHW|SK9;#S+BH%&?GL2#OabiXkVj6PNU}nf1rYvGjF_Q`;22x zrCg@7Ozyd{tux?>KW5FwVVQ0y>46HK3GnGQ(K$zF6D`R8Uy~JPB5?KFoMrM|_yu^n zyd<&%&zHY2T+`2;qU$49>Q&ge@%eH8ooYHxFiXFGNcnGw1hy`St2+aF=fCl>z>aXl z|3KhtYSth3;xsedgcAe(-uh27rS1;w@XZ_BfYRZY4w!en{~K0p^W(lPKN=3k*AgEM{|r>>+XuD_1s|40c2z}t>{>HA_mt%;6UGrlQH@;mLV z>g;oI#0)xOq>X7EP|rrtyf&J5eYpa%8o(z`T=X09fn0`9IGwb)Ylfp*QHvJmIDRnEI|x9XETksP5X^| zObqoN8bG6qX-py;86tfjL)dc?hx<9 zviI1Z;)p$TOW-_9HKdYhB& zovnDq&S>kps!CbdjlS1DY_1{A?(;976mP6Ddr{1OGreYiyzP3OvSmyk;Ty6#aV=DMl$YqZE|*PaXAXPZ*ayosE8V4O*( z?w72@O>U;=C3p_XK42MQ0iT}`M_Rcg5Nf$GN8R0hBxmS5^k|Q=zl@=ElwVz7OQxZr z+D1TU5_|N20juZ9>oKx>-@$_Ftk3HXnw#um$T+lSXxHFyXiud5#`a+Q_u?fNl`P+K z&{uoYK;EGxdFp=!4>bhGMe<+i_;~P+z?PW}$<3~qpolD<*kX8&B;r;*EF;?pD|~CZ*DUNEBabL(AsiEyf4zzemUM#G!o;&tk7{+AWZwe;qsEo_aEE; z7@C`pn=apP=}>RV$dey(|GQ-V(`52fGVD9b`{qp->G_U*#Ien}Vv$v&mgCL= zt_hhA2kCn6a;x5U{ZXbi$m5=G;RJJz!+B!`(%frY#SoJpvh-JbQuBv=5j4BAg{ta> zSwGA67c(H-`J)6DLGdF)yFNEi_H{J_-{G9)+d3|?^0l%xEC2XLpZ|fsAD+jf?V`?IQ$9avX^O@vYKfaBrc9%fTJpoBt$$X3$T5TuIhLe7 zzr#MqS0&B&AnQuP8$&l1Y|6hW@Ae=|eiV--o07%+1SFL3*xB3Bm<$;`^=*-sP{xfV3uUvYv)i$SpEZFaDo@>o{neHd{Y zFP}krBfL0~$LE=Cd3Qlx7&OXbyF^|baeJ;HuG?c+>hjJN8__17R2r|WSw(8c;RrHuBjX>(8=D(W()Ee>WwAom$7 zosie#hj5MYzgxe-nDv!^VOWEX9jp);2c>CPQ*1L}(udXD>nZteQ((V5GlFh!x z!jg&31Q4uyk{~So0dFPL3ka3MwukbOn=MO$xl+FCX`I2+3IFTo532k~V z<`1rcQcil$P&j|2=bJCmCENlg4d`{8cfRnZ3pGab8rbigKgy&iLducx$1%eB<2+A3 zrUX$pdjb&}w~;(Eh-9TrA^IM34w2`~PAvH%ihs@9V|JMzFn?urc@0~e^m?f)c z{n6ztWZ#i{TG`AWPak3a@UB1Zg`Q@bKNf>-<2~mi;t6e(H(P%kY5wr8KlUGC{)j{V zTb)0$S%2vFh5;}~TYqds``8EK?0G_H3~hQY=8yFC#mM<1J>RT1h_%MO_4S9$A7K%N zkoWs+cwVE-AKvFFIDZ&jOPfAirR414CS2Ye%^eFWoiBl9x&FXjxZxaq{qeUwrxSS3 z$sJJks=*N7scQz>{o(`_ylaMQkAV5yTc8fh8stcOPW9liF`pQi3G=xYuyOAhq&LEg zllHw21Y6#=BVc|T_-xESnmwmAQYk`d6GMB=a5Q^PwHf4DBpsD{n8*d@b52b;={-Z? znjt+uU*SmA)D&HH4Wca7jp7h)Y?`ikR%YX<(OQyk^Yg6B1^g6EpSUcc#jV!cM$ zY{++Y(u4SpTH1%v9Jg;}ze%2R>1{QiiX8Phmj&~(#{0+3O?CI1ct)*u6|R^O&x_nR zus?p;&d>_~owpr4Sxt`QUpPxYSIoVo;EJ-yE7&i>C22PSzwD#XuJI97rgxuq&kncs zb>ZQh?yhsgnh8I#US0)A;j%M&%ffB3_Kwz;bHi;2G-YUG@}XdmY`aUxIB658}!;5zj$<;<70I0lT9-ZUxV zd^*3}eaR1b&K^vf*K3@8M|l0-bdl~GUL(h5Cft9wBZ&d!()Jg}G|!n?p6%qk;DA_a z7D&^4Id)LyE1&iR;6j1(3^as?DHj8Q{o}_3Rml()alA0(o;E}Fiu*1V3^+NP(B+WU z<)B2)Tmj^1*Pj(0ZLU}(uU5(8zizLg4RG#U!T-Ye@UJ$1B%uGHOI@}1@tGFK__5n# z|J#?t_5cWosT{M^IC`e*;5nAX)gls>1VYhHzB|O$q^BW|xO+ z+XlXm!i$qOF|@Ic-*4Fi8jj!GYhgRQSjT6zX}^gRd6JgUroUZS$MzY=o=Q1lo$cfq z8McY~L2NqBV$gCt-wbm`b~M`4y1KnL+1jJOADrmvZZ`Kf)Av^d6S~{Xr-Mhu1lcag z0uz2`+M9+6YC7z{4FA`+@qj&XEb*YbEq5#ADQG+IncPi#yt6xG{7!fHFf_IE^2u1_ z{6pOwjjs|s-g;S1oapXs5NzG$JJ&K{0sp5hZJ-R!k6}g}C-Qi9V#^zVJdRB-7OVgb zSqZ1Ox(X5dnx!tU-LnOJpz;_N$7GVfQo<-78o1P0Su)NybX)%)IfDLQ48FIj|JnQxelSb@--1R=MO(z# z*C;fGHa!>mZ}$=PpYz?(=s(wTw*K=uS#hrZrvre40Bxh|e|vUwKi;*N^*eE${};RZ z&*xLs^g{0b>{exk0@dWwA0M~XoP0htW!T7v?>>45sN zZ>OQ7bqGM5fHe0%WWQsEldfP`klOF)?)V$NHTCvdfQGK^u#)U*c5u#~4EY7uCz&8VMqpjbns^s0;qd)8MS8u;{i~zWtBHUlwI?u)<&Y$$0 zlWXCrlcU*h-gO@BEtaRfW!rC;JMs`{*MQ$l_S;I(ZTsz3$P0t!wci>+d#m7k$jRji#_Ut=6c+9D$lJ( zTbr`|$8Igk>&~5Jb|T>x`%#?4xkj?b^nFl%jy>;Lm8?6ZJkLVIl0Yc(yz5TxcTqn^ z+n>G?JlU)hZw22~@Zv=O8QM7WG!lD28||!WGurppyg$u;&$JFyT76}IT90YI2n<8p zxFhdRH#K)B)@#Kd&AwSAud~iV?_V?3rs;hk5{gXHr`03Bhs1eF9LLVF)PG!m?f?L7 zKanuN?pM)SF9vW=ITHrd;#x%C5Y@I!m=VW`Jg@EY_z^I`yGPv!IoV*qHt=P$M}0Ks z)tq<5+1DsEhBp1}ur+vZQnrLxh^7UZ&ZxwepnhbsC4d1`G!?@_LNVYuSnQzKv7`L4*0o&AwdMbsIA{U;5! zPW?uG(N7`dgEqzLMXV{51Q{-rJsmw73RD z>Psp%6mA@IV`x*sP5GPiJ{7z!#(1BTJ?){SM}Au;N9O`!KvXX%j=+UKmDV z05s|nJ=;fJWIIr=>v(=Y$xWqSqeV`;_FP~E?UA5s=9!hIWcS+Utn7lLIk)0-_HZs9a6M2zH4yRdT{-kdWnyV!*QSBs zgKB!HEF8IQxTq3qg*OT>Dq4O@e42jeao~a54xXgO9xn1%MttS>FZERfe#(;h1BoXB zcfEc@Cx{)C8ZmKHwHEV6Y!nI4;Pk{))gH?n}dCuLv%Q?Y!3FXIO-K0 zam3bpo_B>o6Wt>pZID`cGei)9+YE2(y~y+09NUmV{iQr&mB{nj9FKeCNnPIOVurw% zjm=R>uz(QiD?RJYgd_YWSUvK@NxhPm(5B}CN9;al>!=qiq%tSX_8KQBZ&Gh&gYX__ zvO%Ugk{D3#*`D-5Pg)t6acvf@7_eD-Tazjp?dWcfb+ksC<1u_Pk%Ugop8i)p^G;)2 zSOsMBUBYr{cZEx77b}?@15mMcN|CNMQe|!@ldj zQ2+AYQ;_4U=6mJ~4+R4grhI=`Rr|i5xgS@uU*#^|zEN!PZ}0~C1^;76`^U}?bI zpaPG!|M5S6mw92t7n#WQ%x?DOao1n>UFN0_a;e0}Yd)?-zjAzzro+^Ad)ys#bkn;o zsdMBZ(C$dOegSfAc}IGe`6b|ctGb@ee|L`NUFNopZtJwUQuAxmbD`_(-;^`|Q%ucU zCY{oKxr?SmrgaH<*+$WQ?|*rwrz$g8?x?$fgER7@Cgfuy?VX9fp4MmrUsi!*+xSje zu2D0+%iQdln9@C2?4edwRc8Gz+AB=wyEXv#OiFk8U-up6?np2a-??fyIJ;~p;18ZV zW9Gzt<7ejY3t&Ysx$#4d+wleU(kE2;l$n9X#f{^BI%DRB#wQ!|b_ZgMW9o2eKpmbK z`0WAxuc0?I=iyM`*BRCg#7uDS9ys*5qulfa^Gs@TpNc7@^n>UVP#{ z0>`))pNL1cj&4Jm>tS&suNDLwpK2|6)H3pMj9&_G;rKkPtp?F^jzT6oA1Aljz_ZpN?oBX!f_^!*Lj8{5Hjt2y{RX) z=13t?r?yOhNzT3qYv(tdRxt!H9l@UAm!AklS=cl4vi{$}Fx%?czx6M7t(g@#13eAuGW$bS?1J zI%a;PF7G}B*Dl%YvmT8-Gb=;A7D-2?Jxsh^ctM-NIPdvQ_V~ejNBr>GGw%}72=zEH zAd$k4WG z3uI5yi!F=6XY1FMNN2J|-s_RacdH0i+1RoQd^Wc9Bb^PlJOaK(cyZDuhPEy88WQ_K zt#E^9Ox*sk{B#13N+ur417s@&-OK9DF@9&alnm zIR5oJuj)%CUQ!Z#`}bAdwNEqqDwo?bC)B!!{VMKASW|3a19|AVPN{{r^{o-mYfseRMm9 z=Vx$fI8(E$V1+8r!&9#1jog`8JXHcQ-Ag+$XG^8OHd}^(qUSB#17Zt3@ntc*tz)!hIF`kckIrk$lv?s^d|3rv zsCGgZ!p}zdZ1Ck#@HN7VlQuE5Z5ck-wjZ?7@MRwwai$1EDDo_lj@tBG;0tZVlr#Ih zVVCgM_kCwT2JyvyR*&~HCEK-SFw#@Yq$u!4k9-qRFzCCwQI2}by%m;!6Krw5ejCna zk0tB(f_lGi&HdicE+Wbk2Sc^`)M&(W9X5{eKjY3jI2)ej*IDL+5NnM!wJYCQh~}NM zrw;KnQ+8wr~J;6 zXXA+1P9dOVgCqBWFB?1MMc~LFc!?u&ExayXE1KlGN04~8n@Yb%i=1}txxf*-&&5t* z`;22xrCg@-A~`Fju4J-HM(nSc4_&**MO1vHA5YUU=X-_*i@7(;K6B5BFp*F{t+fve zMYB35s?7eIxBNy8T$)W%y6fhF;)w47qQ`W-{wW;bo(l2JwnL`sqUPsR1kU+RT}kD# z63&Ci7(;StikwgwV&n9YFl5NmdGgTn9@N9z7_tKCN_cT1?>!)-=?5~X8yu51hO9&y zRV5H;cP)Oi!H@y)MNJX?D{W$E+ag0*V#ppe;&|+<5ZhAjt?$uNUozPqBhGjfi|53W z$)5J6zGQ1})_rokZ7Qg{cElRNED|K{wW$)w;OHZ!k%yk?26!8DYM3Wr#5g?N74SCB zoe!RDa4rG97A?X2h-ij3&hed>dq5+;zL~AG0u3q$k2sMhX$ft5E^H;XDdnVB428B) zdcN0oDsbNc&XOmgS2=#@d}!!NoKegmC9JhzN7x>+GE_A`zu`Q0!Gc9DRvgJ75X;CP{o(i#19P#$pe;28xy{%2}PrW10by8z7W$Syf;^`w`#bVqKTVEQGu8^CB zP_V*#u0!l$y`*e4Eu7Ft8qxN7EpDc{Z-uxy)IIw@K64jV9i9C!Kl`)b zZRV!A*uZyj7eAtQZ5RlC{qo`9EZ8Na6~%9g@Y zpcj0tUaQNt|WKYw_cTXxxQC%RLpIchxdPx`APVJp0$uzD7U!H~Rk1 zqJ`Oi6Q#xs9v6r8p7mL!kKFP4E3f%qpD;fE=W15T&x4JN8@Uq%l%4g|?%?4!s&`CG z(R|fACZ|#(&&g8vOevnT)N`+Bc_B87>WVHjL4-R;Z#$Mch`A<*V0pauie{r9dFuq* zh#R%=;(|_u?~XFJ*btHkYMeXY|Ns~#yZ4_JV{Gv({q7YP)ExJbsO0}|>ZA468(cj_!X z(@Wqv!~~~SA#RTa!Jj(NZTz84N4?@WvTZP8h#9hoz#Yj3yBvA8ycv)e295IAE@@v2 z;x?WgL^>NhqYXwZ6(?~3z)bqD_**||Y!`#p`{8fhseB4L(FP|8fIQzhhsZ5Jw z&)aGC)!S}Qx&O6@wwTVrO|X`xhL$^H>v-8(9D}?~f?>o5d!&oj%m&@YoO_WW_k}$4 zOnWhrdauVeLOPLGhqx{8eq@l3_xa5*aRu_(W^p3Vi;0gSBMc_WW4p-5um#@6#A}hx z1``LsmklOfktHU!ph4$BrZ}T2l1ha({di#_`_Q2Re%qQ2+Tu=Zm6xfW#`n4ZA2wI-e6q$?Pv)}+bqm|2vLhKc9Q z&;D%jN@Li&m^cot^S2kZZ>?9ae!Bnc-wv$|9Dbw5cX&d9Iy|B11H%>J4-Z#Vu6${8 zaKnIa-ovlI@~0xa^G|InI20`OZGG&p8h75HI&)s+@yIVD)sd@)gIE7@Sgm^ap@qeP z*T*#Ezdq)V`G+P%zWmUSCqMGg_&?wH>QjeKX$T%FZ`kqB;+KMp|9#2ImuA#oG8{Z_ z>Kluh${cUaBxaR{N{(YPaacz@}K)(`PQM*#eqX*i|=@-?xjH8 zHqoi7r*ozt}0w~Xmj9($0omP>yo19U~kW^e=KyKx1Og^&$0;Z@1aktaAGNY z=$oyCVyKuF7XM zer5UO$e5P`fvxqY4I*bXUQSnD8Cj&Spg*E2W(@|n`^v{RmhZr)tB0QH-@a^OqpxO? zt~a>7{*`gP;~SOE```WBmXT{{@X2-LeY9Vpf6BLyZ#3LK$SE6A7tU(@(Qt6fw-1CP zOMh2-^=S{B`ZezQMqirrz73Juq1*aj7{0Rqw9j?Fc0==$hR@aSdFAsrTzAoBQ^x$+ z|0lIQ@0F7mm;E^~bm2=_X`qy^+;_nj4-bEQ+*Vb#md~ubarKvfjO$B}Z&ioCdc7(y*qVpl*z?N&x;}q<@z#?flkhIO{5uM_ z26l{@HEUnqtlC$5HwDiNY*p_L?C_r#KrNSU`qjblLwf^H1^&_BmS4BL;iB)qinGLu z3A-moN+YWdeDBrqfyG1DUHYTp^ZP3!UwP$?1$D30p2YsT?!dXrst-Ilbt&FZ6Ke@a zZpJuZ3-QL^`Jt^PTYcqYwuD=Xww|V2^yB`#?IknStN+qJYxy^!Db96$YR@a5*}ySS zA6f494W-)UtaT|Dx0Y91;>)~Eqilg z|Br^%Kw#So!!rg#_srb?53j2J*y8Ty|9#VQ?|t~`##<_G{_cBUU;l+w;~RdA5j$}ZO305 zhi>c-Z1>HqeYJ2yXh(Ef;f{ZTPJDI4ucn0by}WN@!RJCd3bs#fD7Z6!dpI(=!8bks zPPQ;V(z-MMZgo~sB=o`q^#$AS-#shx+~k)h|8O!mw-%!GsBAK7Kv@jbfDUkJP;2i%fQS0vHGVk=j@9 zz5zWsX5aAt$KJcZS5;m4)~E)O*-ts#WNBPgh}rPVe!2?;my zx(%STqhrED@zEB=jtI47)OM_>O;9>gb)cP#Q`76$+d5VHj^W9 zX_eh{r1mjgj_kLxw}iI7GUDp$9F(c-yK*-*zjbwWHtw@Fefq7OZ)M*%_?vfi@jX@V zKB?ZqQ2cbSFOs!&SWSNS*~mC++wiVH5I%OT+tX8MWp54CWN*sCZ>T0~Q#SmE_J7t5 z^IAJgai+SQHhTy-Ro&OFVH{Vzd(Rri(-)B|N;ihTb(!ryz|gO?r`ij2D)vNkk&k}% z)5D>_Q`Jn{x!pN_#6aM8uMgT9M(RDXd+RXYq_dd6az1POuxB?)!X8SQYOmEY%8=*w zRK5F$HONC1sXVl54f4>~i^ebqy`S_=9Fdsn#I-f<(j%`w#_}6V?wB4(Ug7X1U6c*bs8U z7)Mr?&6>2T`<*qNc6jTcExt>BF${jT2D*KLoK0uCF)+anIdL)DUIVVqM?Z=Opb?_E z)|jg9AG8mLkDvDz?#WW4e2DXn!{tl1><53$uE5rjyO=Mn?uXa%yY~EX_L|V%6nEMh zl!tepLaN+?xXSMF<$SC9Q?}LpZ)-k_FX8tvMlYYfR^?tv1FQSGcJgQ0S@0EcwEJi5 zcKcghzLLS4_@=6NbJu*@{uIJjx$Wn@k!@Ddnd9mg=KRuE94xuo3iK3MH&>r(`+I!; z4_={urM$ec)Tx)g|EWi<@s}RC^3nU=vHl^1^7fT?^8cag-I6u`TI=gR#Xsa!YS-Up zq25?j)$>aGj@m2UK6CIdej8Rb$j?!mgt|`&&Fv0^ztZ_1y^q|*I_Y=Wq1S%t)G^Q) z;idV5dcuR=-Af$={p^!+!>5OAoz_X7ReYb;xzMwZt*KHWlzQr(T8rl$e;D4HW&d-} zyz3dm4XD}n_eM4rY|=WQWXIbCk~WS#Ky-wySO)(wB#>hSYaH-$}jyFKZZLE3$GHIeZHK*xFUDkFMF(<3kFpYag_g z^~2A5=Wn~WW*hx%A9BEoEK*NhXxkVp8y1w+eS6#T-{k}b-51&< zCBqtb(~9I^A(w{G0O&4UlfBh9 ziJHteDQnZ*Zr`A`H&0P@#J{u${y1qGwc~#s zde=3x2K9V6$#?k2&{C&w+Kabpd#P_7VwTH6TcYPv6P%u4sf4Z#l_a%BsIA#-f7jlQ zGB!h{y_D^~^w6MQ-_<{y{@cB$Z~eT@97I`X)mX(BA)jcSBihp{n}PBk+C-b}!w*WI z%0^9n-w4L~f~U^d%Chw1o(lpWesIN8W`3~WROSB26OZNHXN|q-gVEo!ii_Ml$hSdb zTZrvNj5qW93LGs=J4ff&V^AIFIHF=cn zr=88o=ZZuWFzKj=W_b{x`)nbANt^RDNH6rbCp`3x9{LUsz12fM|t=<3{W1^t9ZCAez4DlB+mP*L7R5sv$)zU4@g3<*E9GDQ{_yOlnf{fuhL%N2Adg|iIg9`pHdYRl zRxvRKLgo=;An&~e10Fn5OdY&=IC(Yl0u&UYifins`N2Qh>v zh)aEjQ151<9(&X@E0Y<`*_X-!@q>M7-z5$kCdTvYi1FM;;t7`Zh(kX~OgZqw=SDfW z!okakkv=~jQ3nj40$&b!{1kl&#|nBiO)km zCq{a49=`f+V(`ZiBc5!B&w7aYX(jPQ%i8AfA0~#sH;D1xgT#2x+r;?p|3{2)sC`!O z9b5~<@JuGgd%sMK^jSj;IY)@`e15LRpClfQ_#>WVS)U_@|8F?%j}YU#cM#+K|3-}W z9dg{e9ryPg_aN#^x}Qso@Qouzc-9c(y>}5q&Nm(UJH+t!GBKX}Kg9TszW_5nXxuP9 z62J^6ikRhxorixlr*@7*Q-5%c!}tp(UHI3nsg{GB`(O7I@!=(&J!KL*voBlIF*cs{ z4Qo@LT3tO6BT>G)Rm%|PF!BLJOt97Rc4rSyla9zq_K;%Tzoldu_$aRSl^L6*}*`7LmDguhudB?|Zj!)zYPzof&_A zr7XMZU)MaS!|u+N2;-!?k6kDHFWWaG3=h~s|{-SFOefQkgJ2}Ss&u51=bN0yQ>Q5&JuP#aC zZJk|cmD|a2C5?&N)&E?0Ri`!9_eS=C^E-Vwzi%i{_WXoZ{=wcw<1S9lz{PROAvMur zxR!qxr~6GCW$(VadTeodabtO2Vs^sU5Rb6>=~ z6^8#0U1zU9e8r;X=4Q;inKt$v|Lq;Wuez=K_p#e5FI(R+J|495?2YzW7)iM-dBxkq z23y6GRNwXLr#gN=GpGCa@tnYR-zLORTcsT+Dz+ynse!E%;+v~~*kk!FdS%wgayuVi z7vQyJO?BX~FYEn%PgIZJfB(o4HPIsQM{dHGTj<9xvqK%vyzRdovw_y?w+&Zsv&w#w zJo~j0(T_fyQyR4qlL9^{j`%6ptwIPgSy_Eb( z@4Stxo9@A>M>^|rc`#pKYWSpyNh2OwHX4+4Q$<9U2aES zF~9SH!y(`M`|hYdZGQtsWRCrvla{Wn4((sH^ksy%8}nY?M3{XDbJYH#8|Jr?&m+u< zrl*}SGpwI_JHPhUjy8nv4EtU?|M&ShqcO4|GkP$3+QxAYlXIWqG`e$#I0m^6>BcXh z->ZG#&QufQa(vZv$C{-TRf7U&wfm-+u*%oDk-Ew~yT zpcp5#MpwOiN89wm9Q*sWb>PKL-^Ft43T>V^zGn*BX<%-ztA$ceIEl zq+I(NiTQDpdiRFz%HNW+%fGte@$XOnOfs}(T#+^AtG!k}&(9tFE2})RKU!oRINa%* z2+8g<{?%7@TIIesPCc-;6Z~?d$9Uf*)|e0W=5M(eE}{J^P}b=3&FRc>Q5!O&gE$Lp zZT?pOCf}uBIn?H_!tO!k7<=c}MQ!aGRrARvCRQXg9m0s*S@vaJsTc{kF|w*FS`4`n zhV`Gje9j!BUv}kSWbga-+AjWnt&5`w9CaK!t?=-FUNGWP(n!~-8#+$0@9V9MKF~8g zRA3j6J#*iG913;cdESUKJ__J&h3*`IG0@Wzm3Ek4)NWN^RQ0Zc-9?z^aiu>h^8Ep8%z~uvVwBmd zLw9}O#)-vOTVszPB`@2LJbn)Ox-5q_J&Ey|z}{~ney#GylZok{Oor|qS7MDmErBty zK<=-sihtP;y?4N>xIgKeK<&V_c^~Wz-HB%+4V_lSJ^R1NH&$#)()CoPZMYbNu2iy8Lq&EjDx1rc^5h z_1lf#sd-pHy*_wz;1+dueAM5VlUFcxaN0^Vb^%uB6|T!(pLKKSmf(iKt?-Lso6x*L zp)106UgeiLHj_0k>x#U>YM8E-#ycLt{YO5#Ed5!t_UEpBM?E_&ugd>G4qtSc`nA<> zn$@sUJvVG!*80%R!CL|w)R$E@y0fxH?7yYx$4@LYg1s0(D4MG5uzTHD_0nO+6%|j8N+dS@% zI_@m9Ls=4~>8DoDNnODmD4jV6m}|g+7jq=&=s_c?QR-TodvAubhv>S7{BC^EVG}>OoH=vbOup6^@BUt-_ z7H{;Ku~-A*M<2mkP8+XsXGn!LSA~?}EVGLc%1Rx|qjoh#w7Wp<7jY@n^|&{B;OD;l z{Bvr%)8lz2YRF~2!A?W^{F>^#g3!EB=!)QsyvS!^BWrs%7p8JrSdiTr7CH51&dbj| zi!&=uq@76}U>J-fn+=*ez(bnO9&?kV<2)ed=1FC5hK;nA8n^;H)4q8Kp6HJ{f_`|B zMyHC>?@|*_0nL0UAo4B&!<5&7hgn}x9-kF?b8!!K-19vGBCi$SR;iKFFh9W%yVgC44vH z-jsI;bOe`x$omo)ro3(=d@NTY?<=^cJb^HXq!7R&?^fKK@<_zMWBB;pB9HYq?8pR= z0@~`6g#ea!dF|I+*rX5l;g9~|Uqr3#3QmqW@A{vhp|ed^jzy&_DG<%72b(uY#q3 z?pNTVJIfU9!A}DV(A_L+q~o~gpY_d9+RIJa+>p%|R4w3|gN{Ylj9E*%K2WuQn1jTe z>64m&1j|xeefqa$X<}7tQyup0SL|lIlX-a*jCiI*&Y6}KacIRK;o*ZWq(A&r5+l$| zOFw1}FrE24yjY_U$t;I{m^9QGw8a>|q|1n5+s$<7Im9R|N)Fr^KYrB3H#qKX#Ay3< zIP??5h&abKTXtPb>+)q8jI&f$I;L5q{}I2J@D6}$o5?8?C!~)_ov_fPze^otHI6g5 zTk5gd>@sYtb({l(fAjiUbRl)GsfFae0(|OBfjAzZwjqyxc#;03gGC-~2R!C`WLNcGmS=`n!iHO`21GG$91wXz3pV)! zq4yc46zF~n(u^ygYn^Bxef3jl7je&aXTb7#p0;2)S(F3#3oSE?O5WAaawd>lR-LnT z`)fx{h-SXaX@QP7x2*D1I_^};D;Gg9`^-rTFfG0G$6mgj9n%p*b^7RBgRyFvW^u=t zficnlW@Wwtam!>8YvNdC{u3U5$12P79e+RyrrhtMGc9?K}hLVwgD z^|(ykump4_x?vmqeG!*{&U#1d2F^S^08cD~%wv3SU%G)OcaMgffXEYCu*v^8bc4Ky zm^yD7>#bfw2NUCazy2AwaVbYdnm|4bTx0MtPV*mv}sRA)_>R7kwBB5`c!hq)s zCAVPQyV;BKiIRBXicb}BwVFR#Lk{;gn5W!=&d6&7y(Zna zat_4`82}}!9=WurSOz^04=!X||&NN(RIerLq6)pjh$NmUY z9*U#V9bO$qU1#dBL!dL!VcbCtNaC|$vGfYfV>L_$4yTI=}&!u$ykMq#yduY~40(^eD5Wu9V^HkArXFLi+ zyI_Ih^6Q!`j1DYmT4pWPOF*1O8uhJo5SRq;DA0VK_L=C`@fTb;>95kI(ah(rEzlVtO_xTw-@I*Y^xZiaJ>7#2 zP%oBsT3bhUj#&MPF@uuToxZIRyT$fBjD3#w4#WOS(PtKnvNmFmjwzEm*H>eQj!J7| z0Q(>H?)63KdbG_~ifzgLncKf5fJqtc37A;Ps~`d*P39ARzLD7HskdLQg^s7;yY2YB3(EC(+g8LQ1cx z?3}LIbPlh>ELa|N5CEW@jd=GGc zI)&}WGCtsd$P-$y$sY)vk}HB0K7QNl0zBWB?WHXuWaV^?!n~cPPpI3t+O7aNO`lvi zVZvW!$4tsxpWLA%Gfkh2{cZ1Dt8^{)0ld@RY@cK2d~>MMDxWCIRxLcMGb{0WuVwuT zGlTUE*L<<*OH+SB>%NqBeN!4C-o{V({Y|JXHU0`2<_8?t?_OCG~{+UC) zUn{ZS?IK^dFoX7MA2~;q^=Nfo+1i|=_x3o^I%;WC>!QEglL8sf0-{&Edg>4yX2Mf{ zw$Ib>)0f_x3chLkM32!%^x8g0@SLglL@#*tR2dvHv38U&Lz2>|uc`t&K z1}1+X^wdDvK1|cTY#+9_1ZWG56#|&FnRcYv-zh+Ph7iD{=Xq$Y2UT%N*MzzR!K7Na zD#0dWW4u-S)kc?UCaOl`vZmE5wF^6C+;$}1L!C+8DQ(Abq|tVyPG;M&iWqIg%ZcGn zwH=}OQ#Cq+r0L#X%#|8qTk%2atg>XM*0`gwA|@KY zWO((kE!9|06wFS(GV-F~Lr3bqx@dfKe9%a0)AD#URyeXE*82?WG;^$g@gl&oiss_l ztkewq6Rk6y?tua8R{NWc4MY)_Oh(hDWc&&oOJ^>CLj<0@I@1Qv)EhT|<~syLUNsn| z&Rh)#WaFdSi&udMwU&_QAHhu~I`aVhHOfQ45+-8Pw&QLS-Qe}7GYb&DX?@5uSn5{Z zLt-FwCW^cPLFhdlPns#Irm4RA{yE=*VPcw6XBKI%>X-4&x=?`hBq4xFbDos|X|26< z_D@%WPLWXEXj<<{=ULNI)tBbXoz-bf9ma2Ae_50my6$3P=(?kI*!gk9OlMM10xe0T48ibuT_g~rk=BS*)xq3M33 zG#&P6&A$I|(4Uq3_3&3lihDHv(~+ZNzVr4SWgnV4j(YuXtmBY;Es4L^J~76xfaoNa z1yd){PAUV>tK+?QcgM8~mUXJQv}&IA4Sr{ii6 zKGO!$MFY=zz~m2vjzf_*;Q0H*n5LQ7g=ShYJ-l`y`yB-6u63R&4(TdSmk|8Y;7b{J zqUhkD1`izlr_&yZz;aH#H;x#3kMF16TR_~$IDj)>L!b1M!Q83|(agtGhv~#j(|^{^ z>^Y_JwH*iJ)}|q9=N8!!o4T&=Q)j8O1xj%R@G%?=8`YV>ArNdM35YzQ1)KbV&{+&q3iN!gh|AD4!>gfx zJB@9AhOrb^Uwv@o3sCMDA%N9;oXqbks8n%ic1}^Y>Km4~qRY;hb&B2B@H}-9=ZR7m zMS%TcgCVk+mpISE(LwrXolJDl9eCyzP2fm3}a(^v!JULfe)c=g@_XQ_7UJI2 zqX$7}qDNV8uY_L#2@|oYN1ul9Dlk#B)y4PnyS#ezFL1aTd;yUsv|y9}ap+Nb4{=}f zU}-Bd4mBL#$z$>~v36Q3}O#i&+dWE^b0_0gv$u#t` zUJj7H)v4MVG*z&%^W1XhEWsrUn^q@8O1ko9TC(qtbv<>r(&eZ~A`V?a47!pS5m)W- zFL(H#bNGx;t_5H|cjuv?f)m{zr8{WmOV06=x}bI0axTN{cOB+M7fJKI|2cj~@D4zl zJ?g_6NX{Ro1H)?S=u}?NZYNL=ni)YHZC&H%z!7^OIwr)e-CJhJ4g$iJjp&S+;df z*gh5e^_&xaZpx)OAg1huGFNFK=C(&bhw6 zWuIT;$*TfnQj82n<~IC%Uu}7ie-cL2mSD38K}XJg8r+xS5}-dq6)scW zFhd@n6?vb=y(zB^bYJo~mTbyX>t4ZQ_!usc7stIWHn;&ih-;y`(?9e_AkUP?U96+v zQJ&~`%3X!a)Wuv6oQW=;0)OlAtbl}x*wn@BgKPtnI*M&#hL7>iu;INfJPUhznoFgB zqrp!5_K!;!m%1-xXj4GlYsM*a3H3+B^&+`OGq_eG-GA8QU(-rQt4EkJDd75F6S&@2 zbbT2dsOz!)h6|Ka*2dCZ)j{}Bse_{Q2b%ek^N{8^^gLoz z@KQ&$s9i+*w_nkp>KL&7+poEd9FP4P-f3aPh&59Xmh6ug2Rb*;(4#?p+qC>1fe3Ce zk8v&5ket9ihNjgmf2Z>n8J_}DTD`iy5Dv^sqW9>Jy6;k4I(cyen2(F)Nj2GqMnL=#o4S-IFLZ;~pI!R~gqw3=M4reO zZ1M*}moiRMpijXmbQzjvylL?2N-rH&brr)H!9`sM)!+iN8r615;Eh`hP%Nuc|hh{HYvb+IHz|*=?Rob#IRkg#>9_P0lyDzo5amn%(O*E4G z9nU_0a>jkBPv}H)ZDh4W*yv9r6WA9h*A92CUHlJ^Kk;9=(ZRcLZuT?W8;E-8H`iv_ zlRC@nU$<8G7$Vb;#Mv+V&Q2OwSW& zC+ox#8`#-plIb^q&Ht0iCT1E4Kz%9j>d6OTgH^%>Szg&`^v5z?gNxZvO6ZfgPnBcs z7p$Xf;x{0V{wUAXlb-^uvo&r2FW}-k1SEV{fMM$0w;?YA9_2Ay621o9n|haZb|!ka z3jSL0tbl}x*wniRA$%T~{q?y{M);PAFkq2qu+*)|9|*n6dME`FdzwR=HQhZ+eFx)E zgQipInXbiY!u^yobF4{#Zs!OAOnR(`uJX`Vd1&@qQ$C-i&C2u@AP;-9 zC{-((z0NJob#*J6m#kV5N5RI1uT5+Sla)|wpX=%yzqqQUl^gfDEUc_;sz<2@i+e0M zlGD3oRi85ZTW90d9M50i;21Fi6emWdo*;&u`(9`W&HPG_vlUmKWZj-4S$D*R^ONGi{0 zH)V*kq6kGEW1x(JJq91a()H(reeBsT#I4lKB9ad z`AW}%&oHqsoB5V{w$!1^h#^Gx7c@66Te(DaYWJ&WqnXd4=lXwut7p}IIT`k8^LtEv z%kT>@>}Fr|3DvcTDABV6(OrBp=~Tw6fRwTdFif2lgah*!?I`-;g=}=xo)c`t^H~9r z$9@J=9_OBmJX5F6gFjOTZUCK$4tyH^Vz>l!7S!d_)Pa8iaR8n&=|4DEgaL~@gQadw z{y^x!bUQVubX=+XQcW}7G%)5;(AT&a{W6S9`I;Up`UQ$bagsu zhr-IRaqm2(Z;-&EZyf!yaCxGMTjyoa9}vyhj%(AA?&=rz2PClGIuGMzzK8W_SkP{B zTJ!Tdvo8zJ3eO%?yRQBD_C58XhN%r}8h+g1$9a9cbbqD90kOX}$988?f%fX8RC?%s zSVJdadi#PL%n%(6o_bE?GHy?#zETk{3QHS?iZyUn;mI}LHAf;E7^+19^^mD^+E5Qh z!DD*T4=?Jl8eGg$QkvRuugU^2LF858-jv7rPxME5rVjJA?Ki@GCN2Sy=WW~XIfh-> zfCo*TxDRwDI+1+(xiPkoeK7(w{HARhs&i=n}AZcYBjr4!j+)F82`sgJX* z&pg&wTff8!2@&(dXb(NXLtpHnt37lrXvQIB(XPDG<8C!;wVKk=QrcD9zkU%HuIFA%}aw7l@T6FXMbjJO#%O?@)inv72YDY+G3 zn0oaH^bzyE*Va7Vu`1JcHTCoyyu;M1H-OGWuXe!SHMj&s-x2$T3Cyvo1Hk>+nlB*` z=NZq5JcFffP5waWRhHKjeEefo%!dL@UyIq?Z5pdQ55=VVAk#*nR9-+KEyN=qVQXR( zetCv%Sy_A8|JZlFj&#@7WLx%F`lRh7)+dacfzv1_m+co}UUJ}AI)(f8^rcg#;yJTi z%?Dj3!hl5{$C6DQl?w-vXX=#8;qQ2LN?*1W!)EG~?hJJb=be`0SpoAKg-2}i2STUx z)qZ8U)o}dn*9ZjA_VUi_Jll~>#Yva?7V8Q>G?d?tbAG_8XSDW0rBXFecN~`Fu9s7E% zsu!@=56+`Zj#*ll9eS-LUcUIs5raDqFMef2mHpcmtE6LwUHIwb_FKoajER*%($*bT z@wKsE1-G|f^6Kctc)IG;$3xCIc$FUcj+8a>yv%Vek9AhW$Hnf<&fUEjk{%qnJ(hD| zqFrJyzxKB+RrZq@QGf8T70jv$?zbxb_=d$DW!tykI<31Zu)Q54?NLpSX=!oZyuJPP z;F#EtUn^_+Vb|{#TVwv|je}jj5{9#5#Zw3&@TjpMCYaY&OyzC#nWHe(uu4H#vQ3$O0;2bsW~Sa> zkgeM}(oUv7+ELSS@p0)x*Z_jh3W&U^V3_h^kVm~md1gJry^KtGoCCu=At3VD*I>%y znTV{vD39Ti@Lh|0$`jxjHA{p57J1FMH|1@HyeN2-C-ykyUXRPH=Xff5Cbsix_`3zq z3P_lU&3cY~HSCi>GgMs+ALEH()2b6UfNn%uT;Hl+k!P@u;(r|VocX@K`XJKXk3RE; zeJ`o8jct44SW2nHiYy|Fwe40QAv!v9&_l0#K>$;Uq$l@-BruqP6coz@c~E1n4xWK~I3<7- zQ2+AX0`e|o*EAis4K(Kv2#7yoQ)hO7=m3w}LUgr+1MhVq27>Pp5P3oiHu(dgGf}(@ z2&ynLd>R;2Dc~6qCIqZ(r4tz@=6C8is~N@8HT01+0jhkX&`bGt$}jfyY*Zz<-@e94 zneQ{QO-GPhemM?Ri8cOMZ3TO?wzDzryTmGQjAg%G68~IbactP?N;Qx4kDNzpoL^bF zb4cx3*iCLo=XT?%u@(=6|zKd6sP{ZWCe&vL=Er5|3b$EM+8mJ_`d$34?e zK;(JH+NVGs%LC={S&_#%hh`an5cC3E0wQlN7-sn9LtX?t%44`hUJUo9e)|h(^Lyo8 zUj4>7NeTEB5P!s`eq*0T1WejWy!hU}^jkL^%y0kMc}CyAZUgXFEV=qGu1n-%4Bp z5+-6(&u)Nlj(hZ{XE!5!7l|-nk!P^ft;rt-|(BuAk%EUxnWw zc4wh0OQ-iapy^(UtFN}TQkPU`Vyha(v95V#lbXRzmCDkXHu9zO2K6fQ0C5DE^E|0j zIB%Z$obx*?96Cyzrbl(lwO>7Ye&%}?bn667vwMAG=Ilq`^^A7=EbLK#hMf-!*eair z^nEgEpLt+>{E6za-IMKNJEutRk9-mC5AFK;p$%3^&7~u&?De=~KkNk~x77?zE{R(e z2lvjzS@h(EcP)wU@A}d7VM(iG1A2VtsZ-1r$9>UfM~)m>7F!%Eww?a#l5lU(ap#k} zu}%v;$G32`mbE+jL~xF~_g_5vG<@tvbg8&CZD_`&!2P(XIr{7~f2~@;^^+HV`r^xJ z^)Ayx_3^Iv&EU!MC)kcYTEqXH>h}jFfq+E=Fx^c3`3TBI8F(x^^uvpKbQ&&ZVbSmV zaNk#b;kBb*g*+5JCC}9FUOT!Qey+hKAmQ`c(FY+f0#6K|so!IuP5nLxfz3p}x4~Zm z&kFDx3B;y;k03x*VD_iqV+h|IB|-m)JcFffP5waWcQXxBsjJ_5EIXR|P{Z-t(JbqI z+0ouH#&hLWz|0S{Z3Re6zY+5k>w_wB1g5*H4?ML23oegh!=|gwiEOmCo0?lxH=f1M@lEI#9 zvhF^VYX!b*{gdt&nOYdI$0XMj7ANmMgjP-G@S0zYSa&GL3TzHyey?wW@8Wgf^Ip~l zTV?+@$x%x3DC>&CqFDZF-zAN)bYCwfA5i0udL8g>C4m^9`bC$u8~f_i7REz%Y3Bor zPurz;K8T>cdgf528dXFz9#yZHW%x0;8}o)y#Vk_uhNr9FS?YJD`qesu@(884j6R*q z{zm;Z*B{+sbNvAJ*qmJROFC4{>mR621uS=_o(iHu=&P<_xuSlQy5=D6nT7%)uL=xP zUIiYY{$Sm}XX%f11jk)WeapRSmVhT9@~!~Glve{G5%4I_tZN!Tn{~}f$TRb)yvy5X z^AH?b@vMOOBi6-RyUam==7HH?UGojpHE|IJEbv=Mj`WT!nI!)JxYABLEv6 zyp0%{iebt@y%YiFTw=DZ`l_Gi&>i*DJmU2FNi}f#t)DK;d=7EEkNRn>I+J+K(D4yCnWYyW~Jge9wq!h1ZUg!HMppYSYHuJL74eK$;8%>$*LVmq}fB1pYFq>)0O_gWvw@x?a?E&GHezc%)A-`G2dr zj%lyq`0G06slMvEG7$}&k88Y#zQjXM^U$@R8Ar@xtoyF?xPQ(=t9IA*o`#ny-KghQ zEK@a|(GD{kU~t#-N1Y9FRn4cC*&IEsRJEa4_pQVGS@+#dj1PR!p`Rp1-M7!-A0!^? zthYfO$T;_7F3Y*Vebt3C>5jT^4soh3Y{9`CYV+cL>%!=T8MoESbS8A$YMlRGxpVMk zd)CmCxw4HScwm#|IUUP;DjIhcp*qHT&3D-UV0&jW*2*>@!32 z8gVvoBOoW2E;n@>RFeYcEmQZJ>#*sE7j^kmT&DhsgXXgWBF{T7z7!5D%e1SZhFy7= z4w zkHnTVzujI@zoh<=`t9vScBtnXD_l%V_uu0G(Yv_=*EU=makV|y8|m#b;er@qL3w|z%@7M`0NTN!&Iwz7G0{mS|$>cho8Ws(1P{Qdf&5r6UXc=~xf z`8=L{9#0n854HcUUBaM4kb1js>pS&)pZTt*8UwV?zoufq^OM*aFS%?~;LoA=^6(8S zef)x;joE@lxzXlWs3-0(ifxOL8^LaM*6v7cV&_@$?TfSQ({|}zve0{#s}{!}!JMSf zYeffqmwc`;*b@&HCZWG0)|mJATIcvm=Dz=7>wmUC(B9O1PVC#Urr0^y*ZjSooCsvqAe0E;+xB2;m(l#Qde$?+M!yFt@O30(pu~mnwWtn z(01UsjCu9tzb~G*J|Qi@vj0&u-O9u>a5t{%ywamjEuM!K%IES*&AN*1bEDrbZQNjk zlH>02mllQsxS3(1el%$|IsYfLS3c>Fy`7}ygx1wLdy84)QuL~2=uB9wD^|^I#3p0Q zRwdGAAUN7*T%x{p<+ur^Z_FNEy1cb%(UMipZiJ3#u4+!LMyPXynk;9bkA%hDlgzaT_jEUL^?DjRGR?1~5!{hm7#Cyonr}E@MnH+ zr4fIe8zSk!@mlk}laC>9rbpg9Lmtyb|= zRf`aCja%0bZ%qEjWsCD245wfH@~s*;51nN<1tDc?r~GS!Rowd;Gbn*0%Y_EfnwsLg z&UE=<)$XVKZd`u2^Z7Tlcl@R#k;Sz@>CdNA+%G?!ldI&dbLE*OoAUBJ{_~XolrL(E z6aGGM16-DRT$K}Ztq0%p1&@2PhhFZX zulLYxpqZb>;bLlh1z3Rcr9Rq#`=Q7$_lYAg-8*pcdB*%uVTp6 zdo_(d&FV^{3#`AS(WhIdLU>C48P?e(9N_!U_0SX3{6kYV>!zq`+osG>b>|qOrD_u# zT6SV=itPx4G=2SWOJMs_EZEqC=jc5g<<+TyGx|(7 zIn~3OC8j1=N1LW;%#=@89QJ|LpO-eV(1;pklWMKvAFuWJC}fmRBHnYNmUXj(pLQ_y zkRM9@0PzINI!HXxvJMeX!k#C@s7#n{ITz?YOv<6wU?1pwV$ccV^K~DoABG{z1~I%? z3;PsJZ9UHS95EmmokjLqt`x*HWc%F?&ntN;d&vWO=BSYwgiT(EZPRM-xllBn6?Ss*MzTw*N zW$%o5B!AfMcZP+MzA2yT4SoVU>sS2OUUSY1AI!yN_Vq@{bf5y*=S^kK!_I>P%LsKj{qPFonuAMc1Ka>&xL9Tc zMBYp=OnGrQunbck%c98RdiH=}bKVWwlqc`<+MFy$Ew}{4AF*k37C?A6c!Qmb?`1d` zHaNM!y`W~hRQfj>?6hwm2%D2}ngYGoQmM;0{&PW?p6vgPxU%$jpKH)`Gv|?zW}VrR zngw!HnNZ~e6;!I2)U8;FZklvf)3SvS#qVH0aTzgmX9RduuA_sI0L)+1!Q(HyXoB9= zJ=4A2&(CTaDeT%EX-AvQ-Ay;#6wg( z0`oa|Y7c1N1?xgz4NlFA%+4#|?jN~$;D>nP1oYXZ`m5v&?X)gAVGg8HJek&CGR*{_ z3KV#CVgd3h%PX>QnohJqGn-Mb5$54C^MlB%2H(_)g^)*GM0sAFsIx5`0IP8&)Sdnj zd7SfS%H#Ub2zZpoaMB-fGcHrd9s-?-j-^d;9sCMNn21ds`z(a#gNdT9F20xF<<+rV zS5*bRfXEYCu*n|?9n1JgfyAEXuw9<+o~8B`DRm#vG`~j!V>AVQt-oYTmfyfUMIFq3 z76HnExu)F9fZ6Ud(?Y#R3R_AK3x~~z>kL9})2w(Z49+tsa4^56ueCu{|-ac z9&Xm@V2)upEK$q@VVa&yI@nAHDWw%i7*ogP8#=-(DA^aV$4ql081td(wrViedp$<+W!WahvB2Q?+CVwDw zFzxRY1Xa7g)MYRgQ$U@Z?*I7LW-?Dv2MQbWb$ItMoA;6kAL7QV%cqDV@CIDd<(#}*e9M3G zJXcY=C+FSbtIm1$x#xd^g_VP+>zfm5Gb8O+%RKo-t;<&>T9z$B!-!j}E?)=U z7xute&?l4bX8H(7Y4+-Fv3FUv>4z7xyt0=~efG5D2BbjbEdpigr9GhMDIfYr{566! zb-e7G!uP_=aoz9bAV^EJyq!$)1?wTr2f zXMryu@`M&_@&`gEGb}04XNb1B42ez6piWL7fyq+q-s#G3_Brk;nT+WaaGxd<0*Hko zF!)W(JJiwMdA-oVtLvoLxQf^)N$iH`yV&6@)0JOJD7{=)$M?43;yKCdh>_`N8=L1K zIkxW-Y?7}!PW!ceqnXcLOX!4i^)B~w8@#%;Jo?0h$~*!&W7?clB>&4O_rCxzn7dyccE3<9SBx+=UX-1{-9O<&fbb?1$a6! zqvnXU@HbsGN7^PI=$dh)czyueKT{YTB`?t z9vYSU^n}e9!p?v^qd?8$`QL2YQtvUz#TKPbVf+e6$+{E_oi((}LqL_{30VBGT$uW- z8+t|b2+U38k9u?tE>oW!0L^y`$h*AytN;$Qmj%Qhv8m6>AiM)S_Tlnk_#_-~a$z3` z+BX6sPiVm=e<1Xk8Al8q^Lt7kF{V<`*FJJk4=O#FR@6t9%8#z%;n17PpapQJ4iOt} zeC4DGe~ryHX~Lw8&scv!X98DuoQ{zB%Fj*u%Y(ar7Jp@!HD=7~gIlw@aR@yDGT z;y;UTuFijA_$#&XJ8mqTUwh+iF)OlR)g_%ji*Kn8f@?*-am^j8HqXzu(c@X0m~mT- z`$*m%A5rtmuG?a7cNLbXwagRW?V?7)s^*Em?+Wi6r20UuNcb79{>rrn-PmTIi5)%a zA3qS^7R$0f8&bbKRlf0-&DPJ_w$GILfePu*jDl8>Qi31cf?nx|0Y(v@9WhM z#B!6d_(gWK=HU@)W++#SwOgZmlCSN0AXZp{y_uu3OZ0c*2jVwZ@BL+CeBy{O%W$o4brGj+gB|&mLZrZ(pqT57{0+yC!0PFV_2v6~VO|-!^S+#|C`aaGV!)ubriQ zg>0*AR?-?jJ^5shb;{YvsNx2}{Uq*(sTr<)+j`GvYwI1> zwx>52SGcWu)znyERrtUeC6kb{YF_Z#39C9|AH+`YE;wb>>`}F6&pdn9x7)+Jt>V+W zhn)h<*}JQ@HAL*U>Wdp18{TaHb%TD+I)~x;cDqiAeO)~wNQ3 z|IFY`HFi_cb+ve7nMU9GTAsU7C`{n{aaE_U3ruszkTaeewl-^BXnpYJz%6_}YCO-m zS=D)k>$2Bp-5k0lxFK*Wd`!(N^M58MudsUX=hQF!n|h7+Cv;C2HE*<8%|B>b+>~~@ zD>sMW!M|RnI^W03T^vx746gK;+#3hAD3$1&Q-y8n>+CWeW8zsl*jae!^SbpP4vymR`$AD6$6HekB{K}sjnKlQagEkzlB z>1QD@=g~Hv;zkm4VhREnjY^k4MEPghXwWp%M+0Lc1pyU1CVgsJ-zlH7Q_d>?Ugn|a zgJ$qpriLQCF^_wThhFZXzvQ8B^3W_t0t^q!fdJ`8aPj>tgF_J?JAnn%cZ=rNX0B1W z@YbnPc^H+L3XeZz7!Yao*uZWNCV zkVI@+uPZ)=WjhCjZ8kAF#a0u;I4E^!j>qL-5Uz~)Y@N4qB9_%ax=61bC;!W&!T%$1 zv7URCQv$t&2+V;n<};3?RS`o;u^))zW;2OVo|&)w=W0DR3d_?JjfiL5bDl#bF^DO| z&=d0&35u)6un-6pJJe+i#*_-S_OZ@W}TjGz9_VT~GoH{gD1 z9;Q`@)rZLyO*wf5Q@ObWezBJle$(std_FS?KUn3~&|>*U<2H2R^s$#&Swpff8|2T) z8X7F{o$fm`Fw8gHH^MhEQ0N=wFZNmER(xsc%K8T2m8}}b<&FlGHI7}u*0_chPA7+6 z2h@DD;We;U7m7q$oje(|38=0V6ycZ2F7=expUx8cOgd!We*G~W_)Hcq0_8D11Xykf z6}Zg0yAlt~1CP3!et7YH({P#co(9dd5)gTpf?>+r0D1IBc?^rly9)R6O}MpQ!Zn{a z4v4(DpiOz)mm&flT>?l!1j5ZYly`aiUueU*58+AiM=WVWfkz;`15DaS zAJw1yAaspcFNi$KFu~*xgl%EQ5o3k%v)X;3#HMDjKRMmMo`=C_G#vkaeavI*zoFh0 zVEPvc0ZjTl4?W&PQ(p_vf2|O}q`%;yX>$wE-CLKZ;zB>)20u&#`sF;3n}G$$vy^5? z^*@QC@YbnP)i(1CR}M;MI&EB^^$PEOp9ZVm=c#O&KHR(F3}OVbj2Ic3alySRt|f-i zoggmI>CZhYZUD`*VB3f>FM1s@5{U9RFPi13uQOt2(jA`W5W~~>%E^D#_~@kQ1sR_o zp3qs;t@F-6>mji-%bwYiYbQEYtyU6j5i9^E6>*hhaDb!y}C<%?UI(!0b`{DJEgJDKb=>RAD; z4v)6al4$Fc!4uTGvVG_es`)7UtPQ-GxCBI=*FNioJeC*AGwriagJ%6m9)Wq78> zT?vM1OXS0z7kLbqgs%nnraaDXtpZO#0@pwu*9!@Vyng}1 zl(!l3V&G98<VYhGUk2)YzniPI56&Y_mmgOB z7yO3#%0E*e1zg{o?mtJZsiuF{1%5R`Yx>Xi_|H{+Y)n%P%!w)Bdf#;UdCGq(y*17J zp&@lgn(Kc};Cf$ktqEPH8Xic`!o~12uW-HT0$>5U*9!qm+G}rr(c`|(L(6(rmMN}R zeZb?c?QN~~o$fHHQ<|kFaqEv}sWsFRQoZk~bcfX`%h|0yy!N`=2bP(kZU{>^#;J?g z?-e0NB{I&z>^mjD%E8R1q@xbL*um#IxXQuI$MnaXKwReFi4F$K%0a&tL+73Nh^0``vnet z4KZ}nYKNx&Wk14ZqPt2FQL)22dJcY$>&p#qm#=jNi%h8mt_kA8TOo{o!IEDIN59xj$k0g*Qq z3{xK0Dxs(;d3;vn9q+t$?!OjsGv!yZEhea)EOwr?^x~p21SL@*WZcVG}?d8Nkq`;8^q6OISg=IfpJ-};}O{_b#~sHG@2a!2E?qQ#A|FLnl<)9rQt zgB6K1Rz9-{XWBR7O#267Rz#o2d7x_$`VKfBsqz`Wdjh;}?|W&MTXP)}sxKGjSt`ruKZD+sh>Xu+LTAzrZ0I{c;s>KX!@f(hD*X1 z$Gt8hxB)zbYmU0pKN7x$AkFZF5vVA5s>}n6yj8e2_5BghlW_^iyS#0{GB~UkPr%}j z*wpt?yeI}H+aCNLzL(gm?>FLmZSVy|p3s6#{y^w^+T1B%=u$v^pYE>r#!i)Q$tC)k zzV>)x9hdU|KRE9la#%mmW*1;Q77GDPdJHbc5${=FOaK-jkMo>T?#NkM7Z`&QqCwoo zkF(RFqcqZ1NQoxV_7BGmY9OEE2K;8)>WraLc(Ip;ld|=xS2>m*b!g^2wk@h0n)2A@ zaK^?Ht1>>{`GSnc#&6J>%B^$sd7(jjO-Ch8w=3WEl|xzT%!T`aBQ|@U^VQiuVeGwH z7|*hYc+O2=uQGd+(KEdp!B^jI)+G@#9Vi7>a}K|X$&vZBd0}o70A9p#Co01Q$92K= zftxXl@p9E23*L#XSG;F8Gb#Q)?R%z)K+w6V08Z1Vj(%porXOA?O-J>aE&z||Cm`~? zeWt@8k7a@KSY||?cTBqtZj>n?^5%kJhA#?v5%4IF;SzZ<+?)D-ALvZ=HUFv!{{xNLI=xYo+ z;>y-Kn|X!bOicYf&f`vf4Halu`ygrSJ6gJq&Y+dIG;3eWr@bG6OrFuK`jJ30Z0u(d zzS7NT2r)mp^PE7lJ!b4HfH!5hwrWyk#$&dtb%Lkq;^@v>Izo2XF0g%fa$&4~IoQAj@xU@Az&iB=>tW9^HB5%TPd&`|7l67@P=Q~w40FA|=uP_JMSV97 z7qgOBXl=M>S_z0euO6;6^!i8X;f)YfBf@}1o>vdg%uo-%3K^N`;V?cb6Ftl^nkfAC zr-%0;;I{D{y7(Ck=ho!^t@LoJ+#SCjW}fOx52M@L1?CgxGXc^}8^!_esh7>Vi#(-p z%_C=6ETM-nUl2!+s3|_61WpL*tvobIWq6{G%N`49H> z>}a#Uf_FZPa}6~Ac#b;~x?eVj)qAo7G3Z1M-9Zb|R6k=WC3J64}gsRRb8%I{J-UGW&RDd=l|F#6>; zJd3NZKALf<$CX^~xVhLWW$O7XweCS4q3kP#09N5*#gTTlr=nHO(#P4J*EizCGaUA* z8VT1otZK%cmXK;Sw4}DZ(Rqq>&_ukCb%gE*E7S=)8+HY@-i~z;frsZFX>0s>uhpjK z3I^=QQE!dL%)#u35AEf6!VtWRvnhEpH0vR&>=(&Db{%hh!h9gG0XLrdWLn;y@O7#t zfm=j80`s|(p&mK9f%5lzjwaJbKs1fF9(nQ@ZIl{3$m}ci$kVtt(_Z9Nfp6;lq#^I4 z>XCzZE{01$!UKMN7#mMm6rnZ8wtc_JyM7ORe{-GJ#r1gceRqB ze?*?aQnx1me{(&;Jk?h{a-Q+QtOv}rAYFxvalkypHp&cO0lKqoDnMG-0-i>TJ|`0^ z4pPmP>l;_78ieH<{Y=+mO`tm9NmU}pI2^ME;#r4WLyS7)ABpkOOzV&;_-7qLIYu4A znZ23q=TkW`<2gTn(V5a)hs<5y;s0~sy^VHY)BfJd4r}bpLF@{;XA8LE5 zH#c(Ujt#+_S6}a4n9r6@(GhFjcE$Z!??UVK-eAlcSNZzw*%R$4uRd(&A7I_^dao6k zSo1UdM(oepoi)!N&dDMF&@TFiYyOVu6YZJyp?z1Xx&+*OJ`>pd;$fffN<10N=hGq1 zi~m}gtuarM-udU=ZcSN{+q3;Pd|Fxdk6wGYx@`9to04bRcR4aGyeSxYy*HYlbvP&R z;$gqvw`tJfoNP#r;<*UqWm%&?nY6}zGC8=X%4)9;C3WowIZ@vxtLSHV_VwQUsDIPz zy#?Fmc0)xSupj?fZ+_xuy#+DINqp9sThA}>Z-qs>>Sp^Sy!1&NuCjawq3G)~3?<5c@RS=g!>^pnnh9MCmVcoP}*@ zfxA#J`aJt>YF?#(ZcbjQI-MH7XrtlRAI~dIn~M>FAfqpESZ!YJ3GMe|#z*l>or#8( zy7dbOu61@Yjo;sGC~~Q@ymji+sQB3D!8(h6c!hC^EiHBG3y>87UqIw}`~8mK0qR7` zGwW3E_{$;4ONcOFkw@KX*3m)Oy%F%db!rSevu(Bjy2sSx5U&8;@$~1y9q?zqSNsuc z^`*UXZ@f(E)Ft@H%UtQHI@(~VTX_$Ofv8i>I7-Eye(SNuUkbG|eviN3kL5p;e!p_} zT{=HZ^3a!nW}HNDv5uVzEWrF@sd8zI&o~9wSy7Mbv$Y9lvMym&>MXXGp&MPI&GB`J zKzA5cj61f~NV7g=e+I{N<~#HPV&qk) zjn>-K)S6NKI&os=YtOgojGR`#_Uo%`zix!;ICUG1;AA-OMpAXbg{u8S>>Jv=XPfcL!H@t$>4 z!7HzXeTRP(m>K_8{Clyx@_nVjKl%TdKkaaAX6(M$f5)o0Vs9$G7bmG+l@lzVv2W9$ zKu;x%4Bz24>*85!<7=y@B|jT4>JIqstoHwMEA|fiVDGQuzl&|hvtN(xkIC~NX8UWh z8R{wTj2Kb#Q2cQG$Fa?^^4gJcgvZ)a9glq__LE>567R{W>ggI@h* zd~4iaLtnp)-5!f0a4iZORSw+yKrU zU4M!EW9h9}o5+Nst{0$=HS7J9zObxsz|FhPu1X#R=6u5%S@3pCU;{?_{IxIZb#vH2 z(OC(n9k_ww^FMjvWp1W;0>}KE{;0cI4p#_`#fv^Ek4H=;K4&UfR8>r)-bIm+Pn;_!8 zTi5yHJT%we2rwRPA%IEKMid~uR0v?wZMYa*=0VyF8*nc`_iaJ|leTn;Z%tVd=_;U3 zcHL2DFW0STXw|y}IKG^t@LXT@*VUof?l?BCYHe*=wo;KT%bJ&`T$GrG`V~!vVPd{_ zWxTa%MSS@Zp0FqU<%zlkS|I@DZ`vPGVtfSGtkDjc?a<8*&3+-eZv^Ie=H0}wPc{=5 z=(0jNd5A08Jxpi%d(goT5ubs5kchGGz&G*SD7@$29Sjj_e*v*`SgyF=KqWB(>DoD5 z_zO#?zkPuxMlZ;?AK@Wg2-EBw*b&oCvDbE-VHaWreLm(BTIDN}6YMhVNJ-0uE9tH7 zHEj>vYL$N`IWl|Y|Ht0DfJarGd*gf0OfDobgo_X%!Xy(QkO&h3HVDX&%O(O!ytKy) zZ6@L33?M`@9`|FUBmJDVRJ@H zZo9P;=CE1OvS&MOJ^k91dm0a$RXBgYyyX(*4frLMvtQ4v@?7Fsn7_zf_r1n$-1x)$ ze%`{}lh%!sZqJ@ZZQ74J-&(co;F8`UshA7@+~eKYc@tz<+r@~!2{_}iXFEgP_K2k0 zO*%0faa*@G?Q5O?6T!X4e~B+2Ff&@7MQq8d%6PULSr`L}-bq=Ye8n@pr`!vPQ}m9Y zbt5FpjRcy{>V1%rw?f#o+qZzkjQDBy*&OpTUnIyDpa>Rfd%6bgRRiqUo|1-&a)<3W zKWCdwXaS<;qvSUqZYsY&f*(ZDDeZmynJUVhtI5~~$&Yeh<<}2>ZrH`Q_se0Yw)bqT zDVHRGy@2@kp6^L-ltj=a9d)(6KZ*c#!SYP){Q)G~!t@NJ)-dW}k-nW&uk;6b4$KWxCQkmNB;X>iB?sCPY6Md@qQ@XU5@k;_!+%{IWP) zEj#pYb(}lr#wF1Gc8NeI{%>*kx8m^Kz!^W5dG;?Jgf4;Kb524uchOy=5%Ge_2kR2- z8e87TQH8wwPwp#SxpK{>4FNH2A@1d%Dbah0#8f4y#Re#T#%nyNTNf7D!He0g$~(>f@#G5M60bIppJflY2*KgI{FcABn0m%@=`w+?LKw%7r1tnhW-M}odXF~O&yQO z@UAZ2S9CRX41ie995@rrbQ|dYA|KsR!I|eue?mU7b>_A0lEl}xDaQawGlW)va-XjK z|8H!4*jeP2A|I4l@*2xVj++PPu-m6;oUHb3q$Djuc~RS?RE!5%p4l#uhKf>iJ`{_X zY&Vy}tjb2ok7tHde%av1@5ztfN`CSCm>S?#4<$kJyBroOKR5WfVMl)CEBV#IthSqP z1Gnk|3;?ToXj*)`nF9xoGbBhl>T0{$0p?k-WV=a4f0<4U8=NA*v&f|pEb6afC5+M^ zB7@Ox#_wZd81scsmJbml45!=I#Q0dil#Rkb?IdX#hXN?JlMt5?pj%!9v(ky6+O-kKkOzKVOWIQAa;(R=@l6-D@5F^HR_3g$=ni}_bwtM=%ds&@XwJHL zdg8K|?FS%6_F^1zDA6$o%d!NPD>OL~p!uIQuCT8ZR7Mq|E&fc-Au`=1NOKV^RN3sa^(Xl)0jh@Y zDLA-cM}78SgmAfxJ`3HUnx6OoM_po@G2vkVh;RW|y;JQ3Mgj{ptiFWAL^^oN#% zAsf{+vQj1L-Rag5DNii;`0I#F|AE#KDH|C_mJ!Or0_YN09v~YjrlLJ?yCR~40{eC7 zpa?@uADEv-`k-J!J`r4zi}|ppT%@1MTApA`!Fa|wuIY)N&l<@Dh?9$$7cbHr~J8_t!DbyBVf9K_H54!=J`GSj%8Zzp2k`~&LC*1d7N94{!5+=dFYC}AK@;a zM?;ft_)^N!BiSjwz8{710-j)6`%7a+R~)QZ(yOOw6CV^aRnfR^@047&bz^?5KU6oO zd{5&auv4SF^OwdGNQ28d_iTU7O*7jeob)C>ak-! z7&D^c$;x@JpUmD-Ip?M4deT!$D_$SF?d>7jz%ldmx}AF(86z#%ijy`;#;Pvh0cWjn zarh6bJ;6g`?!!FWqkqrLvgRMPg3bNc>`iJL(&J2L==LG?mIbuQb)f#w?(Q{j1~-?b zzmt-35z<%lFn#Cs&)@3_=C1bmHP15tz~OnaCnenq)1#Qhv}XC}Q~ut%z>dm!e|7Km z1b&G z_p~MR`Y+pi|MtHgmp=UIxbC^aE(hf~oBONx_8iX(xP!yT971|(xu5So-!5^_9%ms= zv@NIXmv8_=a=?8=Wto95iLFEbYHc9Gd?NM{#k3ie4gbt`pHe2S;a@j+vx%Rs^Bv45 z36{t@^^PX4_pvREZ~H4?M_Df0{=b0NKyAMdG-^Ba6!=j_$G83Q<02Q@)&S@v$neFF zi+%-uZV<({{dKTY+x|5`25N)j$3?qAm&mxN0ukrj1IHWei!*$T7vl;R5jbMc$4U#P z*+8J$4@TQR(75Q)NPf%Iv_f*aago{=U_2Q=3y|mveAqaNWsH3ROdmyneDWih#kVL9 zFNwov$Ke%mcy%29#W;KgaHg^Bd#s6bx4IVV;yNFc1~tm89=86#=9Fo_4I67Wl2YBc zRI}lR+SMzplO%FB&+5m-^j{hf4$k3yhdL7GDe5Sczq0McoE_%yh9mH#YoHD~mOauP zppH4cRHQTQ^Qa@^0@Pu@jXLJ|nD<;0WS(+v52Vq45-JbVg?pZ=sRO@?I|n|(;f>wDUv)W?z*r3G{&JKhChL{MY) zwM5G-%bjRT#Jg##J;&l`V}$)#+@pfrXClToFti)I7Ut75@1~}?lsH95d$m2_TaT0` z%tz8t5wCe`1PvgaQ8t;ko-6XRrz(n!3{g| zW4K61o!_hN%LBk?KuKWO3GwaAQP^!1F4muW?igp&+((O zGHiT%O~@N0qLeqbeA&2S&6)(~_7i`Z-h24CaaSwU#14 z1NkfYOI`Xyd@$sdnupQcuzWk+JU-LVf=_N9pLsvYJY2W$C%Qm$ELVm@dQS+=LOsFrh6%FS$i}1AFFiFgA3;8{4Km^ z`=26vIx*)hX3AfZbFc&4!OZkIUEhsmUG2L?%Yao+&$jH1n@bgWG0f>${8u& zijW^_-7UcU3hNB>g)~yWRlv-mCgtw~Fq2LK=?Fe3m0zjCPnEy%bE%KwyE#x2B)`jH zq4GQ3J#2NLQ{`_j@PXuD{8%?1kxFDP^?5LNgO+oQR16>E&#=KM0&l~CZIA@3dP*#+ ztM-E-f8+a$QJ)yTGv9yAI7Rc5En5^mZ0@ukWQoq5GS2ja^0*|*-tyOyyUN_Al*7v0 zro6$}s--ca`D*avxYth|bC4{*ybDvvXxT4S#=%~?17{gg#=)D`iVc=$of#(ux&|MB}-Mk`i16MLiZfU?RH%O}3n=^;E*ZWxFsuBC_+TeN@(aL1?aYCjl#CeHgs!8*T6KNdm_^lo4*eX=Oy zq^B$%=-t3r`c$#+HcHPNjRM~djHOQ#^QTdIWTFC2l(blS>)pTyBQz|DQQ*6QvGmqE zf$j*&C--h3>k!`!yei_CRSvI>!j0*+kFEfIFL+xJ4S~Am8tEQ%55))z*0~nf5+gXU+}u z&fiD1$5Og@7m(@2cL8@&A8)VYyRA28IFIoo*mLf7A9Vzha)Eu~Z0LLs&`mtgk{?`` zr#;u|58{_(tjwWGyz{N*zMwQ5!!%ePm=U%DS*Dfpz@p*a)8J zdw`2w@FZ?6Y6sSwzQP+qmbCND?%vd)TlZxcjm9WrVmLkM*`L|#NF9H&sdr|een0m# z{@(0*By1e5EH|(_?a+0&+lzh8E5mOFuU~awfmX2L*#5xSFdbIA z%)2e~z1^C-et{diAa|BIkJbfSDnq>oLklVk4lTfo=awIP;K%D@FRIw%&qG`mc1Gh+ zff=FlUZ0aUX6|XUVi+>CmaWDXu`{wLthH%{)nRuaH+aNM?Wzlgk!A<~8p;#v86z zGkY8v%PO^Z?+)!KbH6^qxPH}}!7Afg6r>SecweXOFv7!73h1-ewgsb;Yru;$m>kT>XZ%pfP zYVVIZY-a7gzSiyEg5Aa-_kI_fNcAWjNn=y!&R5X`vO&``d`Umvq-5 zcE2`V9rVQ$I0nm-|FB@%tWoG`iA-AR8o^nTWQ_^~`|mBT{qSI)u5S+FBNwV%)O0v7eq1Uw34hD4xCzvBCq zoF`d603GSkjf_AMJoCYl{TV8TkKth0z#;-XXMTMIi~6fr38M@Tkx!~$IWiJ3tDnj6 zS|CSP7B5GcBVwcCvidJ;HRz3D-9eaCyCc+xYuX>F zWB=hu@OPl_perN#HTIhI&9!S1J&#s0J<)#1uMk#1WG;|Lm!V3-K;?Evq0xWRG~|B{Y6s%!-KMp+jywgD`or)vke|Ih<>36h`0rLNi!MmwOU zkrg`W6VoLrCJiAHL>wq@Es(itVFR@b5OpG7SqIrJaJ9z%=}{tV`dF#E#t)M4Q1AS^q3~C(;q(_XPa| z4sO_!AHya2`C(S&->-ltBL5hvdeBN>90}A_`L`R)6WJ3)`8-{4u>K@J#Yz}e`%hl} zCCB6mbAstdWx>ba6C~xKTECg!ZYai)X0Aa`gf4-0ke3v5(LF(SMMRG_xHh=aa*mtR ztH5XMQ!?C~OJn{I^p=X3?r5lle1%+{R{A;n42sorJmbFWl9>s=>t)}&9V1sW9@TK` zy6d4UO;@2cSK{3FMbp)Tb;<<^-$jEssPeM_xCHhIab9JMW2=tq)xY7yU9Af;Gs<4f zOr8I;XOKROzXW~Z((I(cf53b$FCv}vC zLECchB=0}3ugLUg*;i$++K;EqA{0TXvT`K45iHXz-=v`;Za}I0s)4KJLGmkuy~-~K z{IXz2eyZ%f1~~aiXn>(!BG4s2?i*71@t$-y?8uMdlHpqkvnqSv2A+uQ<(}f3Kr2Cp ziMlF#4<{&lk03xk$qc&Wr&tN2YCjmVm+27&nR=ED`;xKl$>Lr2{Ky9u&U~_fDI0}> z_5)!!E#k&9HP9SIq3zBxLfNb4h44q#Kvn!k>Ljk7iB?c)jFH3?7?i^!ZJlwUJSMK5 zfAQIP1$Cu=yFR#4ba2lohi4@I9!ZClsWEbxWBuFt9!Y--cDe8cT>UObYf>xUz|Ht} zis<>i-2RYw2iJP(Di80GJk+>qWhvgIvfjb`rjZn#1J&wNiqzQw6ZZRX`?Rc0@j83o;Co0)&A zOuR~wv81754X%Jpp>U;su=&qNZLYH*ZRhf;8{uA26nT7C`4Zu&a5=Q9{k-?DJ7RWl=|B@lpNgyK(RZjK z-Dy!#W43W>J}{&lUrHSl973LB?w0Z7nsK~5XPKsaucEHVb9s^D8RdD&jD+VaTC5C@ zk>?5boj;`i&9+$WS9^g=V0)QJUzv0gm{uRw7yrcPUL*G(ue|xxiySR0+0h=1n;bt) z^BHPB$Qm3kpEDGBN*bzED9RibF)5!}2bh-S@`_vmjE5WKpR$Lv@5_$)iCo-SG^Ye3*?<7CPN*Go9!I00K zXO4okj+Y;?khx=7P+rHsw&nir(HC)(RnkRyy-tT~`t*vCepkC|`i`+}S);l%kF!?u zl-Kq?y}r^U57&*x<)-Vp3e#0{XW8G6u6rlbIikYT>vXzG+Oj}f*d6YDdb;sOH+L6( zZC{h&xI1M>QVVF6nUPLH^~`|7H)D}DN|!iq5!bB&>fezy$4PdW?7>a$Y{FE?Dru0w{9%gHyAc8c^d zMwa|XnX4svhwsGQjrSN@8)BULvpzlJexuM>U{n|@jB~o&)BNF!4Ag*lr z+~Lb9FE_5NJnvQ56ubqvu3bOt88T$aJ3nxasP!33-YGwiVRE#M3v~1h(e{;T@9qqBocKvd zo8)NIceMp}l`VRMrt4r@{o1$3JPeATha9_J3OI1+mPzt9`^{pmDl=&CmRmtjPBO%sav{# z>Gj!KVKD5SGRJUrjznql;ueN?m+n8g_2gWv9_vVnYsb8BT+hG0-O=`Xz=6_mTgZw3 z+e1434~8mwvs@$F#u%=)5&jhDI&`;Tm#PUbbhE;48=GsmMBZuzGsDZqT{|p!rxP`` z+RSt7lTuFVeZ$Jq!cUg@-u*7(a^E<{43kN{J44P%dYfyfry|$h-&N7AfAimu&luyn zCuwJ%s6lXV89P?r;Y6uP-l0t@>Ap9I^=HNL5k^gSit)SdHRH5tS9EGcu4As9)(v(k z#;LjzSKIhta@*6|)#qus&aQIPHFjs& zC9jSNJc4(o{}$G#A2YK1yTP@Eb>!Q} z9g|jeKUTK6{}&JIQ-62t#&I&$=k@>eVMp6_fg^%@XZYZ8S6f@)yJf>(V~A!WceI|Z z4n0>dan@d5`*61d-1XV}%gztyqj(=QwQpqVk?sw{k`cG7k;=MfKTPE`rV4B0Ma}gqHU?HSU>auK^4g8HQ)_B~Ee~G* zS(uk$f1ddw`|0ch?}m~fdxE@gU8Oq$ocSj~(#?W}+W&4q0oeyTmJ^bbj$NO{P~<23 z%zW=#SU@94ezh=@PQu#==o*PYmvr2pq54~Zakd+F^q2lgf7imS_WQ5GIGb^nApOGd zoOBUr0^PqxuxOY_FXKSxQcQewz!Khzy&&|L^9c-_%FjeUb0B^oivbxPS`J3PU(9Vp zd~j*lGA7b@H}q4_i6n`zN63+b*xIi|#B%4|krpTgLXf4z+(W2o79I_Q)d`kg4>T8l zJ{*|_ENk2cGEovkCm%KMh|i95FOS0)#o?UylfdtnN(4Ib6>&Jrj|94Jk_ZAh4Dr*h zU%qi&?FE*^u;%}5fg;Xk*pj3My8~<2tXQ^g?M;|G*syW^8XT~IwszSKIG|A`b`N5r zDG>D51vla~^D=HDghlPzFW0QYQH+{3mXP8OL~b~g0?8iRU;%^q#QlH_FYhOuitzDX zLawJ0e}+0X*<_*c@(q$1)L}378Ny!NXNc&8YFVXpYrTK&vg2dGm1`5)|VDf`~5n#YIl^jufz35=I^_qkGupD^&ss`0Jv$%SLXE}M%J z{lZ^{^?RLdczZVIXMJvQX2N~a`EI(8Y0-hb_(|?xVH9ZjiXQyT^Zks$cRJtbM%=+5 zDS+=%bmOu>^2wC`qVkC+o$qD%=VRnKzq0@3Z`kjsQf8}jh%5^dwxQe(*k>rio9WhO z{94gj_=5O9tNZfND_C3m8GQ?l=`I0PS3nW|)i$>tGMW;dbN{5FB3=%qd@k-#T?{)3 zl3)DZrUvk%j3qzzPb9x;m?2*3p$TxI9#d{ekbcFt;iaJSOCso!j=CiZEXM|T6o!#= zUR3m#;fQa;d4ER%>?KHk5|_Ga|4Fssp@=6|o6hiBAbWNe#<@Hd*ycjqi?m=Kb8b!@ zjR-zgn`Ra7=$bYg9hUb<>%%axjSw;&i6v#aweJ#5-!gG+S_1nnXC*AdcU$p}$Z)yu z61Os9-{qqAWf=Quh0FXYuX_U5=H&Ua8>~H*C&Vp4PrqI2!s(fX=QP~&w9n&&iUb$&$1NW*adojQ8;8FmK@(u(O;%hylm`+1IL0ABtMBuU9}$!*~qkrf=oTjhO#f# z-CEa(_Ae}4$UN~$EcHO+6V_$Mf%TlSld@C-`HYhYbm9e2q-UAoy2b_2B?y0on3Rhg zvR=wvo6y&T05w(APj$TmOx#dhZ=MQ$9M(DVZJhDrdNadFdm*3Eu(3Sy?6YtO&M-yS zo#{i(ro`@e^Co49r#1G*rYF zL9wVvxm^u&K9mH~5f(tH{CH;>>k;{>a&{STtLVW1*a+nnChJe~s{yL=GvVNd9r-a_ zq@!LBrOMd{fF~knkAf})B|(OXx+-Uzz&w%lW8Mi`DVaf+{1hu;RP6^t&VHQzJ?==L zKK}k5)@RDu+z2l#zYBpgj`_kpIi~Glc@P2<;w)CO%KC?z87o?&H8W1eQoi$^OgD7y z$z*sEzc-UIHBigT$I3@2_E=Qa-9}FY`MeigBcw z{mvrj5@;vnBSlk;fV8Tk?1kFWD`u}c^Mvw`VW&K#|B1-MX|v=x^ThVn;GLU<_coSV znfY0fhe{(AJ3eRbNXNmGke{w|J(ML9WG!OZRb?927D&f3NE#~QmqD>8oJmG51dYn? zC>XF#ke@0egTPfeu^6})N&@{QtbkJau}|uT9r-a_GJH3|{BdRE?f6!L3=?%#Mg|g; zk(}>T*TEz|$zSTK{b0yQ&L2cUrk-U(85!%I9LW=l!or2@5*BJnVYnH`a#a&2tuKAiMv;f+{Y!DZp?hBkRoSZ~V-j5coFpB``)7QH$N zJ^iJ^=?C-JE0<_i+gLza|*%-%3P+No*({Enb+v=1cetn)6#wROg*;h)-u3kJ?uyE+u;#&+ zny22n!Ha%%h`ZfKd7OOD)q6tR5B0y@%um)swGUiGOBa>TY{7T%nwz5a_!#>yZCh_*$0;2{{se}M4(H4^I=x`Re&GsbNsr}6|hs~ z@f_5FMEb1tpsT~T60E9Y$r4o_^X@2)>Df1=V)z&ih7C>;I1Gm+5iGXNQLJOyqQQ{I ztQS#miF1^PBNi4eq^7n%(P%0Q{HkfhXnHBm|X(#5{W=3ex|(~?6Zo> z5$&{6_FDCYLO0qwvTtPKC|?|Zuc@&f{fQafbIv{uiQuP>#%G(Y|ByQRxcjJM{*-AF zIgg3V%O;L86Z<)<$Wyj2QLx@Qi`F}tnid7+XDq$d|Bcqmk3VP1 zG@<;JTaM`??eb}`fw&inX}~fh&fHjaFDhMS?X0m4?Cb__sNb}HMNR!iu_nc;D#`)n zBg+EUn;2)xO(7>?KN2|i2}rrga1bw`j*q6zx^UJ<>etRl{0-datxS%Qqd3>HVEkq0 z7%fJM*oXfcyvM*(CGK!h!_xM-McIdn3`ggAU2_XZhk335d#gH^k44W_YiOTrSbO)q z2Z=ksIJZzk4|YiS8q+mYEBIfWWno`bbK`9L9VG#I9;1}!SHx~}++M2D4N=#4tBL+Y z(p!?7>8AEm-K4Rh2|Dhg+m?D;%I(Q_BsICVJMZKUYo@6L=Bbe5*j!NYPm$v>bGdAr zQ9h*I;0W_ilPqVRNRYL=2o|cW zreh@()0}2Sw$~^VzKT$-q~$^Ko^n5^nvbjxXK_7@sms_8=FtCB)%Rt3N{}_E2o|b5 zdJ1xZbnF|EhKhIvR5XXJa^r@b1j)|_3zeU^>j-w_r^?IAfvfUuDey$(TMOuFp(MyK zQCH;~@9FJ;9moALF0703@~sttm=yut*6oDG_dRahVuj1Z@>D7gmml~Z*NwEbl257xCjb(!S%_7Xn z4WQ2=&tIAue!cjYzP5#Moi(PnKpvnR=!*1v~yv&~suJa4RjPMfy5f5Beo zw-(}Tg#J0_4x?M2&QOxZ3ORG+9T8@ROq<*nKBwUVoM1l^8qqeQy%47V3hC4J{IB8Q z8&c8tR(CYLhJ^LWOu>2m!M(4WXvM6wm~0{)X@7M$b8&P3?;rkoxAR*}0j7sma44)d zTrk-c9)S}b2g8Mv|Fe^!U>R_BYZFF_a>aKT{`zpWq32B&BN*4NXvpvD?hSmmJ6)8k zf`dGv%y_>1@STVU%g6I!@^gM`uHpLD%g3$xrw~K{eSa`gqO{)s34tDE%7rqLtIf^L zs*okxA!@?5My82lC%Mia^TL>K7`S5qX*93D<6+I6^v#rSB^l3%nEo24hHo~qjUipv znpxwK8>m0q!CjPC`s>cBxJbmK5#{tRov)b~S)tS(DARg(gx2TydWSYnHM$V~RJS(8 z*ZWc=WcqZ5jb(Mq(kTb^VwN;l7V&v*KFqYxr)=)Op+oGy(CK73b8Ceo4_$;%ymp+vfgjGFgJb<~aK`y7IVi!JopWv1=2$i9 zn&TUClD^Fo)+yhe*T4E<)TZHA1oSCahaFSKcUs{aAJ(Qg?m_8w;KjjQa20XYCOy<$ zXr%TyhZh)E1d_h3Pq_pVE4$?)e3^P^oY56dMoD3OM%!V3z1t!1q1_i;>JCf^baFq^ z2U7x5sw~ruIa316qt3tuZn|8kPYGOYCTo@}&l(|idGo*{!#yQ1&i;xys!#vd?quUm z;|txRVmOadXeI}cCK^-pg+NHirzwGRZ1-VOLJXKox7cTp*krK}a5a<<$|@Q2`dxeT zV|>j$#n%_?nC93nu`!zx7;W2639uB(bQx~jzI?nhu*)u;&{@XZ|Ju#i$hyJW06a^t zaNPA%)QOG95xmHF$qO_4&}di6e{cFjBbV@Aj**v*y!7|x)h%D!cTV5P%%mN-LVSmg z`y*1j<^+;kX9QAOivp>wn8EN35idR_{UGy&5`Su2p?^plW-78S5-V-uCWNh4eWsr( zz`skH_l>%2>6@@=gZuHUrY%}m!*(Egm%67&zB!UuZJqj%!z%)b75vxO=eEa zT;;}iI=U+(F|9b?-Bm+Y!c_F+}`Y~h}<&3T)ka9@&{aYpw~e4Hp2 zN9tFszhRTSAW|-uAbV?Y|L=g28- z6pC1iFHY}5Ui`3b!-lEgadTkBdW>wveF{KD$RvWLxdUyTpB_KIni z$oTncm{orL;KlkULGrr_7An7NoY`g@Lw+exq+@*vLaF?g!;$q=g5dS{4h-x;rBuuzgthk@7Xwh2NZsoUW@SiBg_mprV|9T0+Df~g*2alnejLi z-3M`WJ5R$e1I$!^?>!A&Ht6Ut&m<8@*J2sPKf_1&Npbv&keD*;B$VdQ+5BinAYBz1 z*dXajV5jCs2huMD8s;z8$4JNUbG;pD5~&g!(VntyN|3CX<}&T*_8{o4l8(TokvgV; zB5))NbFuJ@=fkE!(O+1Ju&Mn1I8xKzfV~9CPvTNn?FVB%h;vj?u+}c=M*wP|dqQIA zlf*l@q^FE>K=Mq0nQv5CkR;~7{-WS?Z%vAI=URjX*7p?=c^7dI&Q3_8SpQRme@o@( zLQ+K#Vn192N zU(X3l;^%5F#^9s0S7LB*!5k_&QPx_$>=s&f(as>Qpow(7(3#?8Ga%ubJui|0MoYYC z2aOlftgPRJ%V+q%EPkDz{WY7r=szlEtJfIm7V>13>Kc#R{X#G#Pbl{Opt0izjh(zX zh-(^zO}n2u3dCXRXh2#aN9g_lb@UUSq7FLB8wV=J+qT|MdwiD(0n6{!PzU}M z>ezhtB_uw-7kAUl(6oNy&|OK;XCmLI1D|5++($_KGFx9x9dv7LobrtR@1%Yq+Bh5M znl0@gu=OXPlh0vWKVs{@v-Q8&`d@9`0Xaze3|r5p4u7XmM?5Ge>0cFf__Ns7t8M)% zTW4P}4T6Sp(lODJe~x@Bo%u#`fc8_Y`?eh8t$7gA`)LpN<tN9XN|kONIPV2%(#o`DFIbqKoS1c-oO#a3KTifK9h!ucqJ71N$|no zmI!poZ$8W_zc;{7ly}&pT1NO?0W+NHp$YKgA5}gA(yw8#0bK-IVXBK@(J+zTq1Yb< z5(dtm3l+o1a4>8tzXyR#hMffIuf(OU+7CwmQ_Ty8jy)u%vjrc2FEaTKw4Z{lnJC=R z-EPtHu5NO}_YB8}-gAQ)j%g4WXWFw+T$1=1-;GuRN8|+e|C)~tHIj@BW9VfmUFodsr*vW?~wdd8Fe}6)Oz0n+y^B=^1Bok zD!**-bHk3|W4L7axMxU}d12s*$UGMUu@6vn2SesXX!Wx+jWvGms6HB3_rKK@-ci@|_0l4BPM zOeeQQpc5~GVj9pa_mpjj%1^sqMlV)S#i*#GHV^I>V?5b+WB94FoJGzN!&3JBSRN>Q zOQ|CPrWJd=GnLNS8D;KtdG7ek`@}k|435ZL_RZ=a^Ipmu&kOwx?U{xisBKSgSkzur z=nT6H_3)6wluq0qj~&AAb?V~WS^d+K{i$6=g*oB5g_A*(4VqEmTw_tg;vB8;M5oJN z9MC5JIjrToy1rn##_Kb*$$tnJh&4p5;Jr?_QU5e$_17BUf}8lGKD{aKIPdSyHE_?p zsm~tfU)C`DAa0W{Ookt>FvC%Tko~n&^Q6}=&RNv(yY39*=cl=2k?AYpc^D$=JlIow z_GCFr#ilwA1jR|`!I;=bTs}>GOs1^_S)*BxRQb3M4y;oc3JDoSIu!L&_PqTAcKlX? znFK^s%7)ahM1g%=XgSK+71n|}eFDsP&A zC(^%r3Un<05@eXDtMbN`puG7b=w?f1&?P^`N*Go9!H_o`t4F~l>TiC;!ooj_yx}Z6 z!^k|QyqOf?W#uQP1S25$swH08_^(=HAQe+FH0zwK^=1-e55s#J*)v0(Bs-(*DV~w= zT?9TWBO?7UvAR-)88U#(BbL?E!H2maN-^VH;u2C}ID35`F-^YlE5WrZ*V+3bBr;fn z>C+^an6?t69Eq1pemIa$&QFn!co`J)9o1OC9Q^w%qxhHnt^_8_2OVyOa?@agq+0@9 zm0tlku)fgW6e#JhA7)j4-3vSs`4t9TJ(L6)ChDsEssi&~*s%k&B#{Ln(2c_HYQ5vRn6u73V0@rNEz=CmN8KAsl z|H-N&k^YliWz@Q4g^XiG(O*L1%KlR1Ou@~G&DYJ6*HR~N#)xYPfQZaue~ITiorWt{ ze^3{@>h*$*L;6nc1t0jlr`k_)gPAH{no5x6I9>+*3U!j@ zEq*LE4|Zz(x(YbIl_2@CpP|YYt{lb_l*S`1v3Eg|5E$d*Szw-ic(3=?%#w)6t& zfE{I;j0?lTu)*I5>;s~%zDs@)0^6Y44~A@E8b`sJ`-;j2rc@LL8hcS*GE8nL$_6QG zfLd~h#W*4+M485$Dz(e$4w0axAz_4kKtN8F57x!?XYSLKCfuiqmk*rJ#|Y{W6~m*> zy%U$fautuC#XbrX?v#t-Zyv;(;y+FDLDpfWy)+lWtk&mxII!$8Pe?;Wyc~+4#s}uKWS>E%4eN8fyzwDG(_k+_@{_pKRr|q^H)@(kbHnnD@+H>Y zI?v7UTfh{I!a#S;VM<%13DcYMNNvl>Cojf5IkJBX)=_!2EF!QtCKDB}W~DRDL^O#Z{}6bgV!_qbj?#o%X+kS6d~Q!dT|7W zTjmYRITdS$0mUL9WnTr%1Mw?^y~^*83O`l$U1RfuCg3Xkdu=l{`b+pcl**6$x7@H} z*Xp zv+ld0B*>b_@*N|`6n?5)ybN@z99s@N5jnOKblhtpL57LCD#y4-tP6G=Gg2{pj2FWO zeZ@v7Qhr%GF&rK}Vez*29anYq{4r}u|MMGN z?`P#ba&pUwD~5btJGbHjef;7n*J$n?WfLk=Ylpn9=eLakr)j&&+=i=9cm3^HYOP+P z<^9s1R+nn@K0SPKc(lcB`N-uHlHMPguNA!**7J^bXD-H#A4A4wJNiDD{`VtKW8Xwd z<j{HmR-mve6QHxG~@Bz!k_}hB8B}%j%H=rOV5WZQUk$_JI1l4{ptYZfyS-|u$7nlz2H6BBVw1nza1pJ{B_H`+KH z^t3w*mxNOaeZ5}~9WnEZwZf{`kC^UU>_3}u(f$#^BWA&{s+$BvY%aTgWaUDWznwxNBK>7seF59w}S*`{u!`H~c4 z`@WYU3`MH0gz|K8I_oG3%H@rkSE-$+ zTaDEHxR=EDe*%xm!`-`jMpk=tb5 zkh&GQcdV22DjiFRb*mA$XH^@+D#}EdTH2R2?Z!PfNeIC;!bbf{EBHgF^_8NrvGPHcl7gw7mZamQn zei8n9cl~4M7^6_XR=1}Xj_y2SW)<&B$qBm=ni9j2`}EuOKKOHp_H8Lyw!I#)A2k8x z>~e-A$=-2Fv+i;FS^nNbzoq`M!@)%dGmUdm-p)gbD>NieQu2iaQZlXUpVp^jfja$Y z)VDO`u@k;!iBQCUk@a+}Z&{Cd+kX~(*&I24S&j=~&3YPqXPgwVcfcox2jzRg;|m?0 z!~0xD=BuK$%0fyxAPKyV)Gx(rk_hHJc+ln$2^&n$1!5 z&E{x-vzcApY@Ua2#<-7|BX4Xr$9h}M5#T($YvrvIZhiBs_kVTSS6j`I@OLcy9Rm(I z;BbCdt9c%%vcYK_xQwqpzWF~kH=Ay7%5~Rn&VxA*oIKuU)3dwT%x`HnCxn{Ki5<=6 zq^@SOz~5|6u5LD`fWFY(Y!-nw5Bze$*X?gLCsnta6SG>)3GP-iA8v)aTg@pgt>)xV zvw1;BvpE%X1s$#Cw611zn!nlff_|#M)w}>ai@|fcyVWeh_a*LTvjpEy_cog|b~l?d zTbj)aL(S&rI-1SWu4Z$VzuCM9-^|80bKK45TyMv_DdnwZaj4bwg8%2bTFndnt>#Sd zp8U7K8ehm&3J zy>>HhyGnI-JzbXE=SUtN=4gR!)iB(?*B_qVL}|!xwSxb~y=EVHE7)S)p}8%cE=y3Z zsXGI#M}O(AJ=Yp*nvdxy*)wvJY^gG*GsSqtJX-u@dv+kT>lM>g3@lfl{VYt7P8xZ< zVx|^fJMLLCHCHSA?@qYumhFt<^e10251`G>IF|I@uA8)c>=qxY&&Y1K+z%A*DSPjY zSIm)md5#{Yopt7CwsFV7Y@G9#a~0)NwK*}f!dC*oF;;(r_Uv%0xMhqKF2jEiw#A-B7V>un z9JqaO`xbrT!bs1fJm)#2yVl#hCA(kS?CY)GqD}SnKHiAOeS1H@r7+0*3NPRC9Aw-q z__$^LZ$V97vjanSjLn=~|84VP?=ASB>wcpCmcX}BJ5Sb+$sD@lq8o(^{^z=%3_JlH zE;kC7^}+@JbKUO;o`4RQ^}=O?aKZmv?~@y52ZhT9;j&S<;2-{Myv1_aC|ouP7yQGY z;1kfnZIf`hNx0x2{sf>{Y_$X1d&Ay4`fU!_4*4^$y%lcZ+bp z1G#TeJX*Pw| zrYN>4rn_&kDN1aL88*dCD;%ruFfX)y`J7ErYE#T21>$rO^f}OHd*5Hp+`9vq72COj z$LuwCm>1hT=Gi=aHjnu>k20G_xi_WnaORChN?(O@Okn8U!!wEqFCqFZ|L` z^cssFs>;aSxnTC1on>F>JQ#d(m6n%Y@to<(-SK{3pM5($ZseTMIBV7H;K@KrPh;k* zIlnV2yw09y9Qs9R^Pe*h8t1hCIWXkllKv3qpFeoc^w#FI|JKZ! zfB0RWi?!!D)Ys?G*Ufj+-6iT(O5^WM-!o8uXu7QF((P5-FS&D}yH@wOjqX}Vf{w$u zi*91wpZvA8_t$#r$5X~`T{1z|6f2zMrsXI3-G=2(+^UaHhi=AtB5Rm75#ibZwRA~u zMrNuTrs=*DFI5#AX6;v&{bX4v?>RFy1j>%*%&e{_Yj3GV>I=zRjC?q(`GkB~+U_=n z{y_MLwAmgSv(pq3zO`zQYNJ*Pa|HVRwwD;fmCoTVii1gL+ zC*kJEkie4yV{Co6tw-}U$v+~}ZgM>QVZi<)dXB69z!s)>;%eRNKI!<|cgvED-F3h|p^Cj@&j-3P>khufX)juQ zIQJnT4+i^=zL+^L-tB=%#=nD6p1IHAyiQNcbeE-pr>)*mm?PrIdeKD3t05tLEptB_d=!=DWgh$NW->)#2bIM(Z<(WHm=gSCnPFeb8 z;y>mact22F9lo>|fAPZe)@_VPezCS7gTZ*nbUS-<%AB97*|6e9YZXx3D=4gLmn~bd z!9JTEwZ#Q9@q}2>jkm%L;kc_N-gYIg2gJc0!ENQ5P4M@I6&q`(*4M7zIJH=D3oKuO zYi-u4_Zf;HEnBm0gUYpb4ca&l*52qQJgcb@-><93O*zpZ;9;?b`r5V2 zYc|%_tpQ(~bQ#zRdXUCmW;j@z`;pI|roD5NMH1x9EMMOY&O- zv&zo|KgLahP$ayXDi0_g~ML8<&&z>nXPR?hzu|2~w;kLv`KyAmY7J+M&u?F2tB?8uMtCLQ_x z3`*r!kE!+pu#+J99fF0*?|Ja6h8_8FE?@Hd4a_RP0(jzvodn76C0MBZveBr>{9s!n z`Srl8@~Z;BfMjOV5$%Rj`4xa)0qhvQQBaZ}nW_Btf!|`dOOWCF2P{;6)!--dm%8MK zv1Save}Es`6A6-E7U)!d0r2DcLOuw2mO}EI636d(WPVsOv+0OVjN{kgvCiR>AKO;R zZ(ba~omkIs!(9UD2v|xL@tAI*+5yn997`Y_NVMfPowPp;x;YMsS^g69gHDYvrc|^p z*fV@?C>g#RLFZJrv7#^~vW_+bbdC5{f;3WBf}=fn9?B{5V*>1FLeXEAGlmWRM!-bl z{IFyKTg4cmp+U7DjCC{=7X_@n_Vj}?`_#J~PrYY?b%pel$qqSG{h9@(Q zJ~OgU2h|1il!Q@mA}3?{XNh;B$zR+v2X{BjU6BI8oR5MNk}LN6;o5a@=J)KAIwGr- z);GMnF_wO$xOa{8?AtkFdV7q|s5tsj+B(pYJ|O5RnWDhE8DsfpYhQsg=_#WeLISDu zW8&z?Xl^+3E;|b-S)$;CWQgUj_QDz7adGa9RTP}sc)>qvW8u+Mbw{0Ga>h|RvD12+ zLc#C85r_YK9R5HYzCR8>9Eblh4u3fgKNg3-6^Hl6;eU<8*)B+6_*0lUHV_{khmVfK z&yT}-mY-H^Glruj@W#2%jKeRA!{^80i{tPs<8Zb)5*Xf^I6N4KuZzR~6*#S4gc^?W z)Ewu&D-OTkre{eS&RW8by0s=Ry6ha72!lNw!L^tIHvRS={0{;be)WU>zTdn%(DF{BZPqi`+g2Bd}crFb~`28(>d##&mhS$F+(Xu-PR z#v5wuwUxH@@)av4M7R#9eoZhMs~gtc#85^DNVrcE`NsP!zh~<#pJ^9j z-!}En;avmU{!Z$pn)V&)v(T2>_N-6*ejMpREWV!|-BaO*J@;C$UqL-!>$j4Aj;66Z zQU4)zeD@pb*pzvk`o-3sZHA|s{y=9tF%BJihKo8SAnixlxZB3r&!IgfAnDkrBfb)C zMH&V(H&OR#+9TBGqkd9{JKqkYF77k+!p!f=tiE+xxwYS(`byeE{|faAO$*uh*Qw+C zf2TgyzCRWC4{dwO=d|%wABEow{*_iZ)1b?EUTxDYwZ9uhU4{dEku<^|)HsdbAqWB& z-z~82_fD%qyq&P0fN)d4MAN=NeIepceUYX;K^-4=P%p=QC)5#Mo}HvV&IKLcO|kVE z)X`X#QNI-a*!tttQJA`H`~-FQ>q@fdv#2kz?{fv;3yI_VD(b-5hogS2t=HLly{(6A zo%^9k*JA6u@0IDv`(A1PAan=v?MKv+>HDaoFZn2S^kolF#~A1->IH~5btF3XpYfj6 z=c%7-=XWLU7iYR6oOe@4dhMourCt7!E{_vOx^06#?h1RaX^Bq(4G@gmp%pct7z`7}KF%5Eu8TqVMao@e1naYocFHcTwNm z2$${NMBRhFgN;8(eInv-U2a>*?XUZ)3F!)*<6wteB5+(-Q1L6{4{`>+m@eT_fV2?x6x+Y*OQVmFb)n1>N$$u7h_4}X1>ruahZ+f1i@LB9D$_`up76^ay z?EN{;L#O|GiIa~M5Fo##`J5uLrEkAyQ;i(E2*t>E(O^%ZBCqpM^ zm?OOBkNNQ}I!gYtCoN^k zJ60G+cRJzoFmK6M>2Ik~vdPKytADfhVCmK#tdejALz-F|dZfNPucFwv-*kkuoeT+M zb+Nr;OHy}|T7>+2-Fn+~f$x^N4yE;daMAdacb@!S_bd?uC3Qm+Dt^(EnmYbulX-=4 zi7~-+eBFiB2Xc3MCLmRq7QaBr1XuSjuyYM*>*n{J6)=UCi`57#)TPFEu?HY6h*g&P zOM11`p+++97_BsRH1Rb#ci34tH9Vq8?3q9bcYjr%Jsl<7hnRad?ZW#!^6IX(5|?yM%KVU=P> z!K@&-dndi2d7kv|?sH`B-+mwV~NTKt5+Q?AA|T6Ozy;FwvkyAgG0xRyWW zfk*DI9B+IL`=^lO&WW#=RD_M|u&Zu#ctY2O=DAr_!ly|UTaClWgR1?>!B@=;@5ZK_ zvHWuQ>-(DYf}x#BMtu{~r^3oR$4sYjE%N<$;dQ-y0o?pIeZuZavlINZSwf95mNHxdTduGQ^DNonEC=<;xb=-zKIykmObmcS*}mdFopz+&Eal+ zN|J$ng5h(!^x&OM`jlav=@I!>jNC7X9&3-4VMoC=;pwI;rvS0ABqimQR`6Qb8O(0dvBRUFxCOgkgmls^ zIYs^hhe1dDp2nB^AeHyCj^&LuT&VM@Vz*wsU-v#7ek<^Q+4~mwsH$uIb7m&5NeBsv z8bW|c1~3r7$pZ|AN-{|fU{DZkFFsl(1T>Kdkp!#O#{|&EM=ct!MWS9R_Ff*M0n`gc z8fs~4AGQ;~uHQKR$7OT4`d|kydb&7x_)=MOT%8* z5sYnJqmn(peVs=co7(0^$%0x!@;xavuVY_kiC!E3>3FopTbFyI7{B}PnZ2a zYnNN$h-vM*%ASwb=?Yj9oPoiuPVC}c3+}KXU~{B5wFi<`s(H3TC;ISDF=j3H#0%aK zzjQmkh-b-(+LN&ZtKyy*!K<&&uoO)K=Jr5rUCS1J?=ub~kj*u_X+5w~? zd2IMs+7vU+G?B(raa<-k+XS5+)}XISbS)Iwm?Qo{93EzJVpYhhypOp2wO|2g^}GmN2v`F@36kDz@G#T+2k522kMyVykn|pf-Au0)0oCx6 zAn82>4>P^gR6Sj!M?NU&t%u!AFAeik@(&4;-Vfkmrk4SFh43T2L_Ct-F4)cVJSbf9 z8VQo#Yw$4ByB73h{U#wy()&H^W_oFur;m`t3_LpD!egel!j#`Z1|I9>Z+Oh~CW9XN zmIRr;!|*WEdj#~d;m7>K8cd%J@0wm$Y7xmJCJ#xENM?F3gUCvQ9;Wa?dda{;ldFT5 zfB;@9kPeuVbTaI~3&L15l1v#0UumU@X?hS^q3`g)1L`6%J~4ePZ>G&m&x=Cqf}aFQ zPr9XP_V16iF(l6fHt3J_yc~hq)7n@#zT^Tr39fa8hqDEQfNNXf;p}N4;96FAID1YA zxONpD&Ylngu2qGHCt)>3&ky^AMU=c5pI@dj19Kk&u0@51r($cfUVl0kTT%$P7G(ym zHH|lUu-@5+CD2_g9Wd!Gk8sb3a9;~I+W_Sv-a%g(5xyY8-C*DcU~(m{F(RCMB1mry z9?UC+39A66=fChU{3bkuP(Lh3y2-N!p+0_UxXB|1;rF)TW*;Af^7|v)5=c*9XTU&> zp;up`kmIwE7o>xOHI^wts|e7{3(dLE4uB}$pR|^=D@Ip2;;+Gr>sZlG>ioY-64esv&ayp*e4&cL!hgs3B4fojdm!Dm(fJS ze9;JhkETQaHl#gEUxy_Az4UkL>p=7;FQq@%m*~HeCj4Ke3IE9qM|{(0j)XqdFnxwO z(FmVU^I}Eem__q)!#~e3?=s9+4f7qE;M+3(B*uq$E~n`T#k+`jNQaju^7#Nw>V;{J zHuCGx$1i)TqQI)qbkT$WQcN>jQ9h-K{AC#N07bE2AV{MbW$1I^E~XnSrojlmgC* zwb$?7`yi*yY_@D7USv_p?vFbn4+U3U^Z+o|HUW?uF9oTWaCmCAZPZfVk@jC%m=G8a{MhYjr z{+Qx!wNb_HVM|uJ=SS6Gb^c#?UH4#l2()oBCjN&WrlQSzr22{SV*d_r)W1KVjnw9A zBRZbMDY%~n5?UV!q_$q;xvhF@wcYc(z^=@ztMi0;o9Aor&C(J|f~}rsXmRLh~HE8CsX(VSaVsZ+)1Rw@Mw2lKpd^;uzQQ)0*Wq zzQCT6%ul0^Tf0vdUK-qoSA2A zcKJHQ*DbJ@K6^3tW50$oO%r`;(QepO&DLVYUVCNKkC4*>gznD#504G>@A4FRE?>Gk zu=}=eRa>;-I0KL`bPej0oM|iB|Bf@6Kj~B)%1Q_PQ+MgU54B%@&jGmf+Rf-3t3^FC zspi+6s`krH_^GP@q*WPx+-K>uIT=^cQW=*XlXW#?vOP_$hU(P6>dsyBb6=WzIL=y* zk}A}iI#*~P9%Q{MsCP@})i~wycnsYi{qB>4`VM!k^C#6wFApxW)u@v)OQJ`k#FlJp zi_S!e;dw227wY=!0b51gRJ83MD-!pz`vTv4)j!O14MI%;(7jS7+wPo;R6>pgh;W%pm8;S)NY<;o?8e9n9J#{BtrnKj7AN-J8U zzJj1+?-RP8!<{3le+!*&(#ww>0&j6X?D>@^e(ANIifX1Q-GlVxUXPwa^9s*(@E`2q zIWS5iW_<=&RuEpce8yb-w_+A9_?LVEYz}jG+Y0q+@kx0h>&mdZL|DXk;Y$;2LDKswJj{4WNa)=X38uum8g_HMzlMY3DC5PD9-IeJzBAK% z1oW6U36dUV65>gC4S3H>2TX~_Hf)af12~G|$9O6A6OZ|Q7!OF)!4TjB+yNM zB!O;hQwajylr>p~Y}1^-OgG$YFZ|B%wT7E?2CjhpH%dfDJ9XRN~~5lRlNgW)GD)fm8PgJ^^VWB z4K7o=N(7#I+2FE2`tSzb`di7W%X)|EiZ4^|AT>z|cbGW;isu772k`tJ55{Nb8=Xq# zL5$NV7SWE)W3RbgKa23QKJEpN?-Uq%VeDcX&uwX@tzZ2&oPBO*TgIX+*+isfrvUaf zcqB*;H5nenlRWet*ku@TrJZ9Ons^X85J0|k8uUtnoOX7+lz6quTZZ?O%?f+4*Fe!A>Pj1gusfL z3fFAuZsu2q7!ghxOozz#PaT)AZAt(!li3pVJ*P_-8FxU_S)i+c!nzn=A`fNSIhU6_ z7CdvJ>kN42Bzc`+AHHp2G=d<{j7N)Avt#$FP9^IGWtF(I@6$a=;FL<%3GgeniPP~a zs1eQ)uQGP4enELssI7*0%~w#i=6*B_ZU-I-vQ<(hG4qfW?8}CqnI~NVKQj-hgS#(0 z<%?4~NSeQmEg=EAm|!4Eu$8`f&S zHS9NC(b3KBM(m_~b;}svj*JP|ZLvPBX)x|w!;Z=SchcT%v3$=xWZ&A1oU+&sOWya~ zPVCZg1}rnI-8SpMeK$5u2nAP&R-{_dD2rQ_YncLw>tjYpjQ*Yz~1jX$s6 z)_roy^41cc{b^%@)ctT z&Sl09nR?%x9q}y=@3*#Ysm6^FrK{Z+`i@jT4!z=_1DTo)_vXY`rzNTZTl`Os#+2c4 zJm$vTACuL9bp~z&N%(tE*VDFT2ad;l*IVI@_3GN6ZSLasc>MmN=V_r5xSmRjjpfT~_s{N9|Fg%l@Ntvq;%f?qB$l z?M`i8U1lBb$g5DZECqv`V(qx6Bwo#X!i{@MGCq1&ar}4ZtPDvfs`g&7pOm*Gai`Ii zP9N?udf1(DpbqyQENk6WZR=``9w5p>)qWNzRM%~`b(Ke{&Q}7v9oYNSEN>3X-u`=p zT3Yc%Tu0qh+8Kx9kavpt0?Y}Ivp`HACdt8@I z?dW_J`}BQ(&w8pH9nq zbwf!Y_B*Q3wI)tu>HHLT4dKoapIx}{`Rnx-QPQ|6s*x@CzGI7D+HS6&!Y!TTTWH@? zZQ3sEG+e0-7jJmB#$x~JJE*&vhi^%@cdOB_D!f5sTW+4F77w66Kc`GlKkQweffW5&A{2n{bp6#v*iQ#&B85e zn^7W4*CPp0zWE(D;%m%w&uw?)*Oz~MK%Ka?{15M5Q(HCf8yR1l&wF5e-jv#->06I0 zi@isF1l{}l)ynF9idwW9l;7|wE!Sl%tHAAfqqnsU&x8o4*Zo#d1gRw&y6c2kH+GuUIriz;~e;J5X4sEuIU2E2*+X9Lsd1!@_F}$>_ zFktg!2a-MTOHy+!d4kLHSXq%*r1i#D34%lX`1HQhiPq`TVv_rkraf#JucXQWr z0QYa*FjL7%*J2J^W45(fyN6qlzDtZrd zy0+-zEa=O?lQm@IbP5MaBmA$L;9b zYDMiw>BUF>U;VRg`~K*zpN`zLrK$4*+^*(t*L{y2kSRreTsOp8b5^z4oTXKkPIb!7 z{^2p|rLT1I<`wmEwrF)VHSlRKVRk(7?M|zvI3{$e6NZnwWIx)3b>zHn%)h2qExKmD zI%;C)tEiikALYNKj`VlNcdORnIT`!^ZrMKA5#0UwW2EqYt2*)eTH^Ay>FeiT&`x?W z`$x{Zu6Ff&byBqUcguD2$94{!o|~oL+=D&YMOFUcRyBWc=c`+WcmAom>Xu(9>ZJH$ zCFf~PlxM=s!?hVs;P?(^YnOFm+0SeAtC>w2_f}qnhMQ0`xT7GDddbxrueNKmt;W%`w&@Mr#@ew*ZMS3(^O1&IQF0FW zQp>Wjd$<5?K;KD=^@Hq#Vh^I;7OXijdo9j8v3~RZ_4cyZyw&c?y(Px}R_+YOm&j|D z<0jC!y_Tjsks38GzRZPjGB&^2J%8_ISar!Zc2+CdZ?`)|+jK77xDdCxRT(=^XQGzc za1&qb%)`^-3vlb=r0R{`(bi4a|6dTW?)vj=&)_!$HnBqUB;<&-Wemv)*lyJK-7Ag* z2z?$qHot{bV)x~)5rH%%r7WxIC&%wA{YSoRw6INAi`)-IA~mql-g9U(Y;jwPvFgr+DP;o3ai4)wq>!KjunoC**_ZA6ZYe zrf7}YiU%JSDUDf4KDM!ucixWH^gZWREmruhX^dGlxW;l%R890_ZhxG`vNZi3n(0eN zH>snGkKWU`p~*U?_{iOjPOQhNcC3)C{F?TCO}Th1*65NtlrjI-{&K+P-K~vovP|6U zhLmOhleial+=1utX64?O1D1{`+EhB`f*pRnp_subp>dpC-IyGV&3&wXG{y@8(I^KTVYdIzKwBabW{BIVp^h` zXAE1d#r{Xszbnq?x7eHQ+7oWC|3mM_Cbg(#izTP{$a1e*P^mz6Eykg9|61?%Kths= z@_f(xVv}_|O4Rn}y-sax$F_hCec8TO@am^hTG)FEjoveR?yJ8%wWRfWnqKad zw!ez=5rv)6Pp7WKDA#ORc{OAj^x{^hL6!Ud4+O4V^Fv4{hkU93@h&)0RI_r)d%g=% zzPKIEi`$}o(W_W;Q8o6JW17Cv**q+Mb=WFBOzqbx5ZPQAwnRc0D z=F$eo;+q^en!4ns+Qr{=aNA7%c!y*9qAHw=tzRHK9Q8GKE#N#=oO7Kc;1s>Ad0u`M za3k*L5_cHDTYwM$*jpWWmz8CH=z6EH`SxT?a8J2IN=wYPl!%4Vsi(U~YBu62PfS{2 zyWjeNxb-XTy2PZCM1@y*F@1)ASlVWZxK2qMW5ZoxxMd489e5-(z|uor!qU(4tUd16 z*07iTIk84e;v+~L(nSzfiL~^vcif%mx=Y~K@&7l!GTn-GyFq6}kcz&}aCN90ZVugG z2EC^V?=I*YdQ4|&Vv}llL{L8K`u5-@S2)it4t|>#mE~b@vtMxKC**n4f`+PUoD>&_ zwL{*fbtAKu_dzWhQ!jSJL|$ z?C4U#HI8fHAa9W%>5*@k>0JwY+3;ifm@Y|gA?#*)E78xdg`WgT?`C+I>D>)_)OV4d z)c=w0GCXE_N${n~o;>A-p>WZ2F78DN zZLtiyf5?11!F+5%=l}Lm#$J4wWhhpT^9{Nfbhsab{^G0w=#$S` z9L7FE#DgGl=gj4XnLzwPypOhO2di5|a{}&GqKWuAU|KNXO(s6@Y7KK0P29EgGn$v- zAsysj+^Gc9LpS7-M-1}=;0-I%$9Kk4M>iP7AifW}ctx1(YrN~|Et+`0(4f1YCgSrO z^zxWK;9XA>{hcY-cg)BO(J7|+=e=@w@skhu|to98|)i0nqg&GO;di02LWI+_^2e{HyZ zG$C&o-}9ncp@AQc?d|TG+=&w=>dU~ruj_gd2Ozkvn+#s2PKVaR_-3riH6g>Uyz=c< z%f{u0ux>qFd90b{M(RhRR>ibp7x)PhLUEjS9|yzuNT5AUI$)y6xG(!rwItCoBhhyD z_k0BB%hh_>n&zg#OWQ(|(&~DA>#z!EHs;mWkFUnv&0o}cr@4-7M*WP1X_kZ2qV;i^ z&7C-WV)3}~ut_0UKr#M%qDS6irk8D^$9E+?xyMb?n}M(qcq9;ya5Ww?y+RW`rc2VR zf}L)3eF5Y_bW4!*Zi9#3HS`eTF>VPG?^bx2f$C&>tS4gcgb z5@cM-@Q`U^m>P32QgJ6 zoaLuOcxtQ>u~{LFQvzq1v8{984u;DhkWMz9Pr^pV zRB#uNU_g>@874l^8suBjLO+9X876%6d~z=!+t4t~Et&728)FjNkR4-@!|$_`xxYv$4Wg;;RQ}`Qq*~ z-m0VEt5JnJ2WAi6+uH42Jbdp=zxNtEo@!5;(COp0A5Y!ph1L0+xt^zF72~TqtK28r zRquQwJeDhauoh>nF51j*bLdnRr_+

j>}u`*sT*`w+!^vij(mJPdj3O)L+odmIi18dva$9#A{NnN$dlRot8p22uy zdSI06GS7QRAFAb)G1)xk-i~m5dqaN1B5XWnn=aMAw=or(|KE%yF#{ffdCIy%Nn-YV zv7n%d|8uAB4z+*NaBY0d0nOdysdokG*DuGYKDT}6F4O^eisXjugLmMOAh{~*%{)eZ zh!@xf$ODPPhyA|{kD1;JaGTqTq*n}oGd&w*ZoW@?OpBy<9qeX$yWwWLks#@Dj5pIu z06ho%NRMx}}f=_zkNm)S3N#ylRn|VxbLZMZ`PlBW;-O@Ds_s5t#KoSy|FzRI>MT`1!egJ||U(_yNIjd7w%1{}3JHS~Pl| zeLP=5_OHbJH#Zgxy7l0P{}UA<>7B1B|1w=)mcSRI1WJu;oD?F{6q3P;9;XBvx zu4|z9cpL)aNm|><@2siZ!5=euhz+Bdhix4Rvt^wYYdXV^+c;>V*U?s-qBzRIT{Ve%#4HCyXks#?ww=~WE z{UINQOKAFeN5;jrp@!7}%PBfSqLZyyPaW5E!|AcaL%?(Q;o)I51p4t&`kLnR=e)W9=Mr#m0X^q&)cDb91_6C?}n=ug%6c{P7#SxS(0wli~UTnDDW zw!)@C96odx<1zO^_E`rW36dV?C1!f9pqB(c(lhhDE8#ZtAM(Mz@SjJ3_jNoHWSVG7 z-pDY1J7gD3YByzGm=2~5@dknSnq&lB;dwN9hvmIL_>Z}aSjy}JOrH*s{3X(@->b+x zv)nnK#55`hf{tj)!MUB@usKhwULx>@pER>Yv0e!lbyf!zE6Dy zAgu4#y)y8sfmhx>QwzR|Gia-({-^tscKcQF2;mBx9vU4MTDKEt;Dr89 zP&NJ{`3UnRVHPZ=@9>^Oo`O9BHS?;(MM!fimn^9?ZXNC)_1t;IUs%QxBtMAcFE1k? z8%VNG5|8|41|Hd$VHMwQ;kyzfy=m|;_nrL+V0(|`FVxSO`AaL@ec>-30Ivp*1eqq9 zX8z&=amqL3FMOCjrX!NS6eFMk{t_fT>6WJ1zd!g3%QOV~Hx7$~9=e<9)gh909`YN9{-XFNolz#Y19ohg2!aDPz9+!}OQm$cq+8)dVL^6vYM;?B62ngIB@2kD z_oTTC7V%Eda6f#5OMDRQ6f~2Ej+2FG?O+nC~_PGZ6WFlJEz?YR*Vy5Ff=*HOUYp|BnSgnc^MON-i=(4qP zO$JF-5`nj@)w;1!VCgs(fnyao$ZD9J<>E^QWWxl1^x7J&%Ph;WOCj~qD4buIo|x+X z4Gu^AGBXfFJ3RuB0~~b~FF>!_7QPka0!MPq`n-9IwQq zY3AQ=82p>_Vm^$Q<;1ihCW+7O&>PXY6z z14}jpoUfXJ>lG|V<{=vo`MaEt5|4Du{GD#O`U9N(@?jQRH;s6AB zG3Tq+iXqi$WyN7etgkXw#2dMNpo8OV<$|6v{X#DA0;ql-fU z)*y6XMpMTY=7u}#7R-e*doBu=aazzJNr!8Kl5d3gL|t{|Ipq`9^OR4Z9KPfeU-Aia zM}++g!6(?o&3uAQ{Y?2peN|0OANa&1m%L@LcO95tFYBN@!FvPm%YLK{w-Vt#r_a78 zkmJu;mm_o?czq@F{srI-lnvOPcsJmYAk#$CEE}wYqZNK^6H?CMxW{xL-XP3@!z{;3dO-xk zV)j4#vH?pf1U=moC}jcWjj{m8e$gFGeOfe8go|+=g?`F7-_UU9l0Nj`T-U@t&j&K} zf(rIu&Ibx#iJ74|qqJDf>7ll|G(+(f?sQfwIVXHMp2D5XDchWRe!#R!7y*lUkLp?P z_^07A1=dV?iX|5=DQLky<&Kn z>7|+Ik?%-)SHo`R2`k|43s2Yvyh=P0WSVH2dBQ*7=zw2u^99alMoVHaB|Vduu$ukP z7Ef>lBmL*+3nM^-Jc8{`0_)Q$9Wd!84-qUu@{myTH*AW2h7+jluha`WU{WtEcnm5z zlE=)etz5LQPdr9mF5J6}z;6x#!gx$HbPm?C=1)|YlC!oguCVn}ufI4>ml=r6^qTn# z-4YzIoI9RUQ!mQo3m`kVP;RUWv+TgKl)!#X7>mc;|2xpX$Uh?ai5q_AK6NeJ4m=Vh zy-5874k8BmlbN4H>K__Fs4x6v9q{_1f8cjUe8BCEpKL?=&KLbdhAd3*1Fk)YelPrF zE$RrLrGIb$A-}iH_eOWUq>1EBR%jVq$lBSSjfjDNP3i=%=E^Bo&$cQN4he7^I!)%s)HfGkN>{# zM6Ma>yJGbBWSVG#4F=&%){KgRZ-wX4NmNAxl&D=xI+Q*TF(O zlO-F1p4N$$e>H7n+rGbLu*E&vzb&iqBr7(3alB)ei*)FBz=WU z_P<##s#=7jD}9pP`fI(&abD_yMLB#y<+W5(`;)CdlGlB?USujHlU4FSdi4iyq8u55 zNck+%-FJD7b$l9mP4D6%c};KX5%L=O)Mv?S^J{Jv+aY`1-1BvqZg7OQNr3Bf(BjpPAZ%WX;>49be z$03Qql=LF`#Rs6rv5NG}bErr?P#wbiGUs_7czw|W@s2+qaC_4Oy^QpoFM6QR`pQ2q zSFnyxBUk8MJ;X2crXImBgsvDJlJZGU`%uKr)V|C=^78w9-&sKfzu?~C(0;Xxf^tR3 z?|VVN&*B}-1H&cIeJ**)%}Xlla5Y(Q<*KG$lwLn_m-B1gisdUo@`FhJ@;m~_Usx~1 z;X}6@51WCMpec{^L@$!RykMed<}cS8^k4|M5&tg3PJ{6hX5lgGXn4-U0Y9dX>5}QI zgdMDcY)Zf*_%AT*H1sBX>bcWh2)m6421q=bW*yCZ@=177mq8sc<4wZDv>_-64G6d- z=nBPa@)A}V4;|-X9%PQc_kF$k-C@k14lL;q^rW*%MlkclHqjG*BM%RSqa_%f&7`E! zyJI-NlU-7jwcNi;lksqVCD+bI818JENUq$MSBEcs^4QtAn`b5UnfIMbUMI?-A359k zqmcuH@?)zh+;YA?_Bete|G)sbbN(;M0D|x+@v@4a6Y2*5AX}YH_$L7 z-;jKwzOJ&WPxr+3n?5G?yyO$29KPfez0R+up(i;^y-D(&NcrbWeav~IkI}n$h)?KE z{S5iU(z?3OK_8=@xB3`S9$!#?@ufcI)cMW-A$^SA)kFM3Z|V{J;&l3$OLFsaFFljH zd|iFl$MD+&fH3_n@6+Wz;n>ZpBWb5YzYW)w)tZ;FGJ z{l_@Yr};=<_{N9SC!p*j^|+<*Gt1<&;O3lGf|N6+z{5Ph`G<*~S3}KY;`|+WL3jZ+PtX;@BfeQL!aFK`@S`4A<|PUCNWI8wAU+QM5@fv6Elsn3f9OTn z_CsJ3cZM;2I!JAn?&@j(-XH`qO{`PuHQ3H1kPh_@5(M3vdcA3z6dOic7a=?{1dF~F zgcn(#b`&1p<=$X1KY{*2&QHKc@+X`TAL;v^;GWijPG(2%v6JV#&I?RHvx{R;C^H%X) z2wWnho7K|BopZ`~UM(oTAE7e~<17)%v|kSz{;Tni4)iB9lVG1?JEFT3kGT)cg4=;d z!s+GlKjeMD6!->0Q7{Ns7xdE`qlWtwQ3`Nx^81F=m>ko2Tmnr8pA#Xs0Lb?AS7 zLgpZvb~yj&;iRF#BP7oN!!_}Y3HfKlGxGao~_IdhoT$bSPBM`5je z4~aZfV6^p!*^4e)_Owq8a>u2)XT(GPw{k~}N$zkcyS5mT2lAMJ=X}|J^38tU*m^$k zjK0iUI?#u{lskefC1{bni5~x|a!2IGR->(-!ZU=NflevrD&cZR;iNO+83ldUc|`6( z;TdUlQvB%Qd;WMx^~c&15|aj{UYM4i5zU)_&*ahPH=o60u0WlhQ@KRkJoClWjm!x4 zn2;PX7Jg>Agy(QP@RRxkj^{niZM^Vz;E`}Tx#SVh>x*2n288+|m%IZ!4;~4!??=id zso<3>;YpcdN(wq1yF)ZKm8ov{D( zB&S54;~B3L7XPfT$ZyjWM}$w0aL`uZoeaZ9q;#5C zP#;DUm6Jsi1viQ&6nbN5LV?9{9ft4XZA*_W$!#>>wH=2oAe43n+5yhisjEs?jx@yACbM6{Ep=) z!OTO={H7QP4v7R);uXPe=G_h8d2;Rrwkz<+yJz4*P#p{b9{e+I2{NuoJ@gYmxKSd( zlz24FbHFpXyM|>iLDG|MX`21d7O!PF>A;c-K~HzrNIf*`io7()L(II$&?<}mi$XW` z-@G%^A@^M$)YH8ZaxE%*v%U_cpC$P0bttCwb6JNnZ36yR?$<7qAKR?CU$aal$o|Uy zZ|<*Vy)SY2^dxJs|7PQnAnEP!D$2Rx6A6sGK#G|m0re6Iv$7^YA1A@H3b z@Lq|3<#j05X-~4$h+qy484c2cXxe7}5R^57B8Dzm;9Zs%*P+N?dR~XhFE|sO@}xrf zCEMQbrZFltOs6b)h%%)2HEh=N=fXSs`7qMwB@^_-J6NU?WM7Zu9n`0iSIGWGyq#6vxHEiaoC*DC>BJ%K&F&$}GY|J@W7vv8;$QBdN zt)AGtJ}u4}^=WPCoUc#!^HHMni8p+yCq9)oa9`YLy$gzeGY>F%2jv&~oh{xFlKcMo zwI$Z^>3D@`+Ge>zZ|i5EC(gh0jP%6)wl_}s*Vr4^&xdvX)p*C3d*jR;BV;%8l(WS< zC?n|5ce&zpyuvIi3A&IoA`k0?l$`p8P&sX38l=p@cTY1XnRF(4$y`@|u2ILHziZU` ztnOc4SLs5%v(3wvNSXgj+2jAV>>--AS@zJ|`WeU`1-WOU3;jQ#$LQxnJm-_V5gO0* z@dPa7l(WHK>M>X$vFmfm3p%@3jsz$ z1#S=hdV;aJUF=Nj!#yCz!bR`>`X5Fn^!m)k+KKr)eq~Bu&do5rXMGQY>4u~J?$V!E ze|8z|!aO%%SxS)oG;+;i5Bfo0)-0xhkV6uKDd|P7cXk;4zPB}tYS7TziB44Zv&j7p zPb1i)qlkZrN7KCCc_!cSJ74sYp??3*>m^yory2WCVGBlEKV@#fbo8|6UB3(Dmb$#9 zRlG{S*Sqv51b4gk&MU~z0l_uSSd0>9z2BG2zH&UiPO_wC-qMBz^?C~W@c()BY4%lg zr#hKL_Lsi&8TKuX#}ZE0XFfoH2S_n^$T!%h*%mlvBi_$smQn_e;L1ABRugWVlJ{Q+}OPrx6JJ=F=n_to^3F5@~nx?8IYnM`-v{PwI zdL^pDrm0$5HP4lsLXi7N36;H40(UCO)p)Z%M{wzX)?0pX#G8AIUWoF`3qrIt{Jxkw ztj%REN3Fc>9KQP^7dxe%U1ssOX8IqZfp$f zakRv#-Fq$nlM6pv>E^Ltw*=IRhukv{H>VtLcfE$$fitB}H?4JW8DP=&xY|KU^-r-5 zxU%cUWr01e2jeW=d#(SI2R~a0C|Ny)xAq|`=I<1caH?tp>`6E7{C zRN^izE7zt@n|?*bj4Q92IqT}#*IfJ6ul?Jc>#nbyS2cgZO*dE9+_JFt)LJ@W$6-c!EWVuZ=TamM7DI zc!TgV$|X1G3eTg-J1p=0F=ns~LZIJ-AF4;DHUu0)!ttZUuDG%wifj$K2XBH6ACqE5 zIWV*Yk7|UoJah=FF_cfFJ6`a4mhmh+9COTCE7BQ_hvCcv#~ekldU;J#s6&gMZyr%( z-#6a1U{IR@JI4;@kER$~aFRxhHK?yb`ole$CJM$FTPo+(_ibz`EbP0M_z>a%1jiO? ziIwbaZN=`-)(8XZ?9U{H*j$Tz|LgNf@;|m8*^f5hjhS{cs!+M zZpGrJXu}UpD9DGV!EWY5H^SW)KC}{eX8tGBMAOWN*1*vUzuq*#vycdCRV7Gz(k)H1 z|JmY0?9V!|q(acs2^jKMripb$zM!x<1_eveHc!$18vV7ZwxQ(u^sz>i}uAI8gcFl~r82)uPIKj;e2qscog@BPu&nWhlvU&{!!{eS-J z8O&o(+F#B?B@jocHM+bM3u=SSKWM`&z$_hzxemX|%z7M##0pse1uA6$Tp@p{!5sRw zl2q9DQ*_trl@`WJ#{DHwnxI7syxn`2TR&ZX^oF?W74MZPWl>$$3#h%j7q>H&Zru~Gxpugte1(D%j%4_^ zdiMkr*YfT8)q4UNj%K&_$cykPgzbek#i=@-^XfP62~2hj=#Ut;eR}w=BTso1gzpJB z9M#jRr~ha5vJ=XKmaaJKA1<1Ctg`y&UGF<%Poy}PpHLrss%+-r_wRV4t7dTH3G1+5 zbj1zMtbVr4d%}{iw(CLbuhQq0RaQGaKks@k>y55O!?vXVrb|_ea-Q>4dagX6=1wlE z^f*05ql*uyd6Os6_o6XF53H^EQ;nJ*o%06Lxwi8CYBl#ym1&o$`I$A(dEWPYHIRus zMB(k0^n}sxd&+&8l`IE`w)0S6xiTj3u6Vy_T3fXK_N25twdhZkd{@c&OS`j1Ey{bx zS=pj=&3WHrdUN!ych$=#=Q0&LI+dKQ@2Zm~=QDjTb~-CQy-2T%s+9Se>WP$kC1=X9 zOI}i)g`G3~C-a^2sykVtU+b)@QL@zhs>-a&_bRu-b^WmT%z2fM$7EKf_^d}3-uBCj zl2EIv)l{n~daYWIzgqu(vw3wd9DC%6z zV-$B1nCZ#5B3CH=z^h^c43Ky<5fp?1h;%M^_BKY%M}8ZEZ-wX4;?pq?< za?G2%BqS8eQIBKY+?y9PG~89Q=%&TW&9_n>7M=}v&Bchg5Wx+1K|-vWTU&E$O+&qK z&t1C62)lLhqK4|ZwF?&A+)$0M`IUFp*4$j(AY>ix%%*Z-v1 z7T3f0f7$gb{J-joe{fA;o2vrTpQTtaO3}nj%E0Njc3vTk^Gi!3GDY~H`~KmpAU$6{9L1eC7abJ_j;lC-}K<~ znj5fOS=F+~vRvsWLGsBGc$o1#aGU$2#QO^T&HQu?0x08?ubJofz-tRr|UUnxzMy#L|u_q9aW)Zr?w?&X_{P*k~l0= zS(~M>mt0dieL76GL$hqk@{uqLmXgGz6}J1W4^Sp0t^@}xXPs|`_7lt%7d~Ootenr0 zv$A%9&N6k*%0YH+)zT$P7A%6vDhwjctFIp)<~4WT(wp?_t;gfOsKtv6LQC|OskxK)4-_N?afxhxjsmuNiI_ z0%W}Ha7E(DFd|C(-(V+Q38Xh!I$%n?!?2t4u?EB)@MAt8Mh46I1nfv#9Si{+>-sV# zjzuEkO$m`!nzD>Z(91asJW^q&{Lb{TJef9GCa@~4;M1#UF+kFjZfTnR`(sRGorb_B z#_i&uhb&FqgL9N{{AhvCyy+lYzwY8%Uih3SR^*+bS$MdXX9lj_h2zHwJmRoS)vy|6 z`Pn1z?ZFfCq^w4y)`}JyPT$;ONpCEa(b6_BHy$T|g6&8nVy)n%n!fzB*}Q-`7_QS@5R$ zpIBcVo%Hf!CypGmoJdWH-lyaw?z4GHJzo#lDj>Dw>~6DlpDbue3;C%9E$Jbb(#95P zmRUxKDD*$h=iQ066>5cDY>t_(8yXyEUtZCtbSTF!=6tT$RL+v?6~RxhVm+_{Mqv+l zk?Xa*xr2R`Jl;H?n+CUeta$-$wo?f*uE_aU2N32+B$yJ9Ci$WS>d{)^Adlw5e8_Z| z$C@>8a2%8%=}EUV&Hnu{){qB;K;JjQ^y$Eo3c+Ws*RmgwH!8L4)^f5$hrtgJk>m%m z|JPM6;YWLWpZnw&^m*@IfnKP=xexd5jr)s#=0I)Jk+Lh5%s&K_l?MWK^Cx+@GV*=z zP17&XR%6{oX#ck>jsd{hdC33WVy$vI{gmuuz6qO)wb8-VlxMuf!hStgft7AGUKxFl zFKHcdzcyVrOEle_ZMd&C+)3+{Oyae6EB2~=>Uy324ee2@l1EskUwOqd z?s>j!5ers;vTyg57_+pf7F$<*R60^KOT(&9EGa~_ta49mpCzzY?ucqRbZuHdoovq; z+g@J2T#J9JQOnlsBHr?hb>;C$u@_}j~)v@2|jchcjAZ@arehQ5cBQmrl<#P4_P0^46`)xQ0z7K#1ZcJv(Kwd zb4#}S@TnzdjgSGLmR+=;^hUYTgF~`d~lOWpw>(o4dm<-|_@T0s(96pS1x?#$A zZAiGJfuNxM>##E#IbR}Pi1+Du46iltB)!zr&}%aAUF|K4BE}xZ%XBaeGOw^I zPsb?AGqe~W=}EUV&Hnu{Hige?^m)*>U?j3M_1HNN3YYt%gLO$vHQ1^peoO>DGHHUI z=1Fp`hh@ll65|WC7juoW{36})VqYke&$i96vdk18=~P6xXGgfNi*S1)+zTSy3nSe1 z5$-!8-1kPf?~ial6ybg>!i}+C4C!+8kKkyhGOxLFPho|j$qUw@_QsHN(wv zw&SMs`7|-FVSl$@q_0=fyxVZEFw942LYP@a6Z4^MG}9I3XEgEtyEMT}57NXWi8lk- zG5^V|{54H5K4eME z$B;C|0?|#%Sq+QzLlV87ktobB&}Uk`ud_|gK_sSm)+F3F-8~%WPd2l#NRGx;MiM+*;!PrTwvtw7mR) zWnd~F6(Nw`6pf0()ezhU1_#-PmHm2&xnohPPfH(r$z4o#*Tn(mbELYTxog6 z-O{GEymI2`@tGf;T)JsX)P`(rx}bE87QG=aU>Sl`#W%V~x36`7+#a>=IuUkpz%ut5 z4I!5x_OV-$Ud1`Jd}AQZ_1pH#ke=ttOAlMDpR}iCSX+2gZ(jb!Zc9AzbMTawf6_jn zl~Qw)`*&~MGVJj!QR}B^md7cbT2>?8^(Z-Fch!|!MZ6biKkj^>{KQ+9uT0aT)^FNE z%x#@4oA{>Y2U4^Pw1-=-XmSQ7UJ}(^U{N0*s6}9)mF zCXMPYv=s&{aeKDE5}4tdtxZ2{jmu|#hN7m2t`+&&Q=aqf58Lx5Sf)%s3q_8nyaNAe zTD(a4B+a^ksj#k7pQ8CL_SPufgDhwryz`w3%TDJ6|1KRKFcZFZ~hixuJe zE$Xp5TR$1(QgU8yLoL=T&bn9Py`>L5nn7&7)$GpqD&0x80ls`qFBMB+LBKK^wRg!1 zk=vuo>UO#xdR?S2*0(hyx;sq`wXM3HQKH_J>~3GKrZ~|`r(_QYg-NuLLLJVAy28@< z-PR~ALCf-0nbPgVETu+Ja%eGPKC?5R%-V?_w9%dATd2is7|?y84fQbm``gj>1~zSH zs~gzrGRk6)Z?Ruh=+xxoz#w zfuiCd=5lv|*v~e{U0s}3_A9ifKxyJIn>Kde!0|~3Vut2wX)a}CQLvpaM?RA#4IDjk z`LX@c{(;dk;}Z|qz*T;bp*WM8N)Ibe@`(*NftBR^s6E;r6Fthf>t4P5Q^d(#W=q`z z$Dswr3_GB=$Ml5l+KZaa<$QRaHoUYn*ajKbi`_|yKk6Ph@cDpk<=^)IpgYOB*gr5T zr+Cwlzoy5GOFrPdH*@IlQd>8MlC1b9_u-T*)JDz_OQYL*>^}GL_9%Z$RQYD-!w$^~ z?l`=Ztxf&PNA1cb+kC1>jncNfsqU31P01;0f4wQ$cEdXv+A!q$uI)KP*AG=YP-g7m zIU?r;YsQXWKGJu%Ng4BZ-=Jgn&CEc*N{e2Xk%tzMjQp!2|I3j7WaR&F6LD^o`!Q?O>Nb^qZe`h4^|hgP>U<=B121KMp`bcZ^b;i=t^4Lsu8*p!V_9d9Sb zn4wYR`6HB$l%}%7DI-wI6&aR?+|O_MsC{G8VtOF}<5rHY@UF#}lU~3)tp#5Y`~Jq=w=cFu$+^*2SDjzI%00pt-JNcU z?k>P6gP4jQ0$w5J{;ztKqxXB$V0*(mA-mZBiZ?o|_{hn7XCCub&OD}6ZSfrO{AVDw zqkCEY^5`zN<(lO#k23C?2Yw%jUAg6(-W+REo$=q?cMPM6ZcnXXg@d{ zN6u*9T;f;N`tmgI$L+-4@{kie^ab$!qYn*s$N8RePeILH)_$Zq|KWnbAV<3U(spIs z>;r3?ZrH*6DOu0Bvz8|uaBA%F?AaF<=zTqu(`{|a$OT^JnmK-;eP_VoaxVXK=LOv> z2Nt}0YT3w{{ck!s*Z+AtN=C^P{rAV6#o6V)+p=@p?OBMArBH%WDE(IF%Iu4L;cc$2 z`tHv9>XkX`eLB4#bUK3i5sVHOPwCuT%@Rs>*}6(Z`80M$XQB5ddNV<{{%YtE5)#1K z5Q|cxI^(l`7Kq&?%le3CYNsu$6F4y@oan3%#rSZ4Ya&L6)_}#^DAK*FD>l}pH8ioM zVXUx^NWTVS#Z@L=x2D{=Kd#$mwKnGuwKT_dr^j1XTU$^=@f;1C+{4>%DE}DaK(3&t zUaV_1IF1Z2RVV)-Fr!Z2le?z;y#q?7`tL5ysVR@y1$LAeJ396%7r&43!rJ6|`R&c6 zO;Xaa4Xs!Po_Zt76RlP4PO@C+v*fMKuyv;@h<^yjCiX<04lQk}SY{g|z+ z4{u+A@h2UpPX{USn%;j;v{yW|`0(5Lix2-KzhW6F#A}KJVe!pq-!qRDyBVu}S;ey7 zcKTm=uyuf@ZXD1(ELbk!S+-Bwf86x&mULSgN0}v?0yf9gkNivKw82(v^$)b#i{Wl4 z^(R@Mb8ia7x+eQl<9@i=cD!!(15IU3)}~E?XotFPvEQa{3fMiH0tv;N0*NlcmDcI{ zvba|NPD|6bn>64iI-H<1^H|+C_=dWU6hWZ_@7Cd6vHw;TdbE|M0BT zzB4{XZC~EBb#qjAlA5EBc|uB(IUTcX;WEay6Vi~HKO`NLT{}8Uo0ObCw_CvB-UDw- z#hWZWQjF>z6h>#^LpzawS)vPphQ{~Y;je~^i*YQECD$I)i!P)&^-!eaG7f9U=FU>{xI5lcU4x6W)*ip_8ddwwA)6Yv?(!lfi}~9b7~$F(h;^)XCqNdU^c1%) zQ`-bzhR*3!oK?#n@6>6a7F^}-*E%_oIei_E39I9LlvbU{Gxf($di7F_ftL1CpR6Or zzufy-<)N3IUgN%AYy4-Yt#KLOgdW=1D6}y<+Sm+8h?ipI{YJ2@Sw%T3W3Fz07;Pt_ zyn3zoHAY>AT1$GH-db)xrMHn<#ZFv}>p`;Jw;bZcjL%`e$;YR%Ue zH5FF#LyEJkrkbCU-XYHklmdJMSYUAyzRcDIF)?&?3{I4`B zImQ0v%Tk?D%{v22T-U9ReLN(&EBIz4VZf=kY1KI4(Pti>Rd0m!2ONn z0tFkDQPVfgc`2@WK=&bg+|#4b7npJ<-_IG1=Nh~p_q5_1E_z9;=p}k+wh^j0N39#a z{xbBTCq(GZzzZd1JBF`&TGVCQ*5RTQMy?yTVfaRwD&|CSjsuVXwRmToz!?WRj9sTk z8))UKmn%7c@MUOrNHB{3oyKv_?*vBV>LvM3(I2}m2o(f%BacFufF4LF}nF?#S%Mu$< zbAH(sYk91E&%3sqSgZ=?9f(4jVwa}{ERz}cx^9bN_1|aRb>y|i@d)|may5Ta&Ym`F z-OvLT&6SC}9|k93^@TVw9h0()k8WyAt{W6kze1n!Io57fIob~QWWKk%E!U||#5x7wa{vku3;gk1})SmTuMZ z@m_1ob@Q$Np`TMKf&`g1Uq1)+&6XjXtA>1Yb$(fj$EDpWWGwP%0(E$|x1@=lcHgmz z7o%IEnxk6AYtBpY`-ZPC((an3%XPYMboa@LN8c^jX!M@d!#9oy>#Mg`jM^YuJlopB zD{Cv>42)g*X29jWWyXQP2yaxkKmI9gura!qXl|`Yo2JF?6TJXB5>vf_Gs5sC8FQKLF|nK;2@zH+@s;!RzlxuT%4tF;k93 zza;I)+D{&o+-b_O&KF}=yN?X4Pw|{QcwUZ5$@5HnWtB!8TFB_&=C+2jrmR&jb z9UJ*l)ese@t<+IdK2CUPXlIDVe{Pz-DO;N;`aEdezTu!F*iY{}HulA+7Hd~@-1hD< z1MmCz;uqOt=PaA)9~0+17~P^4MKzD@tN8gR!GH23tqwd~KcXIW+zaF+;r0D`MZy#5TG^3D zt(yWrb0s;IQSr?M8wWf|4m+Ux1$$icn}I^q{$y_|X5FJU6k*jiL1>dwHjE1LMsnPp zfp2t_VvhG4aQ0R1;v>KH?mFIBl9-#Pr4a8|;OxH|(Cta6!puY&J?y~1(Zxqg8{@S+ zEvX2Sd&0mRVg&XlO^S=#b=+HAk#VnUO_!P+-BoH`JuMx2&g3L}ak_UH^r_Vt`JaS@ z^&1N)55$~jc#}J^ea!lY-5<3ltPW4tfR^~xDP;qi<6CZsjc;zMNG*8Uy&9?gnFBq> zmGJa{XAdBU2av;*vbDz>OB0J&62mt*wY;#N@vVrS@yEcS?_=h7Lrllgiq&Z4H^eLc zx4ri6RC}g&o6*WMv8JsYeZ#A_`NR8XX_??jM*mnpE7(`QQMMnF!xbV&1G;ZaR6FX+ zzvBz#?PK50z-SGvZMEo4vZ!G;Q;2;U`aAddn66-@R8>=*qt+Q z6H>9gJ#LlGG3UIr{Lf6=$&dfEBS-t64=mc65AwA)4=QbI&_@Vd+aQ?xlax#EJNEjE zMeFNCIlI^EzB>aSqAl6goq@k4y;T~Q{`eMU^d|UuwP^=l)ZFW)ZG^`4SL5-lq732K z6qu|Qty`fDIKJXuwPP}72nfr0R+P)8fFpN|HghA|be99qY9V!C_L@80jW`+|9if!m z^Wr}a=4*wfT9h-CO@R)?@}6s<;7E`z1UH)LA04;t&%=Dl&|Y1*uV@|XiD_@tFuTZY zb{DO4ug~_;SIsJR-~-U#o3522{q%9K({%~%g9DB~aQEbm1CB4hlQoLecimQ=++KlR zty4*YbZ%~0qYsMqkoCLHN6X{iMo*9XdFP?+J3mRxRdNRJ)2aU!61aQ)w2jc^iCjO$ zTxX)3l8e?qiWHzEa#p#MeV3!G0-Xbn-(NrA_;;5$wl}+NqL+Nq8QZPKV%FWb0ka`f z8OB4~7_XNhbINjjO8YkT;DlFve^Hzdx7ycv{$h7pjrKRp)X%KYVaK;(eddH!lmbr% zs1A$aN8NrGCGEVG&X~tWJU+5nAM00SyfIcesxDWY(anV$ZO!?2I3PQJZ~2mpH6iW93emsuZI zCxp{Du=lPp%8}QWso%dkkmXm}{@bP~cSiUAnDNZ^zP$TcIA=oZuUJDQ{yvy*l(;O-O3LJJ%6$j7n`Tg!PV^Iu>;+{1;gpi^C7BaIh9mbgj$So+5gdl+FEm z=A{pMHbXptgUyh78#QO{pzW#azZYrnrif>BgG75Bv^_(#>Xc2Xn+HA9uV=Zzrw=PI za%W5m_?NagrcghnY<~DCT7cKLGhvhOc&amD9k24<=N(f*M~(5VZDt-YuQKL7^u^GQ zqhD-OoQ^3=k0$u9_h&q3_NQ!-wAsHGxw6o+c_dPq7J~oo%;(Ot#oZ)uG&wd-ETMByPT8hA32-Rkv2!?aSiIrhwu<8RZq zZOyhHzKeLr6&dLBb7K1A??vXd;uE&v^W@$AkG3)XuVAHOhPYR23z`nYVk|Ar&3`6+ zlH(C$UBaW#V_P$}n{y!!jD?0h_fq7_wXXFThqV5nv$T2K7?!&c{y!ndlsREX`WWah z&k9~$$%)%0Cw02IOH!UFPv~(Z7$3YE8q-{O`P(lfk51|SCbl>HNzbY2MtJy&k`rZ< zHkD8RllR{-gEGFd-Em>vACfn5*0E%TBNwx6&B^N)h!9`9BR6^7^?%6pPyGY$*QWAU z{3!R(y&sMG_llFJDvZ2}aD%uL+d?&=yigIIAvnanbL6?#Ca(YZh`Q1%-qq_0u4$|1 z(UFh5h9{e>H=8gsJuP(a$?)@kIGQkG&heBXEbR+E{^rM@9(CkBFX|eeWq)+)Hum?Z zWtrbY-S}Rl49*WX18x@FY`AOSD&ek!n+NCf?mntYnPr?lDdAC7!Yo_Xhed6#^%!Y; zKMYkFA8ZYwf1AXTcdf6g7_@_<-CWC-=RJq{oEr`g zIqt?fiCHNhw#~;#c(gzNIbO$qcdcxO%qyK!F6!bvz`WV>dTHF*<+yN?e;aHvUl(GFf5qmAHm@C(&cc$%N*+iEA4tJm?v@LY|(M8RU zDJPG*H-7ENwa7zpu4BEiZc6?$A2!V8m5qQcE^YJ-oTh=dag`%_&d6CDo|1>o5~-1=c`9w=}s0rX_6rP8cSYO`7`pr6+ zC~cN+zi*D~gl&p3UZMBX|9Iu`ycNG6_v?Rs{m=pTyH9td)ZX{YL&s0NIbh_>BjYZa zJZJ9nuP+)o{lkqPy|HM%Unk9<6J@ZB{dODDAMn6~71zkcWDwvS%CXUEnfdu#9Ux4rw7E4`!h z7ruDae{Ia0{?vO@pStMyz1v4mzbW;^tQAlFG5goI{%FJ0^6w4b`5zmm-?s0?XCAyO z_>=LoZ~E=k`+u_GJ4auge)Sbs-1DPL#`Jsn|NHdy>Q(*kJowy^>0kNj_9w3?9$5X# z8)NDQ|8D;IKWOinp7LMY8m@@>i%kF3K|6gi{nV+yoci=sM6LQU)}j>x39SW_B&pkarG@*BJ(Tv&RbA-@aK=DKmGjH z!N1?;AHMnr$N#c%=-MB@`>kL9`MaNV|KqdQmQHbA>ezY7;z`SX{+oy23%z>PkJfK5 ziBx_va?vktTeNT5e?I*mr)FNz{PG*cD$m~VcXv08+5WwseYf5U6LIc+uMYjE$+2M= z^6&l0V0)NRyd~|lFylbN>0w))#olYGukjiXG;Ze7Tk4nAH{InmywO7g(MI{m+SAr2 zr{Nq$6LG*bTZ%5hK?&a}xq)wy#Kv7H;>3Qe*K#{n{XBbIK2Mf(3($JE_5nvpdf~G4 z%#vUHoHE8LCSVT6b8**7&rF~1TxhP9*7^Sl=fveNPp`b)WEa=2lECt~m^?F&$k$5u zD%Wbh^UJvxMP3}Jy~N{$uOz>I{r7=?hW7q&p%Mgag)2!?g zS0~)>e!#T`+*hT~zcVF0+m|{={5Ok#{hX6=&si$?uF=la&l!ugjB)FVFTKO%YIERf zXMn}ht>-Mb$Dqe#=qqD#fr7AzHw>w((z)MZJ~b7 z(z;u9FWBq>*b_$QShDPndfm@g2DLmi2J3HWGSiu)hc8{We97Xw^^hgC4AVpEm)9++ zu3xII6e%qmU*EXAdOY81z)R|8$xNBlw5-kyFVe$twYt}OyG@)`wYV0mS!1>|K~PPw zu4a*TQWX{qH!WLSiy-rL`nn}ebxXOcsp(y~q`Hy(GV<=a<;$Wz^A&v=6>}P-ikI^H z>P7o6>U|69A2eTUMf_wO(U^Ck;>oe2+;G_ zrpco{pz`-S9P9aWBcc^yij=%xBS4qe0eN18vHWP4D0w|N*5&O-#7TrHQu6+Y09{@L z@>D(GeOB_4AxxLI2lHLD8x$#d31HIYd9H}c!xuo4l=%w-rp3mj|ch-EET>PD4G2BkvBIyy7dd zZ=aMmQj_FGZ%3PQ>5hm%Es4$n~<-V zfQs)O8{enkqaIMC_};VeWkOgyzK?8t`QVF}KfV_TR_i^%0^HOBl_-$uGX8wYr=lvs zw+gyVk;>md@agRwE2E7N1hD)j!I6)}o)12p-he|vZz9pj$^&GYB>Ve+9^BN)I9HM4 zBWl4$K7vHhx&2euf}!~5d>KfR2YJ2XG*J~%~gqsjB# z^jQ7`@lGT2#PPIKy!Eg1C))TE4eD6(UnuyYR5jvWVzKg*3@_rN{3u9``2JulzemU= z|1EG%afhQP@O{Bp{$$aX$WNQbX^VBi(un1czF){Oxl>poy8M1N{(hpqQ9k=Vr|oS> z?xPYbKi&FnRKDP+#StYJYECSFrZEfAl<$ReikgK3NiMtr8OuLF?57>&r^OH@7g}&E zf0o#Pf&BNuIb&Kl>+c{N{~+UQ;3I#l;OA9G$py z10VU>w>w2`!hs|gdfZs~IR@=W@^hZRDSBkZP5HxZ{KJhElK(NF6Y)B^46lvfYw&$d z%4gr}M7&Ne^qjHz8Dabj7|36YKd0zfqi49#Gsg1giFb_2&psB5jg4n<+{pkzP|g~; zjFGnUM;hNlJlWZ&IuXzF@j8$s_MB02q34TD|02P^!%|dc{2t9udHha|NoIVG)vV3) zr&&VH`1zWj=NDN0Gke}Bx$vmjVim!oqLDaqq4mbbj}iIxSl4I9pR^RR8Q);_x9mxy z~2H^hFLqBb#0leSzNMb%SZT|CYe!MTu zS98Vd(sI@a!1*G))r^^OQWG}TGz}v7wzoJ5doA+C?y)Gp6m+R~5C4*cFwXN)KIDER)5#(~(iQLK!vHU) zAL+~>;{Mzsak0cEBJTG;62adl!{3*9LgL3n@Nw)wzO}@~c*mcJa$SRdDrE`Efry*V ze#}{gy`qT7H}|V@)}g*L9{Cvr<2Ms%HoS$GK_i1PP zO%iuVd{ZL(Nv8iPaUlu^{iO4HBr3neH023FhygB|c3=_zOhj z|9#>}^ve=y2J?P+B<2%Qzpo_Xe)@@!M;*)i^gI#g?vl8dh;lw8{ln4e@;vtI%y%*I z2JC4k{WFNT&e_smNknHN`Jn@0*P!dvBU<6O%j_W-Xk$2ah1e1 z5+9bhR^kSU8zpX$xK-kl61Pj-A+bf`E{S_2?v>aoalga^5)VpjllZ2@4vB{)c1k=V z@tDN-C59y~r`|^U-zf1hiBA)u9}Y+q`W#AOEA=%x$4`kkkNdX}Q;6Wtl>S-73Frri z&^s4W?>3^JBr==`c?XGzpD6Y2Vj|+dNksSoiHC{Ma~~1WuMeRfMZa1^M0lC>b6i3_ z#=ViLSMQNXJ?0FW&o!9meCaPBf~Q#e(FKUTY@lide}I?{dD4FmvA;PFOL| z=zo)VKK|H_;CB;;pj@Osi#QDWS^5i!Ua9B6KZE`}smI_C(0`%SPw?ME|0wjsMEF~X zW6l0uq)$JFK%$)^UbORxNT2r`{w(4YT(9((5sT1|NdICY=FvpG2EVA+nAa8c4}MYq ze7OIT9|IV}>4!ciBA)viI_IFjk^cF_Ypp$g>X$BBE;ds=>mEOaQ!Wu7w(_2RkDnY| zGsxOYk>9>6+U=QbPjStR7LrboXKq$<8Zqi*@~rOV7`#{8}i^TmC{gf2$` zvaM2=%l*T|7dZKm^|R@gsfE4Yr#WKg*3vEJcW`g(!OeT8;i_U^b$5xQ;i}X3US_!| z8i0e(U3Z9OCyV>`qqxZTmuc+>@4F(^&Zi+jZxb`%_bMi!;zJh~qYs+V-c&n86|(ff zOdKPs0U#)d|K8|>E#SlO%_5a2qOK2U_q8AlCevr`vm8Jsu*IH5N}d%U5A^WQOCN}K zD$-*~MJe7s%c}je&YSxz$9@>s{4%a=!=BUIFlO(1X&9}wU}AcFOo?T1CDsw!cZW6B8rvj^6+#{TM-#V6J zI5#BDOse>U7^fs~FF`RjK~`hvY~Qk?&B5!VzVX7%F0Hz{eD2(mtIFpZU%Tn98(6Qt zcGJ>phw`$gGh)QN0|ss&T0v7RVWdeW|UIWNO=@rW!&?_z2oMqUH_UN}Wc9`&iN zcelzmOnJKAy$gQkPwC3FIL?Gqq~zU>0A1c5$nzqM@^EPN3mb4ud6+^Gv=#sP=Arnf zJjQQ><9SN=?#Ho83y0S6^EmDe-)p_(I}(R4-u38 z`AN6FQDa`886V|g&5KgJZ(r3Tn%6>IMEf8FR75%J;TZ3QGrx7Ew06{nIK5Xedw^(X z5u^O0!J6K;2jaU{DxsKeE6$ek;+x3U7qGOmME`|+b0t*@E`arn-?gHS<#(7274*1x&bDwq+<9Tn0Y|lj60@it$s8KeOkPE+%3+9U_OevHfy6K(G zWKFo7eXLe#Dp1R28ibl3-hFw+idQ=P5=p(>6+=h|e!sXB5FJ$Zl8Wqaa7CNN}h_qAFva*ovDULICGhbK#gS)3@7|#R&K#!WAib z%CArl|GezVuu9A-O*5b`?Ml}9)9uP+o1KSlItoW z^rKpRN~A(XVLQ=LP%kl@eFnpEidg3X5bHTuKe(=gI*UkMOXNM{`VetG{Nj9|I3M9& z8IMa5d<7E6N-UH}okuxE5`{c()Fv-xIQ(TqWCAw%#7qC0dCW;gz5Z4u*M@*Bo1F8Q z;oTV(8M8C59umyFW_628+2sE`%70NHP1xja*yLkilY50t-V&ru-V!iywR5$0+Xe&SJ|`&1{#XcJ}XDtor?Ow})yt;#y1h;5$4wyN7Q z2hsl6PBGLLJv8|cB)-E<-K}ijH8}RdDN^!gBS4quhKG8C@^oAEPWUO$Y>rslj$_t$ zMM_>H0(5!&ZljXNe5w3Bf@At&ZwcCkeiAh4+xg<9%ZC=s-`V87Zj-kMew7vu zt>gD_OnJ(tB_G?VBA&x|>TaT#FC z$^%qsK|Nd7%IMjM7_1^SJ_f0KM!puzZ5AVd*Ya6&n_#PkqVR`B9wf1}+95ua%=+VX+xQ*)%$87U*odh0}ymcj4L#rj$z7NyN5 zqT*E&VV|+SGMsvn;lf^%RfF-ow?yheCkBs#Uz;N>W;pyJ9Wco?X~Gun&9}oRO`X*1 z=gMuSg0<|iTxgM(cV_O+^ry|t66;tzKTMgCiEq^<&!pAGFa6=WcjDMxVHBk8%f>gD zGGB7cXt;{kMH00fejYn2vV&aH#$!W<8T_K4Ja$&3U|+>-T68fyC38z>&J-ub|6^Tb zI%jjV-=buGH(Py2o07-Foh>caccw!*4#Rm*dRjkmZxJMj_sN%z{mK5xF+bhd|GKz- z8OM99`&E8rw5S7mJj+n`+s{|mt)G7mZOg{GCfSIV>r0H)Kn+8&?pJisDX4%p^)VgMIj+Hr$H_9sQ(Zx0DAxf2%qOe}I z@8+71;!o2TGT1)uG?zeCH&u^c%q$`C*vJ3oSIldwYMSn9sEZ~lf-#DJNFfSZ==veouMA-gR&)+P=0fLmgQuuUvXo%u`FT!=ZcOm?` zyb%0)dsFhhhHzb8K$FLOsr>PLUEag+GhUIBcMk$|c|lDctqdh^6OMIx8)O_nkdnu_ z9-VI^{PEI#0pWVO4O+UiE>ya&+vIJ9pSnhoO7}Gc=<=E&k9=M@S{q8@;;FA)OcVI{9ZUkDt~E6l<6qG4jijE@~Y!uz2uwROFr(`gkMa$ zMNCkVO1A<``t`2G^;Uw%3kQ?Iy55_lJlYU#6x_bMi!N_T~g zuMB<_M|O40xqkdC;yXlJEMJsw1H$#|=)`q|z~_ady+e7t4^M#)d27I-pd;{4RvsX{ zg6!j;Y#8jjRiwtpAVgW@WhRi=2ms59>9RgDSd|G54KFG?_Zm~A9jYLKdU#)qe_}@v zZn5J`v|cc`QR4U~mOoMON4b<1G|%DMj#z$=;E%Sm=n>CwfjgEz#U?*CmgAS$5M5JJ zUO!uWKbt)J_$9-}pCS08QcoYR#HQchCZDw?N-m7PV^bVx=`b(Y9Ab2?^Jm%k^%lnK zJI@x+Cp}T(emk-04T?tM$b}Xi8-Kp_UJmPkBj$}3@(;H0W1)pc+UXs z{wNxsVmu)ItkVNfzaEW=?`J*pr0fCcQFa0qF^tbNqVoD12V^AW^@oOhGsZv2I2z+W zPt4IX$mGY$N7F#GMz3+qL({55M63Z1X*lN1ONEInFFkJ_`}yc&5Vp??mNcy%-L~tis_H@`NAq7*Dx^AIN)5KU*R( zTOw;F{a%Ur5(QtOZ_nj(jKyZ5 z#tiXfm^r}fi=on&Y3;MFecke&j0Ng;RtF+bt;KyL4;}sGaI7xMLSQ}5hf_p8QVE->iN(0I@w3^FWf4Hy3_gUKkNxgi#*zMLuFJoNfp1f`2lcB9)fi z4m<`1rmaZv5p_H8VF;&<%>I#%>GHamH{A~0f(W&a08ug5NWUVL4*h*$2gc3}Gj~y< z-4`35C{`zUEf&+y>oJKX8YS9+I?>K!Ir17J~3veGm(yLX;#Nr z6>W}HRkh2^wrQyLsP{@DH!0AqtOGCn}z+w>O_lPq1@SXXDh*nd`C zT6jsJ`I!3bYeD0^*WZBm`V;-eNWRxU#6Qw{v%f*U**_`JKyyP}hpsc3e?n?#k!W0W}#cQ8s7_k=)p}d3g8^)}IoIIM(;ev73%ef}L-+KuNUKl}MFUdOjq zqEY8iXI3@J+yD2fH(BnAl%BKeP40`wwrAIyS0PN-9a-?qP{M#p9`&oPHy1!2+bQMg zdUGE9y58h?Mz13(ExXOP77?{LSCQf)>U#4{2&c_Q+lh|(V?OLQ-w{M`oUJQ|n-@3Fn&$}lS_WpTy1Zja{^tAmMv|X>!uZZP# z?(`Lw&WTd^`yB7GEEOr;V%JsN3zU3zT}2(Fx7RZGy>N<@JiCqesV0vtjC>xrN;pI{ z00hLvdpE#fSqn*e5HyobN(j(j{?yTd&B#wce`YU0LynfZgphy4DI%nM)e`8(V_nT`o%#bQ-WlHVvO zZZnU6@X5&!+@B0={I?!Y!q69MhJT!0;~QA)x%`Hq8KXw~-`qEB@G$>ZBkpO>4#^9< zT$_i$K68vIs}I}|EWyzY0mivtvkff03P)4@rqo42!96r%Ox9sDB%#M+ymTzQ;*xMu z;`jeEE$=`CLvJrb`eV15a0%DoJTsWqUqxV1kP?TNdL|V6mx_^btPGaDJ|?C;q3C@a zlyYC1=(qKpH>bRQ!2I%}FZJB%PrdT=-A*-Mra42FwIZeS#v(ws&$3{j6(P*7L)ri9 zdc+IQG$jnEg%L&_s;-6l#cuEM+f`R1 zT#=He{0jB(zR;oZ>^K@)T3iivP3f$xclg5X2^B+vUt4(HkokeZ3*WA8 z*lVt7WCD@hsaGdrN6-wR%{g|?_|;^8#{P_7W$gdXF_*Clu1Lfc`Xgu9AC&g7qIo!w z`{Ug2s1={6jhVA$nU|zzuS|>%o6n&giYJPu&3}6XmaWwZAHKT4FGyP3jFN+4s5^b9 zYQI$L*m#c=Dcxw-wY#KlMDq~(lYF#Ks2f=|l@?foW8PCmO5Pj<=(=`4OzcznQlDYU4;C7196I!JmpuYhkstWd$vl<>Iuz&Gd-^U^#NU&-%&nKKt&J0dg-^^cxq_k7w;HKgMSfQQ=j8!E2d|^2N1+|T_}$UOqVnp zPM62IN-x4#hjjhS_O0vZRq(T2C^D-p*FXtA6>RLm(GtsdX8p{))e9lyZ2EZ(^2aq{ zid4GFuTT%~3;j%;5hZgzBHGSWX__3=&$0aGI?5=&>5txDmUNWjJx?buuZc+g%(c3T z7&bzAfb@@pi}EL0?;Vnj@lqdKkJn{ORjQM7tI@d*(Q1`pF6TWUg!OGW^eV55dQaH_vRjYdCoCUQg^HCFl=%o{OXFD;BSLZiCK)ivO@oj!S@2b zu*3PSz>Q))!ZX?HceP;N;@g>{j1%7$axzCA?h2+D;ctiB1;&YaE4C*W6_yw~<|K8m za2yOi?n`V>>oi7(PTUtdLSI{rkbdLPjL{#w>nL&*J~4Azy`#sI-c)Xc{}JhP28FT4 z2em7V(Lar3b^bJx+1dCup4Z(Q3Qt|}j>pmcif7L8ZE3TD9TCsk{cw&v*T-oe3@qIr zNefj34n#b~uSU{}@5^-LZz$g4TiB6@TzJDSJmJX0Xv1xM+=grR?DwzmAC9CIZYfV{ z_x;uw6*_U#i9Fs0W$*DJ#y&f^v4h{?sCpnC8(u$vAM(d{^hOS*v=9w_7 z?Bx$qoiBGgQm&=^^^{+llYs>cfUX8fDg9E>bY}q=f zZBI`|M)8T?g%$?4_oTV<&5<33y{#(zfsvqu+-SvB0RggTV-j{Q_)(Uct3h z1vXWBCbQhGJz5cb>S%J0BYAMxm66utNxS!C%kyJ8-8~*xZT&W%XP>ih`pMw)WCPj zjpcW?XCjsDkZtswDm>Z#jbPq!x9b~$T4RfE`bV!lZ;YLO@)ytN`DXad3>LEu8H)a*H6}UAQiDPS}x__ObKCz|sTor}&$@ zicid&yU}-k$M&>)aOQviA#>ucqw_`&?--K0ROEDC*DpVSA}hG}kQ)Qe zu1`n&qxZl5;K-d5Hd5X?iqdeH_Zamw^Mj)=AUE!gw^Q#FGA1&WYrpApcWg?#M}&;( zniKvs?H_YTc6}qbwk!U=73_)V*hkRO2Bz~$M;%UAC|wbdu2{MmK)Ool<^$;h(glHZ z4bn9O=|a-20n)9NZX=Lxt909ebS={D0n)WfcK}G&CS3=Ru2Z^WK)SGW5g?uDEYV?l zq~mj4I=(MY=ar83IUQ{kx+3X{fpjyZs|3=`mo5OL3rg1jq-&Ng1f*Ld-C7{sM(MT! z>9$MP0;Jm`T`Q38fOKs@x(?|&fpo{D3j^sQ(uu(`2FxDm_>CPpz6V3+m979tS14T( zkgiy|89=&9>E;9J0@4M6bPduq1L;E2tpU=lm2M-DZmV?Lfpjg>?E%uYN_PNA*Ct&D zkgij@V?esFbP*sOjaxeC0O2x$blK8*fpi7Z6$0ssq$>u}&5*7VNJqPtE+AbHNY@}; zGmtJM-5Ma>TIn_d>9$I@9Z1(A-5wxat8@o|bZydg0O>lVI|if+OBVss!7>wLNZNAx zbCohiNy@?8h%Y^VRq|@j{Yeibu1R>%{Y}?HcR?#D9eu^pt>e zH|C6*u;w_EFUDHa2%J+e_d2wKnwHluscH%?$7frYEv}WDT`M7YUAU@gSyT05KFNs_ z*SK)`qPp5Rkxk1Qsv4^8;!c~zu;qo~suor^*7fBS=9g-W%sQk}BI=&sp zOkeRWI0N4!z2xIMl-|hOABV31VTx2E?PWe#^onw|GuCTl2H*vaR~BO55b-oB`vb#F`o< z&I!cEvj#=Ug;I%)*Y6<9E5#NcJ43;}Wn#~dy*j>&85_@@B1(K0GdAAz^M08W8_RvO zb>jYmoIBz@qK@Dk2cL5*qMT961Ehbd&0k{k&y;?)nf}Osjr6nR`=h+>j`636?_D#< zjPGYW6%(Io@SS&(8SgP(H@!j!^`~YrCsFk0oz_Y<)uF_lp{^2oA9F7DXP>9_7gnzo z+cCuiYkiUx9_?7HAk{-f17bTuE1Z3%xfcx{7+!~KP8lZG)WI*l$qfGv+&G4dZ&L#Y zq1~onf#4kyKPDnP3+;i(cH%@8EFwa&Oe13AsF;YGTSi0`nL)&RZ_fjH-bsnS#!cWi zi`kwihpmBoAhK2xSwDzkE((|}{m8Ni_e#u{$T~uP_C>@(iPUHG7fGBZu~=f6#2FH2 zORSVQPa^d!jG28m4)nFCS3rM(#IX_!B~F%DBypO=Vu{?xfalMUI9p<+ z#Ca0uOXQjq@&_c=N(@R|EU`gilf-6;_ecy$TqSXh#D^uWmAFCTMu}S_Zk70?#O)Gy zNNka~OX41hdnL9?+%NHf#DfysB)%!JL*ikHof3~oJSOpdiD8K+B}OEEDv^c)%h4^- zBQZ^4rbO|LSny>_e~v`2MDDdL?!Uyb5(_0xmRKZln#5v>;+wO)|I$BOVx>fWH;MA+ zOI#o^AhA|rP~u{Vw0n47lf-6;_ecy$TqSXh#D^uWmAFCTMu}S_Zk70?#O)GyNNka~ zOX41hdnL9?+%NHf#DfysB)%!JL*ikHof3~oJSOpdiD8K+B}OEEDv<`Dxc?G864NAR zN@RaSzHEs(61@`hB^F2=E3r_b=%;YL=%;|9p8|@03Ml$1py;Q7wD*`^rNns>=Sy55 zF(9#4Vo>5@i478)BsNRDM`B3gDv4_(J}hyq#0?TRO57rGtHdWIZkM=2VvEFG68A{l zE3sALeu)Pp9+cQ7@lA;x5)Vu4lz2qqF^TU>3`;yIF(UC(i8R8*{g;@dUBHvufXagM2RixyVAV8PL z@6l%>jPerUlswwrsQwKAL9O_oY#xe#m6rV(JZ-3jarnp&b!t%&gnJRlksqJKGhOC` zc|(*%^AS;F`C_k83y!(=&uhGmp@AfGyp5>}%g+(!eC5T}(9i2Ji6tAQ&sq-~02{}n zIZ<{YXSB_Kna$7prAVY3e|#vKk2TtgKR{H&N84njb(R{;iF&8rc~8N!`SHjAu}Gp% zVx>fu564>zh^RP1kD>xlzeqh=Bo$+yua#{zE3BnQxtmi2`-|`iAYEETzgfeB@7AA> zJw@n05=@zSncqB~2sC#A_4-Hq6KB43EK&>}u|5h}7sUI;>&95w+jv)FQ{58p!n>O4 z8ogI|M@}fboz2UL3Fj4RarH~Rw>Q?wb8K;TeVk8WlI8(zYh`bKoi87}l724N%$l_g z-z=zZY7`1Oc3a54+vNPqq_0`_im1Oxc744C_5tfX^&ENVsIUEStdbMqNNeEi@)&;u zoLO~o06GlEdZtLF`xOM}di^BQr5<3qNpLFNTX3xF^(+XVj4(wiExTTyfe5afRiyZc zx?ZPkR*XQ_+0WAJ9^`MG5(ZTAv>Km5V zFKxQzvsTHfjw5!y(5!pxCs^;xx#qe`}u8fF@c$Nj%aLtxjDRCNb zc%1%2uJu~DxK6xEdsaK#`n;a^?0c$2kS56LKT>fug*%OA?@nVB_9zISDuiW?y`Sy6 zntnyNw9j8Bi`{{junhXrO#Z^2>y1U3Q3ogsin=NbPLXP{tP{GfVBPU5CZOV@?$q^U zGxQbP5yPO8EIm0B$GV;j!rvP`xdnXG*@{%2h`OHSoJR}7Xc*8je<~kH*P;MC`c8~W zp2Z*!^zgpWlX@93cdWHZ|KKQ8mcI#0c4h$ zQT9{3cFcRONVU)D2+-^DZ1}y338?rk$FW{VLuY8mJYR3ei{bB0JKhSu1#pT~o``xo z=A313+Hoy15gjkaUZYBbsM6taU$kS|e^IiJOV8epX$LY-tn<-!jHanxUdN{H=xb0# z&)k-m%MST$^I}ugv{*0tV~<%-R$J!0Smv%Y|3G|UAs1h1xH;nH*R)RSkM%l7-BXh8 zUgfxIKh3(&zfD^&5H4BBGU>|>`ipAUg(x@PinI04Z2x+Df&ai&r8%y4Blnwm69Z!c;thh82^ANJukei!e6Cpqen;M(tB!Z6a;5C7 z*(+N{28a8x_u0+?73cdyy_TL7Bi$X99y7nhw9?@8dHDjB0U-M-UwY1}q}7S{Cp_R@ z<9ZNlB}>u^Zb(Vb@u70+ytVOoeNo=e-L|pxAUY3G0hEO!2QOybv42~n&nA(+OuACH zF_dnz>&i4JG%xO%nom)>tsG(07fSc8#WC-#A|2R&4d7dea}_af zB%-dP8<0>X0@=y4k6^k)<^kzi)CzNGmgS4>hqPcJU-|n&N5`|#=BWg%(li4&Cl$+Y zuH~C=@$-&GDc)K>RSqVXeur2dc7LihhsC>YF)QmKLH=J3|8@=F$qu0(Yy`pbfHE=kTEaW0AF#yKRG2lv~h&CPJ1L=m1PpFw~x zAo&m^)_`RbQ4flxzl`XKj!PTsm)1A+qQClU=9W$(4UpAeac&9oO2L+oLwrJe6=#<0 zx}SbUtjnLf&X%fKTz?-Lu3wZcrjBJDRjp+*j#-Y1s3SpHHfX+aq6zR$8p7eF|cFj%DISpo7u z5C6P$U9{YLKOW^day)7_$*2KpR#C)@HjTEc+VsT}E-6&AMSR3|w(;nM$-V#9bC!7% ztTxQOc=#^x>XsG$_5NZ0cOylicO%obX80d`aZittQQS5lc%|RScXgJPC-%4#v)X0$B$g5`a%Xvvzti9OU?1bPSQ3Su$LlePB^#x9`$SN`@*19mqb|;kvRif`87A+f*2HP*7WbBK9m_VLk0+VhH4}TKW$wPOC2_W~EJ<4Y?_NCrDKKxWWp8uLeD}`6T?rQ$`OZ$qBg9kU^5qDN6Sn++szb5tk=3uW%(%@iv#fuu+@%heuhUwrPQyh9lrfP zI|pm()Hs`S9*zI|^&`uYw@TNK3{#|9ko~!D01SFvR(zKuT-Q^4hk)&gVNh9?o|=tg zT~BR5I>2eW}K@4O;mtJ;8db>xr$1$VQl&6C)pcUq77Q z_MU{l3{DaGNIp1S-X27-JyD)+Z}Az5u6K^X-y6M?gG|(bSCPsSQP(>G2oEC+-K=oT zAM?SyA1TdTQoVxdqy3~4?V&6LunZdD zsE52jMU99RW{H_C7u_;5s(W3x4*q1CA9x_wk^# zX~bikzk_$Ts9RVkRc&P*)W_UPXK;-Q`4m;+z^gn!#Wxklx^4-fA+zo>Ot)!f!H=j0 zfFK^|^r=N##g zs;cV7n)-SST%-C#C>R-HnK^PZE{&~EEFaUJ=WWy5KfD&HHZ=kv3Z>f`1P_@ zY1#Fn7ZDGFSCQf)s(Z*dHxepDAZ;7Gz9Q0PIWZ6Fp5f4#jQo}JK$4QD{0jB(zR-(l zO0YmxdS)QUcCqmZ;u^+U=OEJ>@f{{!W0Xukuh%5~j_~^J{#58z^ZrtoP|uE#{zBnT zFvb8CQSLP9Vb1%rrkG7zx7cFae6*#1mZ>K6IM;sgTDflziF@;B5mAXa9^kV9))o4T zh)7_WG&RfOD9quQSvfG{A&hgIf z^zmta{*Um_i@3k>!146Nr+XYzMjlU0I4>NUp3v^T+%={cF(dqc>~NJObYixv0$XfW zJmGV-ZS?)A-SCEA3ctjAeE7KN~&D~l@BC9Ckg}y+cD}52w z4?(`7boTkJzvA2NT+;}O(GM$=8g{+5YN@x3BJr36g?XIy|9jkVdGqo*YaA}USlY9wn&-qLaY6pJd$?NBT$#KVp zPQU+nqCeB`p6CiT7H<=p#^o9aP4jj;zPL9w(;x2m&#o+gdsn9ax3D|ydZj>Q+x%Mx z@TI4%a;|W{^?!)uHdA!N?VCfjB3|+;bhJJ>AS<=uu z{Zd$DPPd?7EQFhih|E|2B7Xzvdmj+;(SKX--1tKv)#8EUI?+2Dh&l zRs}Uin&0Ig9vm5b9{OYibdKA_*>iWh`!d&PhJ-te(QjjDdbi+ol{Neh9N zzPMiLi?5pMViF>&>#7&l8;(&pOt`ds+|@>6zoe^^ohgX}+*ywE9Ot{T9fKW197A0> zj^WN+hcUkKt|d*?3xQ3`O$@3djug#ZnZ*vv#&~mX3d(*-Lm!$WUn+Z~R+ckC=>WT~ z*oZjVzls!}T~~CXEh;-ew@2){q78z2qbsOWdZR0{d#NkzH>V*j(|BlEI99!i^-VDY&x`|~09L{HnHq?~NB%^Zp6}s=bep zd}v03f*KD4l=mVWa~yIuKH4teLCrOZ^1R9eRPyX|Giwl`+b)WasEOOtW+0r!~8ImWj%mL`Ar74_s7J7kz$P_ z5YU@`e&Qv)|2Ay4d84gygnS3G1mA~AZ}J->@nqGNFdFY}j|z1h`Np3vr)yt}Kc+zmX~ zMS0JQ|DSj9`TqA#jJebSDtWWt9- zO~Z5jrG8I0R%7)PB*TIky3#i@GQ#WZIW_T5?a7Z8`%B8MldJ5Pv?p(NtxrMB2SeQJ zJ>5>%GeZ;CzlKp%!aBzz3I3$@zlwOargnOFx;MEVeaKg|Z=ioznPc;FK71F)@V}AN zosc>dU)s4Ll2>Sq>27y!UI`wTf17W>p&JKhM_iphS@8Yx%gQ|6E=OY9B+kid zUbJtnpI7LZWL}|DT%Tjz&$|=Sa24sE?vzy5`lRl3!*w&SW6_VFC_nE|dUuL*Grsln z;{}f*FWHbWvi%1CT)&uUT87+IJ@3nr*WlRfnDo;&$7bhu)4N^HQOG~f@wAWemzM8t zL+)<||FCcQ{?z8){8-t^@&kvS>2huQ=d#DjB3<)w2hBXAPEO_>8`tH0l-~^EeP7{! zu*Dejjkbq;!~DxSE*O*UcLV!3uk}w9cW?#1Enm~-829zI{2`Oep7Pz?G0LCxtoi-+ zq(@i!ow(Pg&nQ^fo`idy+H>l%ZgH`n zF^^{WO>}O`EXyv#-Aa3}>zDZI)=jvpH~AftoV=cCN#ZIN4n>M7hS$@bn(kPCb9vTV zMt7>?F}(9JIN~VY=9^hIvc1WF6YgME#BndLtqAkjP5kYCXGLQnsh!9QO3 zSe3Xs;ePi6t~Gc|ImS->2rBXn>u1_L&JAMijB~yKqga=F=JRGa?-cx{;@@YAm|==I zM{^N1%j=u!Yw%^4TdHfCmMyQpySk}kkIKlu)if<pAqTflST0B z^0*iDo;dPu1)naDlb>FMQ66m!rc1l$9yslEV+$g7AWV_UUo!%9d0xmXL>T2UT*-S7 z$GV*~Lq3;4uppI|-A>{&yGIohQ1KCUJE;MgR?o0lK1`R$Jm_}PRs>WcOp%hO{0jB( zzL?KNv1nvI+h-cA8%~kiXf&T`#quYJXVm1U{&0#ruk$C__>;s~m)CC+OCd_}o@sI2 zsUn`|gA@6~-vHE%nJN+}kZnF53llSE?eH7elskk7sI zyhJ=`qm7(`@L4kaV7;3zMg;c|vE z(laOhq{o#pxXe{H;;rEq^n(@Zp7s?yKl4Z2_qxVLI-bW2R({y!c2CYL8&T%O_bsp6 z>9{hS}<^KPUGY_u!bw9^Ne__wpmf$}2;e=Ma@uRq_ z@=xiS5%BYNE1jax0g=_L3jc3w9u82DB&BEV&(}Uhe4%0jDn9%3wPHlDy;1|{{Y3@* zx;`F@jO*8;uEVa61BmF&^EHk~TaX6z7~PrlaXumjBVLh8SNRp{;eDZx^|3N@$F&bE zCzDuGQHr;IoaMqiu??vCELKTcMOo$=6Y0480)A`RJ&7FD zGrpar!@rfS^vpBRGnr*!%$i^3H%9lg|M@g~Iv-`GXe$nU>6xqCt6ldyA8z82eR4iqEcVyol(Hu1P~3?TxM}248P<&AeXf z8m@Et->hr4;sz*PBUFbrc`m9b;?JmSme+`f`DcAsrSMYulG@ql&$q_WH4VGIGQ4bX zP0r?|S6>*|HtWUGn;-J!wbcwCjdAvX7ro7Ee4M2k(l$Sb--*t_v$a!`PPDs5pWm@* zXC9vC_iKA%NX>9(=g8)7`I6e!`%I45=lOWcO+MA{9L}fuZoj)I&-PT`C7#u}@ubc* zxjl{@Q>ZF4@SovI)bso$>M_1gJ*cxD?4Pr>L%dgir}}22R_;oV*!9gp@RY^jv+En$ z4!zMgnZ49EWxdol^Lwdp_&wGC&H9GzLg^c!J~VwJswm>msBaqUxQ*0VpVv+Je_T7% zuxnM4U#uJ|Y5Ua+F2A#L;qW6bX8AFqxoJ~U1S^HczxAsZ%8w_E%ovOR^1*Lm^yIwI zpLu1*cwZ!QfiIE<=YexCa3bbJ$CLQa4QDvr;S6`?MAz7XW&Pe7jy+fT>>p#Pn?CNy zy&xA>jeFw2GB?IkV|Tv#LQWad8@dfM^wdm9-T!hNo#WN&^d=lzI>$Lf>6&wA)8PK} zp^EuZtq0hmm9x?@_Voa5;L&Xm#Wxk<`fSPnzjlb@L?}Fs_}q_Ux+wka@2apJC>=wU zp{W?w&@<_mMYZ+I`+RL8-%$ivV<*0QTeRCV+sI4sd;IpscZuJt(ob=&yc6FV^ z&ugB9_8M=G`PkQNyDV2ls{M{dfZl#-^V3F9a}eaiP+aUUV%~0eKnvh_t|BFm@9pdI zls=$5=0(Y?#4%b)13=Ik{OkHfrDdN_*$cjaIK%u?d_+~2jN!K$JAs_HpkuncF6K>d zormGM5MhdxJmpuYhxf&NN<4j#uM$IU`8Vp^e!c)J4vf0x%a<<037qFiNi+AH;X4t+enBDH=4KY*16RFTn>hK>-tU{# zW?r_XU-I$h2%Z6Bwc*;9LH-M{hh89*AfEc>HRt;CcH*fj_V)Osec;fI<&_-=x}Bb~ z^4W*7BaUhF$9Q^9P4%_UoaySsv(GE$kD1o~_$Nl*J04f}O6S&YpHW!&c=>}7T$lg9 z+xK^STnS??e%IaONHH$Ht$pz3(v#l$nPF#g^+g3(&1j6D-!{uX=VWUmpUWBrg@Ky4 z#{~P2NpEi}Piw>TQt#cP=lWf3qdSK*-#z-GcGx=K*jOIH8tY6x&3)iiAwS{ppu8~w z74~>}GE)1+TaV&t>&0WT_a$ST=WZX^3BUK^(HU*qe29+0>=NceE7*xAr&fk{RDGX!x>XtbtLlccW$2w!ZOUTXM>Drjkg5C5#;k(3t?&5w` z*ywAWW1S-}O|GHH+ULcN`*Odk-H0Od6lQjB`>cbxx#p42&H4sF30*z|C#b>@~2d+ZW$6B5q3Fn-H#aS9azZ{|GISf zLxU_S$X|z*`)4XooS^b<yFwXTWU-W&~y^$6%Q_=Up;WjLw8+IWG2Gj^LzoWCrt z05kM7=F`N=^tCLZ7qewj^2j}u%ykqp*_iWWnlWKfQGM~s@E7&$jP;5(g0d!PZ?SzV za?1nOFWrVamTB4*xd)~{HUQM2|gDH09QmpDB4QHhGnh=S7$z@{xAH>DODN$-}L-R7H>VqL4X5>=(k)S3T8+Z>V7sw&=Ni)Rank_)l1W6D^c3szoi2ntgp7e;!q z@zg9)a-pPS<5}`ia-pTi#t#tJ8?B$z1W|HfBpJ(}CHM<07Pj;#xey!6KgcGZr5hy| zMyRp;**1Q*)F`>|Wr$e*AvS)t#3;F7(Z=%U2>xjPO@FkM*ixe85-msfdrup)vz{xW zoH5D+q@SgI5FeWpUz(=Bs;23#hPtYTrsY*toXb#VC8sr{*{DKkR_d0gbu1$! zyRt3y?~Ewx(y}R)0gEgv`_ariE(v9UIh4_cD6bUU#C#M|3NCV*M7{ B1BBuH6%J zEOi`5ap@!*#e#L@I0;=oFV0eC5 z7;laAKTO12(RS(ILBu{A2c-WX5q-!p>3^R%5Pdq!p#bAiB3_Itkp8hmWMYQ&&nCi% z7Uc$hpOpdLZ$xSvg7FD~#06#NcDTZFqmA z|J!M!e;>%L&TMl`a7=U;I!5)he-|+cF8A9E|DbC`_3!1E(yHtCM>0ES<*Y^8&bFM9 z#)$vwdf3W=N914@a&V$+*vO4tqy0~I<%~=n@vmKJxj`{kfwz1&J08WAjH;=g`_72! zuXkn3nBN8wvnjRAKwe7Tc_J{sYnqICT*M4U%;SNJ-&q)#Va3!0jYl1u7*ib>_D*i# z(k{n|MYlchiNpIEOLsupCjVcR?x?pwpwX7K9-iyph6xS5;7Ycl7_LTa@ zU}5k?a9(6&@y_5Y-L8Q~_e$5ClhsQdmpR6zf8w|@>;JO%HSkpx*S`CFBsuvo1c)_2 z#FGy(@*#ns2E}@Ea@Ym|L7|G)*PK9tCpADMpxE19gP>ydTCCib58F${+gkNju+WS5 zN}-juRBdlidtVf2v9*R0YZE|wDt+bs|FienXU-;=gEt`cz4beD)~uPe*UX+hYt6@= znH^c&=-u~JhS9a7HSN8^8F>|v_k*(^2_LC54$W9Sa;PrEU)H!vwDUt9UA$AL-Xa?)JBNDy-b)NB*?Csm3_!{{v^{K98^G8KbXjyY%zTjqTWnPu()$1OkVE%|N1?{Ei?`CjOJ z!S}ntHQO^PzF${{-D>f#TzA}^U;cg1xQY&z@h}fz_p&N?ENg+w+1im=$`mAzBg`UG1M6C+w;|PGGqAeb0!@; zXX(+j<{x)P2h<0RqXVuphELm#ye&rPfIpy?{I)-yFf37j#PBJoC%kZNxPAM&!H4T^ zFsJfb%8q3dM%7H;E~cvUyTi2no+zvf6|YUs?qY}&N&0> zOHg}!d!9=>bSu*wa}fIZrqn9dINW;yYSj-~e%7(NuzkCyE!#R6{~sNq zd*>mY%i(TKgkA9vKnj;5tFnBrc zY`p5+GVd3xk1(jjT4H`>3q`W z&G>8u{I+K#us)8jLFHh5V1JD~bOE@jaIF0@!V5tbpTB^}n}h&e9>>2Sgi#)^6?v@J zlqXr*ioP2A+yWwRF#>eH11I47ip?k2bMJ7y5Wphu0r>U&ZAAWp2vhx2n~(SVC>(CD z8A!nwA#a=zz|0c?UBaYs{6_FStzxV{;nVMdF?*4T{Rl)CQ=Rp|{ISo>ylKU1JdZvq z^DH3pgchuapUQaw)*;Rd1d*^`9-dRWR&IKl7a%{+;y zV1k4%pypE;#5&_qHI$SE-1`(1Lg7r~5}UU8t$3EV1<9jg&P(XPd5DM>!0T$@Smx9L zj$5a>;y>%68(cK&wE*QU6#`i03qvt>`PDeG2NTB;cwgu|BACr-{$C-_v6ZC1bY`J zvgg>%9t$yh918V17Q(v2l=pWPAa4L?EW~v|JoBfgbAMnm9H0ug=~Mn*%X(K;JFl(@ zWnn!^>kOb;39}z!-yKwq$EWJMXr^upSr}ppiflenWjCKy%>T2!Q)0`RuJ}WCx{|+2 zEe>9XPud-Z5hlQuE1&fz@~#J|w-a3F8$=i_1JfWM+lgD?aIeik3Yze*-?QAWyPa4M zzB|+v)}QbZOIb1|4q`trngLbMm@e&uyPar9CPpD#K;#K6SP$=uc0wt>40huJ5Zrr=st>z&8_4K=e>g zlX1&Yu~!1qw$PnO-}8|P)?ERSC$wNayf5^fb}Ru>Dpm;fo%%(H!u4nFld1)~Gw8Uu z>Wba2H!p0MlTy2W>7^AZ?_YYJ9eb@^ABDGYFEll8NyBQZ$(v@xOO4h|-dJ_KG>DZ? zbuUDlxA}{TiaFPCpx%dbS^kI>aLwC1MV=4*?=L*J%>1gsIHT-vTO@jK^sSCDn_g(T zIyNI-Yy_g!@!~x87rM6OG%nkCmYHsPy7P053x16gXjVL%nd3cbRCteix;>o(t2~#k zd)C+KseV3u4Ne}LcCdeS=ibXVJsDdS&UhoObGg?uZbscm%;NYqc5Q3KcNINjtQolB zjoz_o-8r5NP!^7NNb;*>#H_tNz70ZwMuGxbb zqWQT$?Dq8Iov$=6-sdSXiau+66KA=2JRj^WQ}cVClC9mD{meRFT@h9iW@cVvMk1f$ zsbXgN%M#j0++-izSKYdGKKVWLeg@X(RowttP zuH^YW{Te^j`0rsp(R_2qp?_+vFh7lzoKM9XW9gk4fz=atZTE~(wW2#eC#Q2o=F1a} zm1(ccF^wXe=`>``#G~#0?tHJe^S-RK?tI^M6Mdcc=FWWO7jgf}HRg4A`saPH?C5{u zd&j491AawZSTJ_?QM92i>jYz5D-tNP)@ zX$SKrGL^U67e^s$LhZqUlY?!0v99tKte~5UJQ({gHAk*6a(JyL^60alHX{c;)!5~7 z`H~pU4w$^`*;2-h^LO^I{vPBFta`isAEIBKnA7dgd8U0Ia>;K!XYaca(!bm7&m6KT zZ9n{1418{Dws1Ro24K}A%B?CNXI7T#< zy9~_v1=3%u&&$Vp&L=jdnZL`3|Edz-iyp3O-w!q|j2&&N&x1DQjiEM0)A6O~a&_+3 zh2W`FTxHQ6IE^dK+~1LIzTR=u(Cn#3$!FrlK|XwVE5q7Kp+a6N9n#s^~44$dAlE%K$pZ-jI4WGBU1P5-{n8s7+88eyHd^c?Qp=+5_K z?lVfhX=dTHqRA7nkErv5-JZ^6p0SPTc%u1T=jHf1@6J81?d9%ZrcqoN^M8!VVUl{Y?yochvv^wivxysf*9^4~v)#z_d z{7ZW$^6PEPZhU3%z}@SN{PO%UgCcpGeG$+8)#031z&RBs7LHnl6R9#^^#rlLb+Yw! zK*RQP7Sjq<^|&e*HLE{n^7Bz>|XjPUO>f`iPeck;5K z)8Qd!4;+!RZ|sPD+h6Fe@Og^8ANUT_;uY8&(~e*%NHF|?uiLr;U!=M#zQx~&JI=`H zT<$-MC)PJvHg`vN(3e#O+{e2EIqHhG9o-|+Zkbs0LE7Q;4|3l( z5Bkz6D<{W<3|>2K`+<-V^n8%p4Gp)YP(q+h@q^0Qwrqm=v%^`RIY*V;&cg%!OU<)3MUJ%QdsYqozW0exJTOn$t+H{uzk#*RKab}J zjS>0Vy``SgpT`Tze;&^Z?Rze>bGdK*p|PP|arBxS$-kpBl2;k6vA#05%<}}pJf)s> zxV}87t};gbuI*nBRZL8a?C8GOz?IVz{7eZY>hXQx>CUQtA>?_4>2fa}^Ui!Xn%39u zLZ;`tpLr*5GUb2cK$h`(JP+?H@{FGk9x&L`8OEC$-sxHU(mH+Do`o+CUx@S6E?4); zXKH;f<~yCf8}r`H`}{PVbaGBv-WI=^wJ$Kq2pYu!CD$|IFT2T|w=He5uXBfg)gKM` zX(zg_L=P)Od(pf(ztIal_l&=$zYlf8bIAsr9(Zqh&MThtpoO1>zSce({!9CY!DnAC zry|@N_P=hF@Kn)z!$;e#^MiejSNDG;oVOWu%%As$AMec`4Hr?5bNrVVY&v^Ce51bl z+@s+SUbS_3U;nQ2JZH7dMDHT_f#)zwY-!lvdAIMkZKCg__H-D*-`lp0`L*&+Y~|lD zZVZt!LSM1)iWe;W`MAQZ%P*=ztkE`Lj>60T_tzC}_{A@XgSG3uVc-L|*IY{c*s8(v zfJ483wEQvPl|y$v|KGslhP`)dPPNgx|I#~OsH!&Bx8HNaxZA6ZUDw<)??+En8&^CW zeQVa6)u9KsEIId?vm?|0^xOY_Yw+aASAR7%{lB_eBky1R=FhyNwnR36Rv)AeQPySP0h=^Y5ig920F zan7T7$dfd`!*vm*!U%jfT$TR)2`oIvHxl!4M7$By_*TP@sAYlW8TX{$n|7anh3|g8 zCt*GWLh$G`=PIN>O&+Fgui;KwL&tMDdpvJ0l3VWmigidF-wz3_hbQ7Xzb+_|z)!*< zukQ8p>b-!lnea@?^)L5aqdqPRPj!|$vLk|jfS%qfpxx)?>GwI^#lI6YmXR+@U!Hc4 z|6bpHET@qO6Zj8!dU{8-P`#qMUj3H|GjOyg{;J%v2J4kpQW;k&UbW6Y=^l8$&R*WS zpYnK;r04rN#79^jGpu5`)X;EE$y|zfawzg&L zY`LH|)>uB9v%oTy*tEc=6I%^y8_BQHl-bzaWS^X3&r3EhxZ`3*Byl#i#2V)!Naik` zv&to)zH#ncCwg&H(pvr6*<+LQUGK`rLLNq_r#FwINlcC2GN#-SI%h%iok@3CH~-FB zb%de)cCgmEYEi>{uDDMQoZWa!Qh0Ou#TQ*X_L7T_V_eiY|4y6p6Zj5s3hKE4#v%%+ zoBBLo8I+%Md?VnB!>0&C+ zNp}wXx;)PH(;f?myjle4@@gQD?E>$E;pF3eEP&JHZ3GcQn1IN;3jsP`7l@mM30U|Z zaq&&@_FOJs0iT|~DDubrFn?#kN&Ys#ucsS@yq?a<{ul7+@?x62eww_kE_thbhOr)D z0&*Xl5unR!hCJF~=8yA6lD}WTujg+ZBA!N=fXMqf0(5z+wfte}og;5A{JOmT5Ktq+ zY(A2Igwy%T(0O=`5jIG=e*mqgyB_IEJ>Ysn^0C~H!s+t<3VCeH1Vmmom~_4==~%Na zOu)jI0VX}&t=j$KwVIPIPFqismxs#!d=K)@amm{Oc|q{;dGLLX+{Xx)yq6&_ig*FZ z-vust`?Yf6oV3Wh!XTM3+|}mj}L{XHnJH}4Dqn(brKN8`W!!dt+j?5d`M(kbHfndiHFyEJ%*^;Z0t0NVYI4%(Vu|@p?^S zd7kBpr{zz857Sl2*VB?Gzz0j59N%B%_fdx>d4}I-40Q3+@+QD%ob8H7Wzc|oAd=Ig z1x*0=JS4{#sQgTESZH|@;KOJynV*(10X|r^|`192}Q!=sUc#QL1 z{KH)Q7EOJ%fR-ZxK4nRC`a;zfQb+lW_)a#Mh*o+(95mxOUgg@DF*bd-qBE3@fL8(2 z4a1RtHQWG{R*g-E6rF8cXVV-H4?ym3wrNZLS;lOew!Tl%&zNV^>wyQLzAv%qClx(V zt+io#9McUz{asU9Gspvs!Z5U~eLkFO~Jq9em`*{YA@lm(| zsBixcEWmimVLaQ!0jO`gZQ9CDk+IjNIi?(d`ty5W0^5rI#xUc3MG0MMq*EAR7hHd? zj8elG=a?O5q*7~-5NomKhYLrrmBbn)CdP(12$SbvS_8vcXGq9Tlv;zqS~Uc;E>Hu% z+FED02QF)nhiDG(fYhL_wwA-WS~ZBPt>w@S-#_N(uxjhMM5(sc8ofDz7&~H_MVPaR=^lD-}yv;VfmAKR}-m>Wf#KTY?USP<}C&t4nv+0q<=n&P| zG{;ulw`9L_URXE3eq1HqI`_8DW6W6jKyL46X5NfE0i3mDxoGn_^K5i)^l&bFb9}S0 zIsR<9uhR%|t~q0J-j>2x(Da`mp2BkA^flWkat8*(C-Z`OIEo4LWY%2Psb2?z$qs8O zXP#B4FfWOjB0J0q`J}C@E_9wmqIWqGVS2mY?zhGZe2(xc7XY3J$Lc~mLzoW7=O#d2 zLKU1YZ$BcSma1OxTJlle4RBWVg9oq(E<}$FB5ww0U0xR=f(T>&C`aVg!;e0EGmwJK z_#bEci6kxe*x>-;n6`lM5kmzXco4$#5XfFE9ni=+fZwKonRGzpIRUmu5ATby zLvrt&xk~`Y4$1N9%H9VZ7K`TnSiq7^0M|9^z;(wgN8STKjB=Zn9weSqF%Nz_k7O#JJG{Vze!++oa2h(YDyO zw59P2YKvm8YvxX7U9R7HppGr&=*TfEDvs?v4D_Addo5D4-Q6r(^z@54VlliA+Qg zE+F!R7OaQ&g^kk7h`D3^Pw0R}C!Uu)MJqS7VLH$zamIjoWz8n6t(mYkBm1?IE)UjCfhz0|U!VOoHs~V6opKvw z_r0uPdzXNZ{tXrC0Bwn3S%<_2#CtXkmj0u$aO?k~ zxi7Qz^6_h@<~!Bd2*=e3Sj=Aoenj1x<|70G`QquLFMXWUK|0UI=KM z)5vcWOxj^zvF$)!NcB(@ufw?=q%pN&-hzd929>I+kLU$ka9fQn_`F_A@cb5517#0& zdqR6CK);Ol5_aCYMyFYiSbhTROWM~>`Xv@HxOq>xjdB(auo9@fXxa$TvRo{Qq~q=w z+?=$OV4mU;yQb`(7392%$4=le7me%7uGhzA_sa3isMFF))As0fLG0N`gzNS!54ywW zFYigo$G%rJoGy=cP_G9f4^v`E@`9Q?=0)VO@1@I|37Y8&h&;}#>G>7MfUMTG15n}v&|{8&DczkhGNMszs1ehkl-41as zN*OOJTIG#i^6TwTJsQ1o1mq(e({(Cc-aqrEw?nHi-unlH2}rs^3)aK?q8(C3QG_FR z=qhT@QA*Qd=xP5k`B@(<5N)z3_IZ=#2bBDTUL>yM6&$B0^Jgjkgsn}E?dcpd<|iRP z;j`rDDtYuyW}`=O=JGLmvYmlGqA2{s)fM#pN3O;0Drd`rxxn~0&v_LyhU z!bbIJ^%Uk+#-+U9`L9R=;PiR^F6LEO5`EaJe_Uf3)(7f>SfO$7vn~pVHDmqJ+lC`B z#N=arBo7_yt_eqZ0ugwELI8`rF#Nha{ksXwi^${Lu-?|xgJvEDBrSJavlGHnZZO!w@#3cw95P3oi*2DXvtxD2Fix6rUCdxQ+rPVw9Xu}7oFI3F?y5_)^*RWW8v%44W{ ztCBhPq#sJG8SlJimW^%y%>kpU?WLdo==pzt_Gt^gZNYjC)@tz2D<8Ob>6h+YeA~Rn zPmdpSLKtTRV}VT^p&2D5(Fdjk&E{>S+Tu@#;vJT6f9SCCMPemOj1ljs)3jE`hfinh z%J|6gr^3J8eQbo$^}AN?d>J)t#IT^+L9%4((!w$|mh)j3sL}PCR-C0D_uM){eII6I zY?qR{GqzLV<*^-hD$gtIk8QQ-%{IMJ;kI}@^px#868g67>k56#_PrB&)bvA zCQOf)h8|Y_Oyz$-`Lo6`{2t{uI+q*%`FAOQTl|U87i{0-p~bfEtx&V=TOGR9_B|S! zYx~xR>N>nZL+yM_$K76e;QMj)n4#TaFG9XbD*VN;4b%FXlb zkUzJTnA~;cO5zW zy^DtBca%9b#WQ6@^bc>-ZW78YWJH0>;b`ZmFH_*C^E2UQ!LjWoMBsvO4U6YYz7Cl1 znHi(1W>im_L_fl>o^Ii4_L(Nlm{!a1iJz%9K3`X>;%;3~tFHY*tXA>J#ns@OK5fP% zribfP`uZFI^CdtViVqQ3-%Q2+h|@QApWjs5R5$+?d-!fGl9vJZ?3R{`=Cs^7@1k+z zFRnB$vPgXK3FP>`Yq-y(cAL*Zz%qf>`!T%@DPV&QKKA*^L&y3ThGW|$W63+6otyqoc(V#^UfG)B+ubAmFAIt+pI8cZHyI-rqM4rQ7d-U+W z=r1IXzWf;fB=;8>KikQK75}JngHqZS1IMnsJ^^ga6W}v4T=5xL!Day^c@VDy$F|Ax z0_yA#@>u*I9OvPU(q*EKL0Iqk{f$Lc>L;%Z_y1=pK#ToUx~{bT3YIEX=stllarmlcwWQ8MsJWv)sQVTSn%lSywEmFv$5Mazj zS?~<7MZ{>J{?W!Oh%xD~iWp<akGuTVB_UBMw6=KbNw09dCbNeiGzmm zL*gRC_$6^M?t>WjwVxRG^)4~)>wV%9*fZ!xRw?pL4E{o!zR1Rx+1Mn;HP9`=9nJS^Li29g8=>VZbc6dBK%`mOJ^5k(#sAz?33A_(#xFf6M=mbz14Xc z5$t!Mx~tZSe55DBv5H8GSp$C%PC(>UAwZY+8Y0;4P#&)pc{jjsRXKP7F}M&tHi$gV zm+11|LPQW@l*fFDyn6W2UugzX@C5$H*?uBP%RR5M7jcVv;3GfO(1BJ6&qE;lXVTZ? zeKBu(KWQa0bh&d?B3&&=c_lw2`l6r2xt;{DR1$EawRAA0HhlE8bgWbCmn39a&-(&| z^B#jLzK6ARV#Z`9rZ%CD+FCl%M}0Yqdgfe1$F4sy(@uRY-GceG4NDsNaqZsbXvSAo zs=1tC3hP{sAP)e?esaz?3t#-hm-%>l&UV&UeY{Cpfd11r#%<+=4Y94GWd3H!oZ;hbi$H4@F_oX7Qbo^s6v;J8q1v=_$?K zUYz=Vg$a1~3vlehAdIp-BQ9z4j__~C=~D&9@W`HBvFygxIJ+k6m52XQSZ<7%9J^%S zkl2Hbh0~2-cH@e=wc!_|1Dv=a`wC+#Vvo;yux?1qD1CJLOEI2k!?W6W>KY^%_p1=2 zY!}XE%QLg1%~!n?8yxw0M?tLh=D_W^D!6*)1F@gS2H^_pG@K!^oPR8w`Lm8smEc^f zv6dutX3$kj&AV}Gka6J+ZJ#oY;WOLLQ!}{OZ&6m$R$~V3nM|W>N?S$DGdi$+opI%e z>bfgl|NeWeS1!ki{H+z$bvOqr>!)#JePd&dx|*jQ8D*EX!8(r4*^U#(*0;iqzT>I7 z&gh7`QPH2o{jJ}N{!6%I_MG`cYJL-6w13E?^|PnFf9#9lLjmv0+pCWlGfLooU-x)C zcgN0n>HaroKelwv+@R@I-_s41RM+jqz5E;}wHd)9Y9{tymvZ*9%=}}AXC-}}bsJPj z4Nf+)=mPUMN$31vEhf&a;}f|WUqjgt>mM5&^LBf@yS9JTu)Z=J*fb|r5XCokt@+R( zzh%y|0skvDCHCt;I~+v)YGK@-F#ixN`eYvkE6FG38d2 z~?ndoxzjcwuBs_|51!?WC>I0E0o)K77R~7kF$7O?!qLBK=Lq}|P$B+_V)cyv;GQkGE z7;&ruxxtqc_-}0Y*=w*QoRwI@gok0&O}$;Ctrhq-JX3gX%jbAtOC)w$Zu*qB z)7F}+hIuUw4YxMv+kEhvy%e)(!bV)H z@qL&KEAEb-6HuSma-uYeDk5=FANDTJtaY(ZNM!+*{y+$Rwo}rgaZKSf+VBeB1o-uS z!(LRbSqQ^aL(;m~deBMoKq&Zkh91tfnzLVzx>2|}d&IIk@E`!)P}{@yu(yf<9(zNpD#UqvjU6vE`hNK*L3lH_r4waCn1u3tjL!vMGnaOkTel=&$G}!*|dm1|M z9OY#GG<8oZPx$j9empK<*;|mN-cK@~?Tr_jWdf6C8{{R@ zUZ3rXr=}!;XH+C#&zheAu2)Nr@2BpE&&vYV>;!N59F)3gZ#P+oh01(;vH zqu}*cJhUdc)w5nhuo1MH=o2^0IFB1_c8d(3-45dffVtSSZ?C$;ayrs{e{gGU-JIJN zH{vTxS`Zd?H`KKth;KExF2#Nw0WXE)L;;l*EYM5NCRtsrGJ=wMlC}xCnC<=ZQ20`m zMOM&yUr)S?bP?v~iHmUtj!o~k=>x$flPN=UVSa$-jy; zgm1Rvw-Q4scG@)Wm-Fzi*>pScr?5}nrg^{Ihi}c#vl!Jjs$SOsjVZr4<+Ik^-#6g= zQuCI;6s##ZKY){m2b<@sRU*}eMqBf?5{v|nwpHN7b!1JIm)=Kb`3RK3^YN^8uqvnB zEA5jVRCqyt^7yW~zGDq%cKT4fMKl++OK4Z>Hu|Foj z`-VwzfV48Y+O8~RXl?6kG%Q>=e}P>OkTK?qHZq?W8KZ=dy)koB_L6_Vy0oI0r`YopXDjkHy{Tq9-i&2&Ui+ALW8Sua zDPi6khP`diqqz5yUlu&x7O^c5h`?jNAH)&C*Jb4fs=#n$wNmQ#%pzXOF%1K z049jM5d6Bl&5%bv%F}JwwV)|)EF6J0Ok|LzpYioJ22$`K{zH~m{mV5`Py@xK?xm}+9mwfULZ#tN}T1Ns3-apVtKe} zoc#lS-g5+wwiwG{9AMlqhqC0d{t7Uj^@-Qh&%HSu`w1}2uuZPKVn|p8eiK!hV_1l} z&5NvRB4`@pp!xtonGcW?APwG`jy@sIF4VzmW$ zo6zao$nU-MLwv?0eChnDfZ|w+@9dDrw~;)4#Y3UIPrYxdKcAt9!@1x~eRq48dC*CH z$d8lDYjX3#zs$|4df~@EqRz1V1j^t6TdQBL$bTpebHI~w^KnHUuh_v$PHP*Y9!PQ< zVr`gGjY{7%8fQ|!H^>6EL97Fxsjj*Cuw}HZeD>s_BOQTbRTC>Q6MjBZ0g)F%fG)2P z@~Eqn$7@C2XW+N0ErdpdZPDe8guEcaD3AFPd9&fy+k!68)I$MD3u>NZ zyGs$VP?&&)k63RDc0qV5YfO0Fm2Rg*o|c62>fxuNEzr|Dk?k*an9^Ogoh6$9uBFw1 z`#||jc@MM$C$jB~XC0yK9tAAGYYl5}qO)wY)}o<}wYSf8{PqUMq!lJsed5}Ze25|D zee|@(B*Jjm>l$Lrb=Y>erSTTLs!3su$;q63x5Rp&jvYRWWwga>_tS5EE_d>fSf068 z_0MxAd9hQ2??bJ#5;7)x9v%|2;yi1z%(O||$&rXh_MInie#>R*s01FDKpi-deWrdU z`s-8CUk~%>gK+i~+sF6{{HX&e4bO$}rd>L5)Knw=tc`1%kysq}GeTZ&FKd$hgpsl=Q|xwVX^_c@Qa^>7_q%06xL7Jh{=-3)A6cI&H~HpD!a zW8FtIeNRd3+~$(lO@+nLf+fw{9&3CgoNI>-T9S3)A$&!z7^^LsL+IabXCL=X?4G+& z3;WdM<}K&O(y<2QtW8h3BoB2-?gz;Xvm}>kQmpUD?Z?;J#%Q4^vg2%Y83S#Y1+2~Q z)@J?kr~JN7IJ?I3=)6(zYTsr`@J_OLPoFKXI*UX{SC$!JZXCxq2z-`Mp&qBSR zZ6gmIRLPkumOk@?2#dlAh&Ot+v)kssgX>}<3|Qp3ZT|C`JmyRC=eGGX zp?9g+{1xC!#pahGp&)o^??24u*C2l%N1vHxkpL+@D}**aIo>++^k(M*i>7V1AepB z#~JrpiRn8le0Ncpm@MO##Ut-~H+GnoeNjo5APP=EymRk&2CvfUi{&1-4Yr!g{~{2!y9H zFXBi3CiWmt3sPQ5heTiW>)mtYdU_|C7YR8`AAMegI!_y4-; znQYZX|16_!n|IX@lbGaQzBP`dy$&HA&W+F>k>;M{p6od7KJEAvVhmRj{rgxQUuyQY zA7{+iaVgtzp5X>a>fhhZnGv}_%s$@x+4#avc zAo6A)K$o`_5kZ8p-Y}o!Bd&+jZDlLyRBYvD@GXK9kUSCVwsKaAwlancRf;fRk*5VI zuO8kPwi4>E0ZSzTw3W&6?tO`FTCXWAS2vwF^PkU@wz4phoO<4+pm~q1Bea#QX9BDb zs$)y@lw>R|b(G#PjU<&(@BZ?c&<0WlZKGPF)C+~b5yK{8FVZC!Tay^-zjvD` zn-qJW^WgVk07*7+Su9`8&??<+<;SiF}l&+sQ`Ix~-TFx*SeG zXTS1I+sN{Rp zf|KsOFYFb|Hv!f*gdKxbdO9)rxuiILtqpvGa>52hzER$xE@E*N>aWjk)JUk7q z7U#p+*2>=OrR;nb3LD)ZBMUcIObollI>LACoZpajN_@9Yo!9mYU|DL4@6N|nraZUy zsP)jCJ`nc{bYZ{1{Tl;#LqcnW(-Nkwz2E=O-Xf#hlj|Ag|2OZ$5Bt+r{vw{UKmF?& zU-SHP`fE4N4<9kED>`CayLRb~IJ;qx>3NdZ8fE!Bji5X$n7Oe_?O$@g2VuSAbJlHL z5VXL}@KojIFHgJ2f3NR8??aw&Ze=VtUtJ?Sd^V?dyxQU(qw-TM|4-~A;PViGSx~_G ztJ||y%-yr@qH3!;Pd@h3!f>o^qNyw4S9%3Z5P9zR+p8gue3Zv)Mc!2SDNoiut+(TV z6p)YcQ5yp(cpU!`+fPJ30`E<~k0+3B5MfN0;pF3e%!AYI@&VAP*k$hf`x1Bsm^T8k zZkPFvWI6(ACwSjXm)LEWBgo(72p14}LJQWz`@$}>3=-g1?Z+%9KuXgJV1F=~-~bdiBwz_j_)f7p2*D9YWvx2w&-2xC-o@09k9dj(A50oJ>Gj&FJY+=t4$?`cm! zCFAWjfo*{^4!$GBHlVybhxS?X}|6Qb5(Qty)big#EGEqi_EFh+*Py}xtddwYOmC%Dd%Z(ZqV&-6YVX#v(3H+_2h zYj+&C0P&7KT!DBd*$2^Kmc95#!msOdGa_go_)N${N4gr0k63Ch+aQqvuj8j3(d8}C zkZ&P@Pa4ksY8ry)R>*NTWB!k9niOXNl2*X>Oc=v3^@dhj*F2}quZb$b(n zaAuhOJt-UNA@jy4fe1{dX6eq=}C++7_>Ci+aFECV!SIf9%>+ zn{92!JD&nyZujBj-I-+jR2{SnoOPHm5>D3({S0gJ&`~o?I936%eG&M3k{3p}E{|te z%d^&P-;K6BAO$n=UvB$}m@a|)8g+R`5D`Qe>yB>w=7QF3-*V8Y*uJgcVM zF`&Fh=UplaB#B0bl|4mZl05~@ymCxAdQ7D(rcTM8jvp`9xA(rHx_Pay$T6ko{bLJ@ zkK8r8xT~KRr^#O1TfdR{Kb2`yL;?+bgzd?mpBy?AMbERLSWjw~1EiO-bwsL*0n|19t0zaQW1RPS0G zGFR7xUCppGiww478dAfe@`}M|Fq&|*ZY2BXF*P?A0^@px$_ifBKjjwt; z!`?J=s5!&%KAiT*cQd9PT;=mTvUs<#Zf(ZG-RGU>U01N(b3yuu+g|ssHP*}sWDNHl z_00-(6)jC$m)7aaHb#fK#x5NmYmXaw7e;YDb?jjnA=Z^FHLE?bMTDOi$)d>F%# zry=j{x6ZaUt*fy}iHb@T?1(H=5rz zJ(p+2{IM#Wcy5dc;pCC`_bxKqI#f9tt%F&L>%(Q+gLnq_ns@#AmS^|`vb_B2;(dXK zOwW}CILEs>?jK@|#w=y_`+JRbx0w%ww;#FwnN3FzcMmqp%nJ1eYidV7TW72t81X&AyD`?SiM;nVp8mR-L(7Kyj{0YgZU2_}Bu@68uF7DN88V0N zu}X7;X^g(|$S=Rg5`Cc6STh{=IdIA9I4lrL^uhq%^S`(Eg}0}hlhm~v%&a}T%xB-` z)%*7(LXYfeGr#k;v2NPIS2BG^Gyjs-nVB{1;3VI*$T@4W?-5>cBXY1nr5rkZsP*UF zhA)7)Dsz_UNBoZ>Mj7)q!{&Is)wk}2PJgz4T}fmRc-E*K6qz;VEXDD)y|c_Bgbg_u z%&gr0E%Tv{`vTuXS^gU35{zAgax_Lq@GRcj+tYKn>(7sWkI&%K9iGt>@Qi)yuI}*} zU)$kXTZVe(Q(A~;JH!}X6ZfN3Dpe^wy=Rsxn?VPIfy(Xe=Hnf_)0KP5P%l*8vMRSf zX|7PA$KJmJb&Pq=S9yNj9M|Dn<5^d8f*Lfi!;9y-FP_)xJ?gu0*Tn5dR(~&{H4`Te zd!;9>nTq;9=oMXS2H0A2cH4<`hS&W5RZC}Hv316?ZW8J>bkfL*U5#=yMxcJ9*8dW< zzUP=>Z(C)7CxWurWe&xzV3xw!2ZJbuH_WsS>e*BOcE@w5yXDYBYIzWvSZ=Ik&3!oX zaydRxr*dEwmB<(c;c?#;L_eMQ>+{xAC; zz`NM0+>rMtS-GX*Y~N~+!l$vnrrM^y9Lkrhzc0@Al~_th%V(dwzM7Q%&ke}(6; zvA-rD@;D!-_tiomdg`l91)ttm`zz$>^+VEf_tnbL&i^k-6j=C(^}bp&Zek%oCp}`)Y>Ot&$gtRz*hqEEGx> zI?C+R9l!o#VO?WOLrQ(IOU9)Bt)s`07QpF?1&p*)uftW>O}(gY5x&hm8!P%+tQ@59 z|8dPVQSbEn&$^#V{f~i;)Q5P}D9x0icn;S3J?EAV$(PDg5CAzLk< z`oc(p?29w#J}xaQNAdA7i#?@=vCIWn`v}xV-6EgpD~BQQ>GIeDGE6|^xm!Wb5Tij- zR$jD`^fWkKvsQrCwOiy(M!258y@&`RjCF}}$VYrLoNiTif=TEewGc5bdZ!fc1#2m_S+xTdl=vXtnf&z5Mw&PbC#QFs3~9x7#&VK_%G%AI?qa z+>}?7cXj#Z)}y{qzo~oADTwUs42IBO8k=_1=!zWr&OlfNpE2S;xBI${YG3!UiUN~8 zr|f7s&dTxE1ftDX)n;F_>~}eTJNC|zW5;g!_cw>LozrI$^gh!p#F@E)<=%TdH}UAQ z(_5HQvK3AGC>QvqGyb=`On474c%!pBpzbi2@g0=sZE_;kCl6?7_g;T`bZ1ScSQ zBG&sV6utvt)IZJwFn>MSg&pA2caMoYuqS~YeyZ$3jg#U>w-bDJj-7zoi=D7*tYstc zfC|9Jz60LaR>;_%uWWnkE1Zmtm~ItXl8soFk+=Eh&*rxImOKzH*j`=e+kM`C?~*Tv z3)=>E`T7-@zHX22{oPduJ*B=_b9=OR3O$*(IxU>SnBN7f>!};M^ARay<00!lSkVl z@;HA2m26hR@V5dk6}v$DQ7ab#i@p-;eTe`6<*Gy>@ptdro=?Vap?oCeRcHjGh6+vKbbMQ`^`{%|{^k4=hk zU;61AiDzNy!|Ag@^7UAr-K<6|)+ok$JahZdG<|Gi80s7KNgu=L^;2xgNbu-=8lFVP zy3A)o9y-=X6Hb>m3pDuzL|zyHy1ck1Pq$6(RsJzt$8nN?$aAmq51`v01QYYed`bT1 z!msy{9tWL@t!oEgDy#fkAv}lz;24FD>GJ-0uZVJBJtA0E0xYwhKo9Q=Tc_)imAgc$ zr*c(4b(*%&y{iAhMDnVf#(?HMv&{HT=rUKl*vh%iP)*lS@v8;?)(4<%+d4OS)3~bd zJPBklZmJ3f;S2h(7PT5p6475v}7b+(P&AMXml)Cg}PM#cl5<8^|tRbs2Pb8~% z&oP&6%r%V*jjoQ?rDjHVb{bCrxjycn@TpNHT|WP}y90qK?Rmv#o6m%&wyz4e9$Mb| zoA}e;-xCiQflj|?McC;2@79`Fu*;MCP~_Kf|Nfy}o_<&E4tDvBU}Pouf7H4s!|47> z>-F)#gcmvkS#QMs<&f+%I(@lcn>cRIOR+D6Fp)+c((1=leiU7SbaGWXnM=nooxIzaP9D=KveNO6iS>`( z7P~gODfV!*5ZC+5KW(;|vxoE>?(6dSa@$L)BavMQofE4DJttbDRFsnC+Wb`XyZ+Z#c5PJK%X3CH!ieY z=i7beShIg@Q1sf^jnS{h)<(zJ*IE)P?Ns|)cpCR>ycoMb<~LuAJ{*0#qbgR^f@4C`#?5K$OqAjuN=#b$T zwj136UwU`I`#{I#rY`N%<|0-4ZDyzgrHZY63Arpak!!~NH&br8c}2$a5mCjimmzjnNFH8#eK-!D( zyz;~N&o3_>UeK0@`dHw5qNAeGSJ%>5U6FJOtR*6Gp=6eVZ?$QE5h)dmJ|rVS4)>gn%f*1VmmH0(5!rKpxvi%G3Kw z?j1j^5RgjWW;6I^OQOJ%Ct|M_9!Fw91fmLk=sTnWMc;<`N`N(P z;~3h4k3Np$GiKkVP(%T<{D-?}cVC5lTmkaydQ5tzL;{mOen*krd0}^^78{D17R;%I zyEQ>shs9zyqt)3FriBJxv&>s?dqaY=?shd)=jukDjCL~$pC_Z;ON@TdN@DbbUbg91 zBpwxje80Bw0b*pf0A)g4ZsTWd%<^VG>TO)_>^Mi|m41}H7N?)T;P*s&Df-Pz>7r1hdhy9Z&%2qj$D)PIxZ`&GQA|FxUa-uw3Lo5JaBa@DuPMP__= z<2>Pd>Q>)#&D%O}Ei+eN^{e>)0mg-YZYy)Xe`c+z#N$Ysa|`k=Y+(NsW8r1~<-U8c zAK>a={$%G1cw9!%jwf0HXXfTD_uu2Y7d&@b-yb`jc79G%L*0Cw&38-F;s$M?jPCfH zrn<&?z={05Sx8m8-PANb)3(dJajOV1{c+`+R}~_ro-`h3W&UF1n6zR zgOFE=Fv`>0fGB874d4NA+&WA7tUr-=Ge}*Ye9@iqm@moSJour~%|HsuAv~2fh3kpG zBo_foo`_*W9LPsPK?K6YeCT+29PXFxrGUs2TCg787j24OMpmgvN-US2PXt-+uzd6r zLa6sWwK=5-=RLBHaD2?Ae*&yuJUNEXj?P+1u1u}WEG8+c(`qEEsXo<+Pqxor08y&1 z!FGV{2Tv7e{@8Am+n8-1Y1UujsEt_`+(G}3z&wd0pEMe3X%AS3Npntz<7#Oi<~BC* zgTTG7zqoX)yd?-G(LendC_R*J|h_4 zwmbdPzZ#G+{I%*Xzi-3Rw>mc5KWKM#R}g-l?-}1lsarb+PaZO&gsWypt?M@2S`v+KlX#=-fA8LK|N3Z2SHQQvZr!s#!(KS+ z%I|gXy3FF?>bea}BLIvl{YJX?xg*U4&}|Kq?^C z+a8|M)r>&4Juq1+UD{CQ4e2_tA8k)hbH5IQ?U8gy_C?#n@m&I}HE>LWI_FinO~kS- zO6E^jwl?5o%A$FH7O;d9(9>yE`Z_>f$GKaIV;y1J;~xKvO^8!{9kvMqyuL~ZVA4}u z^z|-!j*G_JuWA-lV`i&5jtiY@DLsw}byVGH+3fFa*3P}7u8G5@7R9TkhaF#S%e=Z< z8|)8s-qN&Sc3qR+1X^{2ZC(iZ;h5)Z#2Di|NsNcFl^BbP+KHi%hlsI_l4b8jgPB8& zwvD=)!ajut4%|{|`%Yqi*A(Odkks}Cwy?$Ul(U^E*lq*^+l=jjEoqbO^#I8+xS0B> zw*$N%0oF-;-F_LyAL>3OoNa@IpVoON7NQt^`>mZC5clE2!@sw7U?=PywVuzBHkOWb z1di21ZwK@?oqU84oNl+dFN}Ijd3rm*cX3vAg9lI#7ox`ok#{XtYvVwAR(;wjrMpjjKRsq;G zAEt&Hzz$x|UofI=>1oZB%scSvl)kQ8ezCntwD)-jew6^=^u72#zY;UfIcmgST^PWe zfi(tC^u;RC7h`$q{jG#ew@!-H=7mqAjY$-7A9khAsQKJd^|-7*u?ucH^H=s6z``*X zdFb@M6i5ZL@Xu=nL|zC1y4~UzfJC0&mtr4Dw=>H@r($Qeg0BuvK=hwjw=-PR-G(qU zr_Q}FAIuxlb>L+XABUY`z7p`!-{BQQ2>UW@&jfg%B|-p`M#sc50b1upEQ;NANpxbs z&S%9_;@MZ?do|TpK}Ddha@~;Fl{*@(Q#*QHi#ay+Q~qYU>Gthu(5cwB{oqSwY_}Z3QyJT>LWVAZOaV)^gi2sN{8aR#5-G7< zj-S(GKPxdd|L9{o>U2+IJK96uV^GB(KgS3As7#q=9&K%`o!ipTU=8h*GA4Jx_^dgm z!%tz}!%2+oZfUTV3-tazsA6o&U*+K%2!PWsll1~=SjE2V);W03Z}rNiKey^Yj^Vld z+QQ`rvW&bXmFiv0pE@{i#(tXni)*aoC+fG2MV#JmBd-AU?KIj^%$K5Alk6zxP!ZOL zhV)DtKk9Zx?9@nn^3bvFM&MXo#E!<`SN#QG0{I9bI9=Xf5h3z)J9<6% ztm+33Um7k?^n`t&ygJfUkjXo@DY0@ z5coj|4$uO3woqe8oxZ85}QL22;>~ zy8=1-&ok0yypuPg|GO)*aMn>3K9L*>9rXCB5r!3!A8Hr)F5;Bi1@*pg&VuGUTX2Mb z-&uu^t1m=dXFaAK5~y#9F+@U#xpqvi@6$mC;RHn2FGqlGJ671b&MZU4I;WH^T`?o{056$yN{>5k{T*FkO!!6X%LBV3DT8!JSL^DsU^VD^trB*7Xqu&xhN#xhhDH%Ox{Fsx{Y5AaO3Oap+32JRRbvp0e zm6ugRmyP#Y^LF%WzA6U{`Z$QR0B!Q=(c`&|^BWg^BHoGhq{l2r0ntyk#d=+ifDQ^1 zu<*IhCR=g>J-!;(=z3faIu$)$4ZfS;1SC(yx*k8Bq8{IjOz3;*MV`nPtcUl79_#g% zrHAgdHdg3ej|YICdE&FO_1LPEjuzW>6!AUiaK)IDXqU&F#Jg?x{D-v5d7CS`j7XrZ z|D+Ajzm(eJuM=dz%-uuE<==PYo!?HkapO-}^ zczU-ToTp_O@Y#v&aH^_fKa%UOvLPst0$h`L2i3wwkxQCWIa6qibOd@I+q=(==h!~J zg}wW8uJQ9E(<A&1(kC zBJc;hj)j6p_8XaJhq~^X@vTFD8*^c#`iL>GD9Z6ce4F)u?AV`RQ>ItDZAu~TS)d7? zk8dryD($`-Jm6kFuJJ=T(q3L)@`epAMJIHn;W@+Kfa zmlr|=b%(moypWIbr^4wrrwz1j!z3-Y&G94Re}Pv(_=t6z6M=Bbq`mnto5Q_Kr6LSi zpgg# zucvFa2xF3qPijn3DW`1oZj1hEWjbk|!7y53CkS0Gd>Y0d3m4SaEvmbywzhG;>fznV zBZJ&wJp?tO5At{T1s7d!sDIQ?0r7_rpz~FNrVa~;e+B|{z7S~EMFHW9Awbvt>7Y~5 z{pH|WBEo=0C-pQLy%~m}3z#-12afl_e9$f-T?ZZqaj`=spj4}v4Ju?`pR6Y?s3HA{9IHaCYQ(2AzVkOw}>zZ;i z=%6qG3m>hA-b3K5zGx@wI{8>rC&B4f;)|eDu@W1>#}mi|Bu~V84`C+=^3qDsFr(NhnB`Ln=n72LFC1(+v3E4v3^sjBnW^NxPo&rGHw-IJpx09%@1yE9(-x3C5r0&@X4wmf zJfQ{a;eDak?2#nkqt8sb^*ZqtCZ~=br`w4(dw$*gRNCw@see_;t|UoqHs=(khcTm2 zomX9bu&sGV_c6R_*l+aqrlAl8bh_GUl*A{ton|=-Nc%eh0eYRD4mv1Iz{2Nlr&~{; z&+c}*88T97rymDjD(&>iyfOTHZm0RIoOYV(nP{h3MUT^EjLOHK%v*->W9$!0rqE9R zed;pp9*XJ{+BWy3%kH-MM7r#5o7DOKHY`?6`94C1dZiY!6xw#A%y3)E~VMY<_4;=Z?t{Y*`^hA>iY=J zmkrcY`9$;+%2CFw4*GbW~n*ED-RCJL=X$ap<>*l`Au-*BgFo=6t5!>_T!XA)!DGap!A4J9^l z-hz5gG4{TbWQ=?Uws)KOg!SN(Y~rXt#H&B^PTu679L~D#u|vly298KK2kbRQg!YtP z9sa;~*mp3^d)-05@u}Tu7}I#od;e%;^WEmQ1My`QBZlmK?9jk4c9>MW8X9=epHbNM zU9VA4 z*=>EbRuJVUuo0ecZg5#(dB#2I_om(FU*Wr-y8%!6xXQ7ad}@7XGT9&CBNGkK>nZP9 z`WZzwpXjoi&wA{JaRK;fzk1^>SvTOy!zPat?7ZE}EVq?fh+TCY+3t@U5Mc#3J zHbf|W0zdO2@@Q*u56wUd3UGtEJh@-@n^c}IluDnCD@EHNnRbbe=`tT~dpQdc#RwOW zbcGhIhxdiOWcen*TAls06Y$YiYs=-l&vW6J=Z$do_)M9j9 z_Kd?jn6qB(+4z%~e>sBu0UUeAm0^T``J*SBE3_41#E)Ci1@r6x@As732ene0L)yMO zi{Rt34b*wo4Y3WC@UsjBtS4ZoFJkERz6K0IVFIR35xARG?<1XP&gClb={g?+or=ys z3cefQ1SC(yVm}$j)tx(lsaqeW^XyA;wUmI!6I!qy-WNKrmk~>kby&(;=)`kyzZ-GW z8ESPX^T=y#9jA(linFp>eG?>H03NQ;8a=kWeEi9*@~o&#dAw#n3`dtaUL$ZmwRy`6 zhqGo5!fB@y{*!C9`d44t#+6x@OuqCQuFm4PY)jZ{W}BDq`4KoTnJ_XEI`p^Z<>7*T z)$jBl@h^WY%O=mT4X>gv!MCcU*b`~q7CLkcd>6FI6>sk~MrQ6S>N-|cbY#D$>Y#rH zdpphBnz!Y5U)*oV8&eKVAM;P)SNHzQAJ0ZVsQ(B`qQw46c0w-mHAsyft#m}d*T1&2zwVKYG&8(8*;A5>qVay-PZKZGbJ5$W!O(MB;^S1hltt7>VjZEJ-Z z$a<+2E!QS}0(H{6m9ftUa?2yz3nfpbEj9|VFNRfE$(ndxo)IZ|zOc?HIua?W#2y$R z;>fY;QR<<->%|E#-)=p+ycLNgdt404@k6Joe-J_%GHaxN!1B*@6$&^P#8bWAJJwER zVffR_=~b}vSs{`4DLClzj0Pv8&72N2|jT0Fbu7lMrZI-jd!p;)aV{bI~bsLI$;{~OGq$?xTNbBcfnzqXTH-9 zO*%{|42zj)7sn)nFhU}aZ30~$`x<zEOC`{ zP<%HZfSh5ub5f|l1aIf_KJ1IhQBVYbtJT>zN#JiN`FZ;eyU@7!%Q4;NUBlWxKW#?D zC@_mhTl2;n{YL}-s5xU>_(<0+owxE_(O;Q8)uJCR&0;p}l}m){yOe`j>Z(w)&KOLsCxdt3e^>C*L#t~qdGDQ?l>DIu+oIoJx-I&2>9**z+1sMK zgCXFFJ-^hvYt*7q3&+)I60^_fSk`e*he?UqWt5nGGbLt2;z~%YO_?w>9}+7e5mKLp z)ZN+H3Y}!m%C3`j>>(BlEyaaeGjxkt{Uhu{kS905uTu9MT&h*DbQ0Tu%dxp8GE#c7 z3Y%;vWBQ8L*6FRZOrQOUnW2vZR)vt(EMhuVF>izfgNSK*8)1jjjziZ*;Q;+n|H@%> zdFx?kehP`aQaI@Ho`yW?D&^_z!pmT%T)~$&96OjIkyi_wttz%V{VldH)xY?wf=v(i zC4?J<8^fhL{V}{27=+mjrf3p`C)0l9P9JOKA#hj~k?ZY8ez9E&M`8}=_!%zWpK*|P z#ih}X_?7U&A(1C`;kx@^U@7rEM)rJsEIlPPZ69nu#{0K-%Z-&IDP7_}U8Q$SzI`eI z?eu9P2bdpB51aHHWBPdQL*2TbVG_G1f-_B6_Sn8;`4v)fZIyP>UDN6q061!|w>_B# zY)3L2A0|ivGY>cbquS4JsAwU7ydpEBP4Mm*D-8AEPLU`aYA_) z#>0zY_aYMdT$IRz*ErJMPZWm5^2duwUi-i&r5JWmj$w#hvf+9iOStNDC)@#YW=IC} z)JlYbPAZsN;tc&I@eRmd?G*K3!6?f{10unP@A}C4=wxHT%G#E}gafxOkQ~*^Jd;Pt za6YbC=1@EpdHqRwJQsKMHpsF3h2W3R=;6l7+p+P0V@Zkdfch_Sz@=(i1$p6+;6W+u zI=;LNc?{Q!2W(5>Rx_BQ(qU{mCMKWJJ`w z$SC?t*Mf0n<-X#O^-uEjsOC{tPSh;oe1b9MFHSto`!A>~S#U+P!0;DP`u7Vs%!(wkl6-97vtUFfgmsV?@D!6kF+ z((5+v9BN^1dPYXSnZeLA`hC8y8^4M+cmFbKgjzeD&??h+E;)F|5cu*N1*Or#;7_B0 zt&Kfq;Rq{a{R}=Sf1TCbNnZ=CxplPvBx>xq%6hBE$Y0g7)=DpUwa1pmID8vBr!w<& zt?GL!6FGPD&Y|tCJGmO?llhcV`rIUyb7x-46Kl*z>6T_a-D%!iTxa%n_&-}$77YfC zDSwItX7NqtMFUg$Cc1B9QV;BWlIhl`PPmDsMjuYOVO*ABKz`Y0KdH*NK89Mtn-1-U z!iBRYtRHeq`mJfVrEW;MJ#dHrPJAsC&Ixy?Va7Q)qe5x z*@M@0IGyTt=B<#F%c*dPt2<$N1a4A)(I4y3au_}?b$cHy9k2_Dyiz#m^0vdm@pEOB+?jL)(I1}^;xoMeWrvGATz4OgwgT(H7}@KHx4VHzYT7>7R*3hXs^05HSAdin@t+>I z4wE@5>x}LE)N`2WF~sBFwllqKif`HYRZhx1KA)+^iWq(B0NWmuW4BehhdlNRJod21 zeu>Afe@nx7)p+hVckT|v-_iuZ8W5{|&p_pnhj?dTg13Ntv|&sqM+1@VecG=h&ozvF*f_|xPV zjAZ#_JQ1Xd=Q-qv-!g|+l0(iH$PpgPKIP#N!v~N+kgEN-)UorqxH0@Mtmak^1AYg1 z-mJOKmqr7(AGae6klTLb+Vpp<5MM^>IMbNkdj0CQsukdEEjF){D^{__bZ(fcW;6$N2UL~~p@4Id z500#XZrj9k)rt2=-f^~L`I`#Akkzan!XNzw#R4w!ym-$CSVo1!AGwbA@4%r0ZfP)5 z4`$=qi}ww9i1mSx$P;@a?ssEn-}T3Z%=hy8h?nXI9x`3&nh7%!R~&zrek|?Agf@1! zP)d!4rp8s|8R+}C`}?v`4m{?Z{HbG6gb#Adu9|GH+d+hUA*MH#+$qj(%OU0z8*!%O4;^pjbQLPJfiR(Xwj4z^aDB!;2Ph5`FdkBN z{^E1$hFJk?BSu3;ckaB_D7rB6biZ%-jQz%pX|Ly_2hX1IgSQ)n)s@?-hNhnTT7KU; z^Y$m{=fRt&M2uquf}I4gI3>Mbd^25$3jIJtX$ptPu|%E9~i70o%NuTq+Iea9_VfAbxGzz0QM ze|GWtV4L7r{z8sCJzS?=Qt}16yjWO{@#hlw@M2-uk*6NU-&911VF-!5Pr*UQ!W$tk z5f(0iKOGCXPDpYA>$My`=o?E*Wsg`oWM9TkBNAvpn|mJ$B1u7c|v@R;kYN zl`9+8wAQh|h4UC{Rlf^+4cE6Bc1J93V0(FWLv2;#nr8R{odd&fgzg|m18y@pDviD5 z7;M<@aHbQ-xet@0faH)PV{^$--e$}!4#`)rNww_+#*bY zuFE@;)a6PgNA2fLDyM}*f|Nks8UkSjLvM4G_V>&Jdni~>q8WAAU< zkEcGz^nuDB=ADZHAAUR}YW0L|_4A~rPNrTj4kdp=~tU$39>l?#TJ7xWzs`zynJ zH(tTEy$|31n_J`xueF%?ppR+f@?{;m3LI+!tI?Oi@v``1XUmzZn2gK#xr&j29PNLDT1&!0Goxn5|5-i}_Jkd|yqmEDIg+t%NHi@F7WF1>@R&$_mlKQCtRp}p`o5N7O!KfOP%zoQmR+`A7( zJAq|7M)o}VGS|VoKi9zR2F^n=?#w$EGvbbObjmF5=fHUS^d+aF{jawRm>#;0>*>Sz zo*cbaCpUd;^_uA@B>L*r>tnV5y?TAD_P*J~WMUR*r(X z@nZPX>*wRq<7@D&ki>~xZ_^)-9_w>hB2VNC*WCxBem)WXc)NCS`|)leWq#^=Jj|Fm zbLMfKuQ*70%<;I_POI@abz0LPYVqmSH&3L;f3J^4qd5-Ie>7$z9_d<6yN)Qd>pcb9 z?Y*dCGCq2{I=(*ExBhm@C;~~K$Fqy2G6p|c_3`Pa$IiKHgQ&@WuaA@KFLPY|@AYw- zk!W1q*4()I7>d0zkshDtY|O8;c_2M5K8`bnnr%pP$I-Z+(LQ%AVDTI^u2710K836P zKW4wrbJBcW-m})|C+PY~S6@ESXZ-nU_EX+|c1a8zRXOpVt+vEHTkQ(>Y_;-JbGF(b zqQ|Lg2ZWH`%yNBRPS;QAmrsQsy`5fz8$q~nJd1v4(Die_t;MCHjreEVT}b4yU7^cc zj~nclQXbzOP5;-g($6iW~j*Pcm;(YtRa=CM8+JJZ#n&}KH47?Vz(#{YU&twhH zi+}#fi#+1U>vv-YJT>ifA(Ae&->jIKaI)S>uXK=s|_A z(`tU?I*y1x);~Hf^#KF~5A-?41@NciQp6)q!t&x0&!6}V{0fOb za=rJE3*md=Mojv!ImZ3)$N4!SktcTHy8B?@65|vjdktfa>)>6}IPiP{(}{6p-pM#) z+@WQ5k^R72fr}mN0wwWX((#NjzGJ^n9CqMrvJ89g$h{wWE*UZKSehU_8^Rq`1=GLbUi-SxZ-^H)AhI#b{!WaEUzAKhCj}235h>)U5_7z zWiQ+Y(&HLL;#BM#%Xr1e-fJV>b?}}=IItcQE13q&JJDl(bV8L@+*54;WKb@y?RC5} zKXF`Z17^;0rU(aa1H55pj;qJ))1*Iz6TZ&JYN0UClpYaz5@U@cUU?EL14h02$}nH~ z|4f;VmciIx6!smRH}BvJY9#=BEa}hlKlDcKQXr!v57C(r#eegW>E(+rmCq%vf9*erVXg9a`{3B;hQkw?1FVHkT0VCiJ7$;rj~f zgJ)ES-G0;w$E(;rh)$z%&|vG7wLh57EMC$QCw4Hsg#?eL!a>KQUAU1AH|cZGAN4K_ zV;5IkfY@Frw=ZqGbM5{1VxK0DaS?gmZ!fq`CK-IY5&n|-_F^}1i|@hJB;E9qz?Lr(ILOsC@HMmWXF#QruV z&v&RDUw#yQ!?(1v&?>;LJO6>}7nTNQbzs*W`ry}IIFV`3*^{GBW$fp(Y1U|Kn64OrgeWO_UH+%>okip zBcI7jjTjSyRyaCg>Ae?EvPz!k4lyReWVrV3F^G{h$$I|nl2YL59@#<0j!$sEdY74$ zyRGwz=!BrZcfJ1$otNbeiI`JTlcyoUo7wF-4o8Y zCrChCj^Cd*1seuijYB zkBgSKDy_hGMB1h~iQHPM>Rb6ylID%iwzX8P=2u8DXXR0|+rl&lJzU+{6=yqs4ENb% zITT`@LYfK_SC^p@W8KBFO+QliEWkB!UQo3G*NNm+z+IQOTa%~PWuNoNdl>esV1y)o z>|g8h_CX%YHRH#4O8lB}t;g@LurGrV5_ycbF7GuhezmmW(AIC;7jq&;ew4I$|06x}ZF}q~mZTW@Rmsxrqg7rrFIkVX zEqHe9wz@YNcHS>h_fyrGv$TI&+0*0pV_~=!j1cXd`=Ec;;f(#&j-B^LB7LjCh3K{# zhW_pQS?UZi+L_WL;d*o2eQ2It&$$g%y_Q4$xIDI-l3TkjmpXO%s@k^Z`Wkw>w!Wc( z+^q~@v1?R)UrVP>)x*#pQE}#eMCTxm+z*N0cVz?(V?Ox!e8&!VzKd^yU8jskf{UG{ zbNqNa|9PLKeZ1Fyfivzf*2W5VpG??^3qI)cQgYarkwcN&9s7;sz!_pF?{6nZfqUAq z?IHWrs@c* zF!8CXstwDwEYngSL&#O)?7vB1dRvu#g_zbSu?^^yw^;KnRu+}pptQo+uVZowD(dwH z-&^Vd6iww%@ZRgs&XWJPy&RbKLQHGYR2aPud>J>W_skdip-G1c!|3mEjdKr7k;wCo zC%l0he4g@{1|pBxCGUhwqY~yqUN|K3h*^64xEFH}Zj?v4BCi_PNV{e*MGxR#PeTdI zTSrIWuho7;{fj?x$s68igYY06SvSxyT&5G_hFdOe#tn`c3yD0j3)kHTqmBloXk^cu zOmJNo+ZeIVj`yFc_Jid6*u<2Lkzb{>ZqHErK=K_X!LZKq&IfzzFpk;KKV!oE`euL& zsc>yvkL~*IRtHp5=S0|;f;v~uK9;D``K~-GhBO|ToC8jrCHA=Z3_Ht&whtZfb5+&q zWbiW-a+b;rJWd=%7$A3CgyY2Q+iwkF#s|c*tK%c>LcBhS7^wQdNP&-Szf(_J(SoT+ zV;xht?+Z&j+jaCqLwh-luBWB22VsOnUMU=Od7MjSnWj7)^DcuOx0=BeRpLJxjM@x; zRq6@*PvS(bV-)xDiolJ!O~d#x9$t)k1d%uw?m{9@?80^T6NOPRr18%6N{wm9Ceauw zv7B*a9w#0{b<|rnOjk`yDtz3AGAggR=efcRB$i+X)~nAwp1sbCXU|D`F6pqHxGqMp zjg`5p@2PL?DA=B5EyL;3zIzI-C5L@qY3eg7mb`cLOTO=>e$(9iSTv_Q@Qt)@JQf|@ z%#lXl7NcNn^I6DOjjMJ^s-9bz+8}hMs?o$v|CbdO}Q;_x4$fFqj_~!UifD} z;hBT!IDR@SZmedpdd@woI=DXlmb6<_Z%g5s)f>%gvVzW&a&YxY#KPA4=9c=#HutD% z^+l{W4kkdJPHjTwqmba)R5<8(#`E*2rz{WjLqod-!(uF&+Ky}HuaL-N+fkR-0eQqF z%G2?Y<83e(*D)A;-L9@g{S2W&g@$tI>~j1sj8IR?jf zD2E{)qZ{oKW@hWZ|l8U;+Y)xlP z@@3yWsrNv>I@95NE5$0b%*`Ron2^52{|&oF@Jf!=CrT#%^m?F#jt*S~j`Oc?_S-dq z2hS@%faiK0vP?ajxDKiE)FCIY9%!vsWk8>vahy;H2W?>BbgBcGheCo9)Kwj0BO1oi z4-FB4*iN06I^Zr`Ghc;7o_AcJ5At&1DHBGo1O5Sa9S6H%Uk@WB@~(h`9=~)53Brx? z7%z!m4X*V%pa#PAGALnr#|7@ijW#?hB>u?tI^aSCR0>Dd0e~A7F0qVpL%1$+PfND{ zg+!j%h3oEvQ3tRe5F@*dP0X`NQq#5_Yg{1a|D%r+u#6=dCkWa>tAD1OcU<5C&wUGa zrV-1Sz3;!Ru5Ohf>MOhYFK=bNp;Vfch;~8}dIPmh*gc}E26c<;19Dj|xp!nKIU>dP z=bn)a(}zkfkM6k7vhUu9dk*iT0P=Z`IjHAgSI?nP&X_r?_;~iQD*l9g_C9bO!@Yz+ zadk{O`U1w32X=h&b+r9kbAbF(6BIl?II! z%d5~vT$E)6)|q9oO@{CGg|jx8pU=q34e$HWkAL#BtUwu-O_U8?LKnO9C@E6!N{kD03G6PUL<;?i#%1t&Oo}S!^)f zb^UnOnJg1Rf}&I5pw~&2sFSkc#TXlIGAS4Jk%G2x2I@t9(GX!jz4L2bP%UfsGz+by~0vCVe zHayukGl7lC^qcY!zw!j~G$(Z_;m|S|btdcb7)k2cF03Qt@29FfzSn)gwlm*tV#>xS zQNIb(dn&D1rdUS?W8RhQ>CSzY5!QJnp8JNYYi=zVr<9(alc;N4Wyt(xf2q>p41@NS z4(IzN>PI!x9gU1Oa`dB6$IUvPy;@MmB|WbG_d4$HbsUBi?V1qf?WERmiN*#SZO6f@ z;ZCpbcZo+rf`Z;U?iye;vCdn^S#TpRFh2gH(Ney@)7jE7<&O0_(3E>eX z+5VIGdB+CVLtfC4r`K^S;r3DMxMao#kEf0+MO=iKW{F65AB;MV=^GJ=^&l zY2ZFwpPk8ZeYn5R37y(GA-7a%JsaC?@KFDB8Vf9^t~n&A;KlrAwBL!PUd*q68;h`D zemkxg!w8AIGC1g%&-o>(L-;KHQNDL9a39>(!w88y?^xgl$P2;~vzFjE=!!zd{$~y1TL#t~qdGDQ?p@mzcyPCH~cT{eTet+rK z=+mWJqfcgUjXoRP8r>c0+ueL|->zYc#?__8J(ZF_v|t;a+ZKJ&*oJ4f;n{6?c3bq> z>}}EAK|aSMre5e{T|qiJ#CjL&GuH=h@!#sZ&AduYlTyTDK2z*JCn`1#9_EEE6Lke?rW=N+-k7BCR>?s+Dsq4o*w(Jl9v|kR!8m$x(om zJM0Wcn@5*v^a1w!NgBT86YwG>5B%bSd`LfnFC1%kOkIP`FuY&t`;hOm>M1LeNp1%Wm)J5W;-gf3Vh>mI9u&;*^ z5_y-wL62VmLV|FkJjP4nw*uEXo*&OVdJCQvk~op;cz!(d=$D8vaFM4usY~5`Fz`J7 zn=gAmlcjE;lA5*y+tTs=?Ky*(f7>3zccyfV63r3NFW-q}jQDvZblrYHM%YEV`)gF(=W*17xyHo`^YgXZ)qDs*PVg4ZQa(PIXLr zO>UlDXxz3r*X<|!-4pdiZ&UOAg(l%b|K{n0x0AKGStOJ+l>dMEJre4&Tp4f%!?t_7kdL6>pQ6DBqV2+*fwMl9@+eW<9iTH=6rb-LyP9nU+ zC!Q`TxvdHk1iqHjs)h-`ov(*f8=HHjFkbxTGKU-yr>?RsE7(#~-;^A-%$+mS-UfT% zet*!;Ocz^5A@{PM%CtKFl9kOhpT;Er>xHZR<%PA`&u_cE@NmZ!+iuRrz9p#of>ZMmLjYBNuTSpH)9Yu7KHGq|t%*-Q4wfG#hH=Mu?d z4R{i95rYU^_ch%fQHU)Bi;ePPb=a3$>f37VAqDZ*T3dT)`?FaY*+8VlC* zm-$U1M(Vmg30+g>9dV6*XlN&H5@STOufny+z@>XF;|}7FI9x&x4#_j#afcAXrQS1K z_KqdomAKZ!-3)sWMo8qXfP?-XrP_PYUF5anT9>yAcD|pG$ZLaxE^odjPw<-0-3dc^ zLd5?KVgVO^dOjM7#9-Ipaht?BO@95#NUeVJqRvK+z97l=2k3`nU zkGt{r<86M_#PKfph6~TD`bf!PPQ}RYSvllKEhqIHaW+vs$M0yFW=was)2BFg>c~jM ze-^k9!@W=};Ivo3@cAIjNW_+XC)!zdMk4*xZMqZpM?>U zIFakPeHfMlnWAoJ{37W4BJ=#+ozQ&CnDTB{Gv?`rT4OAH!F%;T_nWgP983x106V(70_Xdu zSa2O<{b~P!o;y0nmK*tadfcY)kuGCW`kriy&xWjD^!P1&;Wg!tUHf~+TK!n#o{4nQ zF=SFK@r_$?U7nT69RP1N{~?1P?qVhT=Q6PLoEIk#Q;7`YtDD25#%2Y&_YsiH}*U5EEDTVN4Fok>F z>-&L-JdrP4cOMK)VLLlU-u(oaQZe$Y*-zb`=FXu}9|ThrOh{`8prVQ>?yL5RhAUY2 zEI^UmSvsNQzaRCsFE}nad{JoES#`edSH_O+`d()?5Ts~KfpvAezt8VCi-0N@r0)sz z2Yv74*0cxu`~h?7@4JGtUK#uQNVXL^#yS9Eq)<67!tD3oVt!8H0UMep<$DqgIagP; z)>f}>9z-ZOt@d?h+6sw|6Ek!j&%+HAFSqWdKiVr`biHYZozDu1yfQfG^3=ELaAUno zToQSg<66gzhha|!Gxo#Z3K$`Y6S+qOjGmc#|7K{*UD#Jdj?+9^`JwYG{lp?_7~c71d0^5(Xd z<*GYf3OW3yP~id}ZC|(tG_wjNY`2`=aK?A$|TK&-9za)As~tEq{OAU&cnW zLb#uCf7INX(dW;2*17lkllN7GU)cp|X4c_xwyXoM!j_Iu_U2SpSjIUBe!?(DA2`P{C;qHAkWNWI-=EcQX0_+tS}|eI3wWDmj+fpxG-6Iz zWqrqbxO{U@Muc(rzExpa<$HU+Q;{0s6B~LeDpDfmod4Zp$GD@1Qg=At4;Im)aoC~E@VsbX3EOF}bw0G{RlJ|ErE>fj%ikNw3OvDn zUuLh*KiWm`^gX`*VCokuE{>jqO+=4|{?KJ?@!x0OpKFaNx5tZ1`!;u^S!=O>bw+O> zb>>(jztp|6w!@fyQzX4N)qmT^J@Qm*1g6dbr2@))V25zGpj(Eg8Kj znYq@!a-%l|AuO->oR!NEJ_&ilx)6%Q+}CTEjJ?>?_b}AfiWJ24&4~GlC&I>|%^m)4 zhpcDId&af)7{Ou45#;XI%=^sE)no6(n+>(hS(7aPCga>;{n~4i$<@>DtuABw zZ&b?7O_*|5Bi)RmE4$1s{{ExqKUy*6fUzYF@n`y^48d2c-DYTQ#n}fC|8ZC3-mRsD zX{QieGvi$Y-$4qktw=fWBc#vSMtzhcVsgE5A9T-I#J- zo6ZNueBY9`MEagoyv;x5UT9s{p4#V6HK!vEO~{*>->k^l zV@yoxGgFX`U4`vNQC-*ndZuQqAL)MfRR2BZMwG1ceVft``0n-Je;M|oU};X{&O=|z zveK=TNAs0S%6(~;&niaD?b5!W>k;c2YpLbilHMCgJ0GPzSC#gcp8LtpODd*VC3_ZH zo5Q7tzSm)H@%5%>{Zn}xwQQ?@i@(>G>F+jY^6mp2ETb8{hTqgu3#G^$A2o;5JvH7v zwKM$d$mZ}(2mTd#b8q>^a${nNg|jn)c8uQ~_gvV2|7R|x#+b9tFTcl1*|gMp#Exak z6gQT}q~CTK)835i4o`y~{AbkIf!xS^p#0ygxhyfocZKs0j72IB1qOUmivcizS~Y|2 z+41hitrfqC+!ana@DmlY4ds)p7kjQBZ_KzR5+8!uy(sVU2&7LthV;parJMani+>$S z*)qwxxBQzu->sO7n5Xv+LCT)xr0jg4*N{wK_vb3Evc|lEczzP8I3}al@5{0-Z};{2 zedd&mUeiaN6?^&~=t1hvFv{iyzX6)w5+1%kTN-b!!J>_+1xoHb$nkXzDkO}j01 zL(1)eJN$RTS2*kGbl<;bWK9SU_1&si+&skgV?S5=75k}wu-SISPWU*SJI7y*S*rT# zs)pq&tE$_YTIz48YO8N*)F!FgzSOk*OI6n|Z)j>_%XZz)eWxb-+QF7uDp+_#oxp1Eco` zYB1KW>yL!xolm+K{vO1$LgJ5Hdp(1D@;Aeg^B$N6Q16kbKQI;XV;TsFJh2Pc-A`11 zfMEpj=R<6nr_MSdTuJKMv0;B8zCV#_6yX-1XPNQgKA(TuO%N$n@_f4I`E=#~5!b(M zkM&2Gb1~vx>N;`n^oukHKF4w@L_5E$6r#NnhVf;Y9LbUv!w0*+atyecP-7&*nfU$; zWHn0Pes%5Y>be$9yq&Jx>l)KQMh41L135ZAx00V>7%w1V!Rk8pd8JPy^UO(GeYmIEtxr^;?S(5$BMbm9psJ` zb4+JlTJ}=`E4#~A_fWq%3+IFSM`6@Ay=!SSFhh5FFXC?>$1$IajG`mzROFz=wIWcN zxVn+=E5xxzHJ*d|@Z{A^s_?W8X2o)<#&knSKW3R|>}*_@!UzcxOofAvvm6U0t_sG| zAMIr@b`ih@h-Hr0ASCj<>wTk;M?IxH#zo{^ifbLWAAp^46q2yKxE+Cq&xKHf>#(JxMs_;0pAV|5VEI687`6*#?dZvE!_>7ju4x!dwLY!-$E>S_L|>`@dOPNA zCVBejOex%TdB z5x5Q1j^VnUA`u2I@-!!Psk;wGI|khjjXwIhqSO`YzjvMd1Wh{gQ?+1J@s4ZS*ae== zce{_)P}^u@CEGac<8mE+4tV0W&g$l*+B$PelAe?Ls}0UBhGeK!zkC6k9_sZQTr1~m zAKGqCnY8Er@Vi~Be;=s8`kTN{fA3p`UGOuP94v1cxw8WpDWe8jMqx+aR@Ab$7&rEyv zsrPR=JOObz_x(WsFW|rM{lK67eMb$m@2L5I-wsr4?KSak6Q14m{(9x_9LHb5`+-Bg z5BSUJ^AEqUD;snElhAWaFS;z6et{hWzlzuAoSfWug}SRT?d?b`CWt|QV(Ci` z?n9dS4NA_(d=jN+z8_HO#1#719)>(N@?dYkq`$Y)5L!`cWcVw0wl9DGp~G*DP34+%rMzbJ1+9b2R${CjGvgX3Gs+Fn|AqR|@)WDrY=59~?E2shZJM`wZfK z!TN)~z^-0@Qx<#2MZG;s4vs3kvU^V7O%<1PrMENH_V%MkfANxoBUd0T{TFxp4(5rZ ziUg9DWX2@T3w57yFt1`#*U$}kK0LXb|Net{^Com7y#r2sY7I9HmN_nSnEDow*iAiri6DoAT)A;WId^XGEz1c1_$TxC{b=6Mi`}c5 z49BTHW8S`bLu)eB_M-EK`WD((WkWCLexndo#))fZy$6O|jFeAQOuNKL9hP><5MM^> zIMbNkdj0CQsukdEEjF){D=rZ=rq@)pRT)44ynX*tJlL&)d(aV-4^CXRA;U0&a^c(;%sv-()?sq{SpGur!)GKY`fG+= zh;<>!TW3y1wcc@!nl%P;UfheJf$J z{CNB7++R~4uM~OkdQ9@Gl!)E-yQyNk`SE7)a!mE!ETc9_YS}iwx-0jXE~yIH8P_+E z;3Fw*LYsl{Mb<`G6lCwe?1yu#Z{5_u!>tEe%Q^Qv*_m?S@3r2sqvX~%Y_p=h`hhVv zRD&+@%}#E+6z@HVtx~Uk>FqAQq?G@BTr-bR92I%}@gB*mU&rznf?qzP_cirWBG+F1 z+KvdYe0$rZVMiXAB90pb?MwA9@;KI`w@G(F9`%Is7#I4Ze13a`TP%8tuEM|mF7m!! zeZ33*)FK}HG4+nTq<=|E+FyocFZe)h(z_6eAp8kQxMCNsyAMX2l<|s@cU`6An(ZUe z*c#J?abkM1O{%XAWqK>krV8twR2FSl<1wa)NaVn4;`U~8-*gm*WXaUP`oGmqL|6Yg zwuY9YZ@o1V?W-kSBk(`7>yl{Tk`ZVvvPCj9!cnvP=kY6#z@Ei$q3h@_V-NVE*u970 zYiJkmKjiqOKiC%?j1*d#Sh+b0t%fBBXBEm9AS3$B;i(a|Mo5j|rSECJctoFX_?}2{ z)K@eTzDMtwimSV#MsVceo0jbC!hQIJER6SIoG!sPBsy+Ai*!BVxaE8|(lWS9yiZv_ znpnglBBh^r!1dcgf-&CjM*83(D4xK@pLcvLh#S-m;?swXk7Xkg$zTz`3ruEw>?&Z) z4unYz6kL^f;Fe42h~MAx_!!H)J3a>Z(4mI|`p3qa*5<~f+8WNb)=7Ln#`X80IIL;j z6=;8;Gpjwty0mjwcxWU8BlHi1(;_3)tlwX{&WM^zjH!KHlg4t?JZK$B@Qp`MiM9V` zg5jJV`x}odWxV`k>OIo!W6)Mfr1!f1i9WM!VP~tI{&ir9{IM^fw?Wv(7k$(9ei8iP zRhBQJjb&7?znPXoqQ}&CT|bXC4qgU-dYLbWJqRNt@;>T(ehmaA zqwn{^-{&PzaETMS-sj+1vE6WE+n$E;@@#8S0`KeT_rXHqd*2?qp@ii!C z+fuFE&dFARx(->*3DyiTzC!2V!rkZfq^=u^CG#L|6?j@<%_K==aKQ#I*5u#@^F!L< z^vCgtau{9Tu7RD;3W>Z@IOy0l6*pMcDUan;Yjx`kC z4L9P9yh|di>4v{V;o`A4l5pra7+6EyjZr|YO=bLSk{ZIcB^uutiCc^l^@Z4yXM0uu zlvC)j>v*cd5m0f_CRYA&i*s+wS64MOG*tt4xNZ_16qWKi{wUnRO$~Qu z&OHv?nOzb}dQL9WPB<5Lh64q&pSpXpaj5v_U%fq|?`y_1v&fumo@-7t3(b7%i*WzH~1n8VFs=1_BpnP#S#_%_KrYW!d0i18QWzm0c|KO6nVpNu~ky~gj2 z8St(DdW_$Gz%6$FP2<%^)!l#pfS-Rg zeq#K{c+vPFnq@Q0=Z)u#XN>=CJZ0=OI*lic$Bge8-!=Zl_-EYPhPBY&Hom1v*y3E@ zXZ)k_4Pz75S^vZQ?C1Y(K6)AiP`{0^jG~-9W1Sl9@MXhj|M!9tP)`YA@q@2h0O79WZS$l`t2=sPAyWx&DCzJ8Vx9_qg7G^FVDdl`tWg z2{1V@e??rlZebte1hWyQ9p);S5}0npF9Nd>rURw{rV@td8}QrlNiaDu2Fz<<`(QT1 zbimZWTm@4K6M`Xr5L=8i)Cr4>0`^2kvAy8*MXp#=U0sVgy-S-DW|wX1{pcBR2s zFk?v&H=1;LHMQ5(S1XBCH8m{^744ChRl$b(*0x|tLy3;5JaO5#J z2|A$$TWY_!2Ct-^h2PapEww@CeboFV)1tPqY0av-U~6+#buGhKTHCU^zO@x!;sk4I z8|&4>3|HQy+HCThpVLay9FV1*KTGTf(_N(j!UCsO%_ToV`0il!E3?~3b#jrNm}u?*R@x~lQ|U{iB# zqe}f&$a9JS?yL8%scpsQ11l}J*%m{eU?Ro|dWj>-$Qu%XOG zq~OY`)%7S4)CRZcu;j}-IUZu~{-qXxmdZRrRKrcax#;7Shy`52t--Y(?jr~{2segHclzUdtbsu?G=nKx3VE}|0?sf= z-g$%d@OO)SOZ|&KawL~aHCRAY2}iCYLKIZEe1FD4OMYV?KKNu>35h(h3)kIGRNp?P zm-ar@Q`|u9zW)aI1tqoZ*s<>)dzNnAa}eFqq8^ZatnH`yZ|`f(^s!0LL8h12K2)VC zqsOw$u?6B*xAS8{ap@!+Tpt$zSrUG_s}2LIFfU{ z40*)iuQ`0b!`a8<{ceYIZj1J}9nQWK?R^gCUWv3v9nSt1?JU6L0f(nMJk#OX4rd>Y z{&F48J&$M)I-LDD+9x@Ds>9jGqx)=!mpJ@FhnG6M+~M;bzS!YQ9lp%rS2_F|hgUkh z#^H4iZ*X|C!`mF*?(iEO-r?}|4&UJLyBxmJ;hPWz35hPkV?Qo-p=4`xD1823A}w3k3%r zd!KD%hdTzw`MaTunxD$CvMf{eo(;82dx{!!-x@YworH1skTn^*4mFp?`qji0y-g8> zU5I$?EbYA&J5^lqGqpqG$!t#uFi3M^Fm^gWb$h-<&o3$X^ zWDHyC*b2DW#Q+x|*5QfdmBC$?cOwL#n0{b9{&KjXs5gTtdI0~rJPFHNXGh>~h5d;7 z7k}h{G?#K9oDoJ9|Dkh#Y@_hqghZa$h3oEvQD?I)5hHs~Hs+a4ww>u_ljNdpOEf;8 zgIkOv(~xy2m$nO0PLWu^X`kt_b8VK83OA+>Zmk+~Qgeh-!NQrt_h1~fkFQqkyoche z{SHtMgb)bNSepVq9*Mws>*rGd$Id$*9Gf$1rn3lXU>w_s@Ifw)Wuauut2c^5yRLkF zTYpVpTUs#k=9zOAu00YM`C{*HMlL!0Qmg;S$ay>8U)R52$lCfB>+xMeuYc6g^8BK6 z-v}0^{Crr^f;TdX%%7V@dHb=8TZp?(PF(ornYM%#BWv=_BO}Acl-D9={x5sV4*kc9 zP2s#q*`fae&jo)KJSSoV`CQqdAH(*}8)b)H03Y)6vO^Dnr$qkr`nGqUx?Aj45V0~>zhc(Mw|*sJWpj`V0CWX>sS zH)k6~hq{azMqlqbqcCXEeYo1gsiK6yg7?9mUpz{l)(DqLh9!1z&!omL9sZ zqhd0yaOmef9ZMz~eRp>}*gw&KWl_uiU%fr5?@{B6AL;j`@iXI~G1UB`@rZxA|9|;! z@!N79Q2ajM7mZhazw!OiXZVNv&-PF9Pd7gUzp>w^jl0e5<`41vqS0mEjennyQkMH_ z@GPHS4b$qo5&s)}n|yZ~XZa39b3?haupe5b?9nwZlGcCpQ*9NQue6R2mSdkTpE(=f zoS*H(UTEvXvmK=Oxk;B*81lbtvh1OeDTZ|dsmENu8#5}6l3nV?=R$&#-#uAdZ7GY!Y>~v z!k6zC9iH)oIp?gNFOPp9{NgJU3sv6D?uWG8(9qs>{$DmpynCE@??@Q${VLuM;koQk zX59P!yYt-UgwO3(&)uqG|FuQ;hPUrQzGK%!Gn4P~gLNDDF2#G#+}m3dB>l&Re&B(Jk|DSy(hZXU}*m)%yK!`2Gz2Ks2)wjY#bGg}2W57kpv0_t0(Yu7ge* z(_c9Ah2F-IOZsZEvW|@OnO`@)xzt+Yq{^Q6+MWnA9>LWM?g;x1HMDjd+O&3B!PVif zMstJD_8Y@X`z~BNtbdF#F+cTD6YG0Q`|et6hE^`{f8DoP`|PDg(QA8*LbLE8>(kLfel>BlyVEWi9euxBYas5BV-{Mz z?tiK%J@kvUcq#}S*n`=Ig4}VRjur&XStGA8v3mK6ia)6RO_o__sPxxM+eL>npRlFw zIsDq=iAvl>hmSnoR`Kqu`+oO&bgNTJXQ`6$r^jbH@3P3&^+`AV_mhtY%762_!udrD zkaz-^PAq_Iu`J85haV~jt^ypE7GwTDk6DPrx!;mJx%!iSDxb<yVjUhe*U;0_P$wYY#d=#T0eA4*u2L_Am-Vj=MnR2rE_}@4|zPp z(Yo`H18+Gw@JZ+H`;QHA?wgb-s{f|*MuXyGYj{7*r{kO_JG|SfDY{+`Rk;U?t z9vX`Gd$@3G;nn4@Mgv=yIyrjL;lDoimGQeE_eYOiVJSQ^GrGsNvs|qYQ;RM--22#f z!Z*G5)MHcHmre=vn}I)d-Mw%V_U0T}=j+YPT4DWD)a=gc^Jo1)?O2+L{ghvM@|OrR z5M;Q<*KK`R>!!lq$L{{E?e=Bly%A!H8k6?Cx9hRBzr|D8a8pmx&sQ%fe5i>3bQ|!2Q3#l`+Lcxt@9R zWhmD^e+2kcJ!;e}-=<4w|J2^z#_=rW8*){2q|Pt|9s@x{*>WgjgF}_4lTWTSpV46kd?Q9?`%Jr`e+OX9^W1)|K(dj%dV%2 zrdLK%AI-KV<`Wk$I^6bHD8H=P7i#`(X5sT_JN#(pL-#a5|76X_Qe0mHvuVPDuTyWS z!_?95J^JXB3&C&SuwlcUm)^DTu0`fO+z0nwV1qB?<=za_xQFSOzGs#Pb-ua1=B*;U z$Cyx{(2n`|{I58rX3H-^<@fib7QFwv)clm5HJ4t$@Rc5>{Y{6hCwyDX3w)cF^i^kF z)Du25yk%2()&ZnOCGq~I!{tw8Jux)cYooxfsLq*ntvM2QRQ#(BF5quu)*gj){NDoj48fNf%|Uw zx%dkxlnMixa`p!9dx3cRDb#%9*%}z1wd;2Vf*WTE@OQ3zkl)^5!{%Jugm>~uRqvd>$@jyL|4Ir|2*^NBfjh(12tKyvxB9b zX2F)RDMh>X%qg6W{{F7#{`1T+3*g86aqq83psn0&92rsYQsml}jcI@A z%C_aePt^$O)QEgz^3S_|)AMY9DzIt$<7qvSGw1!zUIQFJ+2QyG$AVc0d;?{RWsKzu zR%2r8#OYIN6c6!&eVS=>pFR_=;9$I-;r_v`VU6*bX%kmZn~0OprmVsJS+-yJJKuSb zOkFz;6N^H#8fxI$Q1gL#kf{vFp?ARN+55-WX4nTxT#Y?>c%H;EhsT|DzzjCWwT?e>$c-Xi|_6y^U`*S~##rW z*<)Ylv472D-|VqJY`?~E0F1&ynV-?*~Lz;cRK z&tV62arTx$MfWKreg-}?x|MvaVeBQx2kP%R?$e=5y#Jr%a32dL%0MG*Dmm<7a%_I{ zS#tQhpB$5CoO_`CEr-8P4u#A^+2eCl$T2T_FSrl7xYgkgJNyxcZ+AG?`O)7laum9! z9s6#F{~LHl5OY=Jh|eK%#3O(rn~{$)PL6O_k|SPEI-KXk)BY&{FzLr17I=! zpC>Ogj1GrC>hOre-*b32^oRbat13Mm{;g=y@Ydh!+ltyidWd%Ok!J z_fgDMn~MG@e+dlUwHZv&Ui|CtEMa-u9f#p>xq8C>6My8Amb^0?!uNus8RfnUv~4v9Rm3)kHTqus%H#pt8&EkS+Z+zz2oi0`TDEJB6$A(txJPF=PTUOsf+ z)&@-6B=f!Z?Bw^BarO^)afW+KWbYbkE$j?%kJd#7%!Qri`Oz+;z}IZ=+IpnxsF7%g>fUM}aW}P7RUb2d^m5KJ9<)_2Qr_re7J=wC1A{0?R*+|c|*N*}wN z2l0@E1#fZJv?n6J$5*1g&-CZi-ewuG7Hcgx4oTwV>GPbjIB@AIwO_$4U93s4>!OK0 z7!B@!$eo3Z{s4Bqd^xkJ&+z5#DR@8g(5QKwg*+NQ?Lur-o$wZ_jJvTLI*6YJpGs|D7V5Q4 zqSmQ*7om-KCI}-WwbEQT=(WvWsG6X>Xaj2-wt93e+yQ$swar`b$Cj3mXb`!sgmAcHz4FVAM8@SB$*72@G7@FijaJ=9OF9K)v-wCQ9fBYMK}pd?~rp z07BBN92g5G*oov~0ei3h_D!9kT|+K0ttoY5%k$h*xzhLe`-6eZX6zD%Ger8jxW!&xy*?U-%XoNu zqp!i=M7RryJh2Pc-A@!Q#M0A?6OxN|Y!aj&;1JTB(2n9XC+Y<4;Y3 zH^w3HDX?=w$Fm}^xHy#bt|C|2i5rI}&AWU%M=ly)7wCR#Y;MT6XW{0_I+5BvwrcPi9jB_z!LrD#mC{T7W;zQ|CrMrmD#49J7-Ye(u7?|7FQEX3 zL|zzn9n(s2gF4{Fpex{}W6)mMlfj_F@K+5ZByl3wF{mU-4B`%lGej7;$kUwErS3i$ z7&JUCfBzhICQZykul&5K4$@nj+_ za@#g|kjJGBG%`PTZu0${rFJ5_Sj2wLy0p-)iCuv@?5B#e(gNzNG{2SJbwxC=oM#yE z{GuG}#rj?(uRX65qiEPK@krOVa#Om2P>cL96FSfD{9f4Ce{|-%ss-e?e%~{;`Q0Q& z=G94Rx0oxPl?^8zi=^Mfv>n8b&#A&7VhgiWN-y<0QNM?y=(>Jwggpc!B-r8|Wn=q+ zWt(`T_j|mfYrvIFP;9DN7-bwo$VK;?pgyz6;Y%? z4$}q|hRoz?_@Isl83-SWLvkR|z|qgW*-K`Zt1qPJk_?NGG9h z;^Jca5C@*&aQ#ozmtON?F6vyfpKujb>Dkr zagX(=kofcB&urXC27iJmx5?lSXQq?EpSmRRCl~SiTgD&iiHy56;!ueAc8fYB;=}MK zsTsZEP;t_yxmG5?A7amzwB}t!M2-WQmfy;^mPG^Cen;U>YRVZvl@#EMf66?#=39T- z|4?UUyS<9QEWWVw3!TzVG0!)q{&&}u&avf2KH4qgHieIGKDM)hby_+L4tVk60r=7NTl{(Pf~%2|!HbATo?YxdxO+n&NxaBS5-(o* z8*i^r4`O%`KP%YCiEGfY+bi4$cHsWZ@tlYlWq_WQM!rSZ<6ZWB#?4HaW6ia&teo&V zUtbN>$jxv6_Uru+(v3Q!_dA%DLZY8+ALwHhZ#(+Qc0K*ja4dvl8lr=^RIAm3yl_b5 z5f^lMQB5A>BJ#YefogD1#}5h1J3Gp@OERm0xI;!a{0=n!%Kiz{N=U*LyKvooFvdO@ zuNc{@fv5*Iee~5q%wy`m-sYj(1V=KNDhKS(P~G+Z42wSZNZ}37#?Oo!ckp0YNWAOw zoSDvcs%lPmF#9|_(F5f6c{tzG{M0b(=bb~^f89By{MtNU_ZXbVd~+whtHyf8YsOXO z@vD|pYm&PMG`KIVGqjTtg9k^a)vi^G zC6U1eKfHLPb`iyWFCJCEP1nf|*!irG$SZ?`jz`j8p*$UrE{7dZ&@9hy$3-%D)D3?t z*mwYR1JGSk72BbRPdt z^t_Kd)-kw?Oirhl|E2mBH@J`6j!OO;;lOSpI}j&%1E)s|s8*~FBJ(TA;Qqz<@!7pk$|HenG3<-jBy zYi(Z9a&0ntUy}T3Riz2^K7`Y%-sv3H{#fVsaF%mc)e!frD$Ee8v#QQ$H@YWU#=-D`A)xAhvv@W@?9 z%))2Rgd`9I5(0)SNFabq!do;;vbh35L7*)vm4pB$l}E}$86E$}17=Pecp#(W0W=SZz_^Z>k}SM05kIMCq^mzh~~u?%g$3+8?$3 z{3e+__srwW`^?O_=gvUtnxu@aXr|rIpfZbUP$$ssS~!`bv*og~f$l8zisG&p=!~i^ z+=xRbK_#f`oBF6qEroJaX76da>VvMSUXRL#W|h6zZ+2x*>&5RVKBZO3RlI4H2KVgB zUe>O+OZmA_CtIvRtI>)RI^0#(U~gmZY-4?7KZBWx$^8cfgk!d`}s zt*5Jh-Ujm@y{+D?EJ>W6evk3QCrD2RA zpfto+4ncomtKb4}beWp23?_>*9^85OSQMQtsI9^p&^fm&LdW9toQ;cW^_S9&+40b8 zd9mX~(FCg?=(>(2DtF0UVvGC93{swDT8;vsiaP*;FS$tePF7kQqi$S~gl(B4A@JWx7wKmkY zBf+t!xV4SO2CaW-?xtL~>2kd`v~QQWohZhEqGQ*&Zc_hZXTiWdJawCOZ`;?)*1ofe zk7Jwl$u^?@a1{M(cD-|~Z_r>gwtQYbaOAWjxg~$K=6(Le4tLS`@?iO#uAv#L%5k>h zs_L|Q>#5?zmb@8<`>s1{oO_^S(M8&+a~F+eBj@>*OY_d$yFp5$5;ncC-THM}amhSy+N2@$3CpQ(eP3w+%{f7Cba zTQFU7qpxdnz!c8SApBA|EH}7`4M%=thQgwWzBOETdpHl`NhABF3l94HJq>)a38`T7B@o?Z|*^(kp2J?hAMdItp|0vG~edQ0$3^khAyBa#!i zG?HEw9Q5I4Ae{80u=1JoLMR-`OvubaxD5WJ{ZKga|CNB6D+JsKceg|UCB0wb8D3#? z5X!WaKPm_DY6?fi|1~VywgP~gE=1C|F{Mc+c5gcZd#B%NUi?>vBPi>HJYI$%x)=@= zpZE=>OL?HY$v%ZgHW-c%(1S3Np2Q{8yI%-d7u7|?L{1O#z>!W5qWw1UM$O3D)v)eP z4G#%?c^cOIUlA^(*U0VMp^82m1QQ%m+F=_^<(=gpdMGQ!kxu22*= z?}lX~DoHT`pgFo~F|@hD)U+dmzUe5U)hm|9=%z<;{XWQ>9fKv4V1_nc?LerXkpB8M z0e1-4Bp~rf@_$yq=LI|<;L8FY6!4IMegWSW@UVbK1Z)+sO~B&t7l0{&G% zYB0(d>Glw`378;YvVgq>>?a_dHbLPt1f=f-38(ir1V;!+YZSuA2slANx{d3 zXTqlnI77f$0+OyG`P2791m_D_EZ`ym%LJs`3MpKLfU5VB2>7^w+XUPpV3UAP3;3*n&kJ}!z?TI)DBvLh{Q|x%;9&ue2-qrMn}Ej! z{6xT@fFS|91pKRjV1&G$Oaj^jOb{?xz}^D(6EI!C3;_oVm?hu{0i6Pl5paTllLd4M z=oWCQfHMS~CE#2E=LtApz+wRx30NlJQUNOjTrFUwfOiP!5pbP=cMJG5Af0?g6Cs^6 zl}QlqMEMC|fW-F=gBkmg@Td1dbn@0y0)I_F(($4A29xHWNf7vCfnP1~B?OV)g96_r z@Gk_Ohy@e*-$4-R&~2eaho9_){Jcmw;GcwlQ1~ZezM*iV1iX$Q!c_tq(m+o@kAU}) zKj_oVrWEgxfS(9=ny=`Vlq>;z6Cc3|Wc>&t%`pO>KoARwxdNX@5aThdufMXij6PQW zcHNcpmlO}U^%dfoo9qY+aU1?jE3vxxuziWTtL|sx7p(}AieTC{*8gzAT zM&Os$pwhG&webic3Z$x$C8n$k#mv3hbi#)7Xuh#uud(u>uTyAOVPdRq7T z`g;2S!YzQ6MusB@HWD#N_W&>qzrXu#`2fOYAdEDUp2Q{8yI+X)Hsvc~{&~H)!64F| zUL38!_^{W#TjE_C?$pD3BOdXl48Vbagm?S?dDUW4oxPxEo`jGVOcd`hsJLXE-s#|$ zVz92LcgTcGL;dJqF4xfO&7%AlkRAL->8a`KRgT{gs9!xlAU#qV|FQgF3f%N#!Ua47 zRvJk!_S^y*Z^;N0%MW7DEht8q^Wg^%AlwbG(#Sj!)boS4fgFI_xAB7qkiSex3{cY3 zIq^rm`-R{KR38!Z&!1C3bci2xcTNEfWgR=9p1pvCbgNg~1g%(&KX=Cq@a}os*ni-3 ztsI2cf`9vWe{^#@Oqdt+K+hOCy>n{t>nX_7AXcz`hRqD(vrJUx9ro&^pGT4w{z1S2@oI zcuDZH8l7W4EbRwoz|ubA04(iW?t`5Sn+4ksHUZWIOMAz|u!mp|z&;K8IBYHKI@mj4 zi(%)&PKBlUJsq|;ER9d<>{CmY-v~`-+yE|aXovGPxW1XZ<&Dzi%hBL#w5zJ;;wJ9J zmoCHw(Kl7Bz$w5Pt5=pFI-53gu6$&LS4E!Hr7Li=G44LrLNBf?T?~=I3a-CYRF12* z7h#=%OMbN*C~+I`;v4B|XYDrRB_+5Q8vZ5Gx5n#l+McqsWF;<>=SL3DrQ6qWi#yT$ z9~B}=);M!3=KzsTwuip~n?YIwSmUEDGq zj<LxV$JGd{Py|^T-IJr*NemapnN$lV8^ZUs8gN?T(gObyS1x_we&JZBi#48 zaVObj!L0A`OSW+#^)g(bO?9<+5eV^H(pQz=hO5h?JrGCUx=kYTm55RyuB^w+(M!s4 zu{AE8j`G1xc2arfI+$ddSA)Ib8oUvU0s4S#=5=sLa&2Xs(AyAZ&>4C1FgfSK13`LoRCi=S-8Wk|)4N zUv2mlXxP!fR4zL8`+0&`TpSSaWdRQgNb?r?`vrVkK$_FY{fL0A0=5ZwT)!2;4eO#UMTq<%^G7y*f28WJNi zm#|D_RmJ(81u2(88Q;DZqCCKa*FvO^Uje<`$D0!?&Fa<7Pv_f(X09cynVXeX0j*o@ z%<_{hXP|}qMS#YYp66!}RbglxhtFfW=HKu=G3xFA!hUK5>XDiYtc)9~SF+N`QB3Eg`7H7OBu7)&~?j9^ny*HnASgbwX%KKq*m+`>!g(Ke@ zpeloZ*I`VQew}|r4BLxctktc>8ef{)fLPYV#CHdFnOZ4csIcF=6z}&PMw|2v9#+Oz zq~Dc4ct7HLCg5J{U{!*jQXi$RR@b->1mXy@U8=g(LigK&)rDriGUl0pyU+x9C_waf z@!#JCNcVQ9#! z)PG;Tt7}jOo#b?;#n|9fN4xWd?08v=t@B(i^PcWkttwuJTBXia=c$cqT!-B{DUA)v za%(bXS8#`i?sNT>rz6$$Bxp{a-Q{o=H4kn!LK9MX>%|VcvBAv-Pf-7YoI6z9T6e{S z{RQf(!j!j+9dU*}sGV)|*A)(TTRM!2#XpixnfgPoE+uJQ;ZSH=uEO1??n2h!3Et&l zKBYbmT6D(BZS!mLhr55$qWCNwrg#gT{(cg1dfZuPYAI2#FH}0uO%AmvWA4lU{$b<8 z6VzY0U+%D*wge7#Du#{jUk46$n2ZI5ln*5r zJ%QJG{^@yVV2b*)fC2i>ENHBv_TPwJw7#i8eHQoBUF2VY`f{H1lj7DP+`ki(=tg*oZeeuz5c~|T_-k%iorz+5A z-g)X%>ZsHl)bRw-lYY~}Mm_KUZDEm0?ecJbuXnFYP3tlyKRdrFf0Emd5l6iPrAb14 zU3_;w^^S-0zc{S;4i=`Wu2VIh6a84dvGQ5;jY;m?TbR$@5vTQyHxT1w2z^7*`i3*q z64$B3Z7BTFVWZEf4uBS>Dek{{@3_c4z)k(YsqPlN1pOn2a%AZ+#3{M+RHOHG>M8b( zs=dQx9vp>fd%tV%u%U0**uMGo$d9GNrhtY&llu2($WPLph3TRM zdvWt%Pd{>N@S%6?L+_Y`-f?|5y~EmJXIf2DPp)$}LI;0e!05|T8{PjMh_7_)#huS; zZJ;u>cYtMl{kx!a&hoS$T4ToQ#OdeAE->tFZSwvTP^l)lVf+c?xOx9ja+w;PA1Lsa((s*o~a*6Bg0LDgMQsbw;W}_jrM@F znxJqt*qdPW^k|(#{Yx52??yQ2>Cx?DPPh?0{T}-c;JWPa+oWi(B#oq32?ssBPjvLi zUFL5Cp7ra(BjWwAq$ksgT^A;!f*NEXKpBppu6WFZ#9VO1R_O2U+1vZ*s>{%(}QQy=M0UoASkm7kAFYe~)MTZq~r7LVup#WFO- z%a;fs;nQF#{R~t(>2uA(vot&%+QVb%$=9jhzz(`&0;ImRcp0f=5x|Q-jSd0A7}v2v z$DD!0>_})eL3EPqkQsvW35USpPJ*Ze($6H_h{p*c{O<@N+}$F4Z{YgrGY+CJx{&YO%ZJK<=5v$1pSHBhwr+||>d#;ezSk{nN=Dqf(c3Vd5e1Zj=)Xj78P z234zR8(9V$^v1^~CG{a=-DPUJignaYBS*1QCp{k=?-LxwI%59bWAZQ7r#t+;nAlnv zEb7^xnbC*Y-$rYMf@bEhc#Xb`i!HvC=D1E)(4bEHB>CQp`FCpMSDK#cT~f(LwfUW+ z(p47R>R}Gs19tBdolYYt#K&d-5bLM;YU*Lzh=cp%JMN7)cdR$i9ov?Ud_$`D<^7h9 zA`3#t53D@A|FKS|8PA3|e&_bFcW0?qe#^WcD?f32H~&7*>N8*k*N?Bu@aE0aFDWe_Gv(;VCQiqrZcux)DyXUQK&rQYpx<6Qk9SYCtYahaywJ?usgF(% zFo$!L#Y?NK(#m;6y`~bszo=2hq&{#-rE}C*em3euzrt(yssNSmYJcjZx1$YyTA4kH z1;1a79umBY)20@P%g#~JW2!*4B^5U@r+No+Dmm)tNw(p6Uo6|5>a%)N)$7tz>nQxy zmH1WSh9w+Ua#HJzxJ%oDJGJ`=*R2R~>RoHY>@?eOcKZ5t?k_H0=*{1@KSe#*$qaK` z1#Zd_-7tM`0HsTyogT|_1$$Ogne#$_+*PIiS71eu6_{}&^toJkE~v2$ zl>vP#r~1Tzy!aPwY*~E=JK}8hZrVGzPH(O07fe#@{(Wfk-$u0;weW;slEoEFu4WFq zmu<2&WU57~maimyZN`EHHP%KPmOLCcp%}OAk5?1DnI}G6W!)I>y;n_oc$QkC^-=0hVW3R97 zkD5Dh>YOLBF@Ce5!x(38On=0emg`;-T8n$Tf7dzA;yLxM=dHAhhdWGU=^zCWB7Ntw${aZ_Q zI&yKXn$}49F!6j$flFEg&*uYdl%ghpb+|RY##*nr zd=K0<`O{?kFqLJ_40;MEhb-%R7$q$DfalSZdAHwxGU4|8t8gc{hYkLq%eK)~WIGWT z*HFlUPV~x}=DnS7ujq03=*J1lxUGNunDH@7eYUL1-1(={S38VmYA2$bq0advIeQq- z3GsxZAKUnMThwC`RJ+fycX*M*MU<}y*VZh-H>f^|2KX7TwGMnelz=gy*hWIKO1V$x zv&I|9NBdp{d^WkZr}yZ`$%T~j#{%(dpg0J7)X6c<8y06 z_wMu`+lDHQeRuY* z=eMU*jCZ4lxPpK7XgPb4=Zxy)>6!yYnj4jc@=7`FQ`;9g?Nc~2;8I@(|JC?+%He|a zKG=i1f~%_gsi{8VFgH{N!50+UKJcsGRPH)P9I%UA5(m?BT*I;7aQ?A>$FwVkjLQ3B z-wyhw`I6u(nBO-b^Ll%KH*R|W3;Fy_>Hqrk#~l{qZ@%l)+3J!avzIuN#zA)-Q!vuntL|1GJ^B6H+2HH0q8`7Y zeetNg(B(U+Ru3UJO5&O}>f=P6M&_$kvIW^FS8#I``B7W;uDu9t*}Krwp4u>NY8>t4 z^R{+QF{O^E-=C4|&0ibp+z!c4HXGjAQiN74s?5Ut6jzhS^JMa-A4_e#9PzOG*TuUR z@!p|${n@b2mejh7)Un-!aRnc*mSKp?j}$adwJD=r!PoG4VHUY$n(An#$aK60*^VMO z$k)eN5+7%Byv=B{G%9sz+nINkn)<80)BA6y@+Swa7Bjw>owUP(T9{L%jA4${2dGz4 zy;;1Y+t~i-aYSRO6?V%V=gxgbV~FdNVRe6w#+J4lpmC*{ZM=1f`!{`hr9JrRjdn`) z>wLr%Zgpzy{ymq6L+sW%A)1lP})yKIr zhxef^H%wDqoZnD-#H(EDG>+41SVYpH4B&-|N-!yu8rkJE>;V>gQl2Pg8%U z^E=f-F8AtO@IoPF#_uIX_k5bs5UTydG#aNkn;zp~{|0l_VFST^qET@jxeMH0COd)?8UQyeR zUYzYZeWHqGj>$IFxlW&~ni-srkwl@OW+k|IUMORS)=y-co;x#jA66};=gvH_&+IdH z&RuPOV9+sZmZ+T*_R@AG`(bx)|5Uf3^@psgFxgM?w>U_cZP{3j7(+*C9eRYXfM=d4ia!~cs@k%! zUWxn3kyIb$=h2hn_-r+{9i?#8g9on-U9?Nfe_FjP!TR>J#!1cT+r|!}e92k3zs~}G zId8l2*lh62O$m(s1op?Ui(v!U`w>p=8DdnOJ2Pcpy3gbt;4@=|ec8SNjp+@hjmA^C z1(_jFuly6nIplunKISlcO?Vo;JUHG2cG)WuZf~SHe}ji=B_HcGf|M`2Z(nm|Q3^O_FZ7OH z4mlENRFFSfbuXQy=v~iwP+mX`vKoW`quU_B$i zkuqlmuVZa2gZ_qJ1$tqHzBZJ&Ys0ZePhN?>(C2myCft5?o5Fd?xiil^r_amU&~3XZ zhigMO?>-bTH4Z#sNLuf|IdBtr^9?ko#vf{0(s?P8HnC;Q5Hx&gf0wfmAHjFwRDPDfFS%ZT#OjAWwG zw?V~xelE8okh*Q)G;L*TMjD^(7=Ts&xq^aFtI_PGes}JS^|=((2GwBRnKirjbk1L! zcV_tRJKGUI$AFYfjcG1Z-9_ygmr0j+m)YB+U0ctiU+vepY%BUz5*}yaRcCOm#+Ml* zz8!mRuI-tmqLC*J_l8f?J=gT9>z?4J#rIGhxtg!}q#s}Dz3_?QUWQer?FD*z;keBO zf9MZWdg##XO{|$-hfoZn32sOh5$m>m31j8U%U9nDzY@InBlG-*!w)_6*29x?|7+Vj zjxVN7y!^jH?*B>pWzOb@?)!u7x$B1%tk|(A%Tm@8!!+tWdp{mq`yoAe{rQ?Bbbd2X z4c*GKrzCDs40E^`nrKS{F-z1tV>fV|qgBHt*~#WvCi6AM*>=k;%QcC%g7|#xA^**n zNLKe9>PoL!TA`CUYl@|dpja9uhlZFZ)?o=8v~RwbRFsbzo0B_6@36dNIo!rO!)}mV zY2Sd0@5IZO-@1D7@>Lqu3nJbAPtqTAp$(Nx|5u!(NB|WKUCg~jnElO7!3P)xpte#$1MkIff zrlhwB&-(lw20b_2q>=QB;h?8y8>H#CQT|9SE9w0h&qPnkt<#Y?3L}lAR}BY!IOjKn zBUvYf%Mk?J2p3yk^8cj>C)1sWKv^OV0a?$_iEz@(gK&>a1W@Mh*Lc>K*ExtW7u={U zl)fzQ@A0gc`45I1b`0F4p}diSGldJAd2sl17}Lr~D2110AbbnHJuAk01OQChTDp`z zE+|XKlzYZt=so{x0^IxRH$^U>3C;A~B zPX1Zp@gB|?T&ewRG4)~N^%0I9?zKEP!rNoQ+j)4G=8a!UJ!0sac1k~D5_mr%ocgiC zwLc@iM!X@54&Nhu)~*&lS}T*jk&g~fvt7g(afV&Ae-acFG(%%k5&qPlHIvLsKy$NZ zV(TjslKhRJo-0BUAYT_f2t&9k5kSI;e@a7mu|xm~UlxPYJ3?v5e}hB-39paA|0@Q6 zCI){o27faKKMI`2DAhqP^yff~|K~CIUt@6W>B5Hc*E0t18-rgQgI^MZ3w=mVlj!Bd z_+K7_PmRH6#^Cc}@ZuQ!#u$7>3|<+7(>pI|D1Y7<{9)kaM1H+6p0>vL?~cLuiSTY7 z-p*c(@%P8z^b(I=oAGyot7!R!w|(I?6duBBCwvN_Es_>2;P-7VShQ>n9lbztq|=)6 zoJC<|QOP15vZ(y#h!5T+F8*-@UA1Om1c4tE4GcY)Z51YVS%>@gVRjgcGx_~bM@ikKpa+6=O6jAsKPh1SLV8J4C zTu{z`D^}bx7GydD@ok~@W#cf%NAFX zJ5O_A`Hdpk(iIiAE-YWY3SJ0+Y8Oqz^h(v?YROrmc~c5YDoU4@;Ioq@w=QCcw**bk zIivkjZQWtV#M=k$ZlBEf`40qXoY5rU(klT8rr7R+T7 zKY<|P)7)mjBGE%Q{2w9cVvK)JKZUUqgy%zQMz8?u7%V*O=$t<#Scq?v2!hFNA$TR` zHiA>}PFVOK5qL;I3)T|$Y0$+cI2~&Wf<@R15gd!}oCItni1I%{5c%TY-J=|D5{`8E zclUt*PvGqW{!N502J5DB)dSkcG4>=u(4o1Q-a)4em?7X`0kZ@gA)r&hF#=8yaI%0d z0o?*l6>x@tvjm(g;5-563s@}RA_2<;q%+1SpA`bG7O+ylI|TFyNZ(0N_`3zXPrzCM z9}uu!z=s9gBH-f!ZWC~afUSU3Zzj+txRBs@yt5~W{x%M475kNpT_K<<;MD?tU%;gV zXW*MQK*JF1uLV3H;6Z{HAhrLe1d;An1kwIiV~JshBEf8ekRseb5DVT) zf@tRl1bl)Z4jy`wU=I2%^bCm3bb^?)9~AgD0Y_ocW4{{ZA&BzOnv3dlhJdpKoGaiw z0p|-?Ea20Cl-?(VqyGg74#l1ZOBd3am_ZQbC?kmcyhd;;V{Z|hj_f-{k?B+$#$_=DjZZC^1En>TnfJ0OmjVD`D%cmDR-+Iob-p(@zG?`i8U!-&YY z3}`||IFjP!Ef)A9f~i7B1OBTCPmj{opd-n@^_%ej{e4PlWr|~d4wvd652(&4c?;pv z&>Z_6$~yQ*vlme0@Nd(nqdtJ?0joXDP+y?Blm@Ju8+3!HJ?S^yr-W&P)6-&U`}qus z07`oFT?B@8*w7q9>0-$8yihm{L3TAPyea^=p}t9Zl!o$7rY9`Ig$=EZ&*!`F!v@A$ z5f-d~TS}MmL3z{DdltwjxJe_^mAHg@_kYzMH`4E8zkiUesO6@+yQHaXlt+TyeJ2j~ z5;hb@TdCZn|2_hri(}!!muK|dxPFNvcoX;;wcR(|r!+wvOn!d%Ddn91nKZRp<%jjX z=v(sO(;0iL(D>>Ltt_SWiTpl(d@EJNMts@wY4a60tENwvay@HZ)!ZAp>D%+aYWX2F zsV=MNQ*41Q5#9S*+B`x1e}VDp@xUncbRfBmW&OFuq6Pzfia!nXMJQv%iGV`yvAQ|8 zVsN-78KZt1mIvRZ++f!(hMhwFF4CS_-~X5MF|IPKYr+@_Eww6lx**cj|14c$Y6od( ztdp4nOI=5f9^xI;f2EP(VtE#=dnp{XA(oz;w-G)UR_ls*fY|~&l^%qV^kxCq^T2KJ z$bcKs!!jUDuLRF}9(Wx1`S3vc=JCe}D~-$(L9o5BsR!{^VAK!EQvPV{$MV2Rcw7Q^ zX(T;~OQ?6h5Ij&nJ|Z)SmKy2uM*Eu~+0pW^g`k>@nC`x(B{>o0c@eDqo|bUx551^m zC9ex}LEYGqeh5o-8s>SJ$oi2RqGQX&zbSPQM0RvKuS?Hs9W{3Rd7r02XS2bCd0--X z6X~nEXVj>P>f2pt=+;ZrF)H}o^@%w2-c`wh=(E9dHkNg&W#q^rfA&bz{xy|Pr}uA8 z&Mx*hs>W95$hm&Iqmh5l(;Ir3%(ViR4Q)F6)tAq!_Oq!hq1Ac$_WabNKTS9L4;2nR zJjic9n=oG)DpIlBT-hgRO8TUwPta(w_?1x!`^R7MgG+Yy-=2T$$nEKU{LoEc_np9s z)jhr0+FUZQXEA+sv_Aj+qj;w{{(ZV3;^$ANuc;)hq^AO;8#ptVX^iCMb-WK|!#`}H zaE?l2@B`z#>^Q#-d44?L9Qkld21@w>o0s)a3$#k@i!0}-hA|HXsG@N1&5Ryu3hwP3 zu4a@upZ}({=3oje42`R9-`~NX+FTlX7Wds;`O0^3?^XERB5ihFD*3oPe3{PMynu`y zV*e<jFLElSGerg`|hA7N-ZmO&RFXoFI*)hpkx@JsXH* zz>Vlpz9hYcc-Hg(=Rr?jhd{ZBT>}T zdk+dr$x$Dp`GNM?(vV*kEcsKPA-Oq37h%KG;d8{&$n2rvw02%ly870N#S1D{uUxP| zn`R)EEnil#W+it7O%OIghcVderxbo}Smu1g_^z z^MIcZZ@LfR7Qjj)^F&b3n+^dv05@6_%d${DC~rtNZ0-Y+5yqm+sB?}g`-R|5l&^^S z=g)DZdMDljv0K>ac!zk&gZDeKYje1WhwbjnHvRagMdr7S|IyB|Ip=$38=bWR6E*(N zcO6CiN*a3p_pFb!O1zMZq5mZQps!;&o@4pLUv=Y|!jSEbKg@tT#g#_Vi{%dq@Hij- zPzgfk!yk4a-1+c_Prx5q5thawS;}8`{NWJF>x7>)lHW*NLcROHia*fYt(kwGUr-x& z$1es;(ttYt5m|i5t}nI-v`5e{IQY5(3qgt--phj7QhKz`xHM;+Q!tA2li!WaJ@36M z$zoxm_zLY^D`wo)SnF{0B9$b0IQhVMJ$8IHqcMnuM>h7bBUrG` zlZ~$i=T_dQ+V*cs--rF;kNx|g!OVh>d2Ue8^nIROuopZx0Xx}gq-&g`UZ%d$m2d#- zm~$@GfG;_7gf2ezyNRTWi#xy$9PP4s`nNhKZ!H{o^fx#wA;sU2Z`)s+Kl_jO0#@hG z@Egur|7JOB{PeN27RM@guhfE$wpH|9hsbMOLzhyUioNiWmee4=62n)IN>T#$)Z^o3 z27eIuYKO_RwXo#~(H`S3R)5>~NGG$DbWE|XblvXih1` zD82#3R{o`@bHq@;{Sr2GX3!o_WxOBfw(zecrrn1#Pnu{qeZ}4Yk8}A)flcXiX-A!~ zJV0SnsXm;jk16KHOh-zw0)6FZ{w70@e2aZ5f*A?L5JQ;Y4E3 zAEecH#B}$LCne&|>w7S8B1dgbbH+F9Pcaolwx~i+Xw6dS{w#yewr)g3Z(2dO0+!Aa z|EYkKcLNH==MvrAp<9!#Ij=S8*oo)8CZ)S4V8U~UlzXZ(l7!TAs5)6nJt2>@1Z@@z zNj*oA)bkoH_54ZY^Xb<^>Ull5=DCS`&z}C$csB0riWBkijj9z=&;m$7Kj=DC+lVjq z%<*jK^XmUb?#V9g`F{6u&mR`*<(`=iV=-~&lY!^cf5Ii8I|5S1nZjk9GlSOn6~W?Z z&p_5`M&6TvRZMHd$xN4^oF7=`jS7Y3p5$v7L;jC&`Da5zL+bgi-Kif*lZ7_!mR}

>{Xc2lPi-QNQCprvm| zNpA|m>v=lKEQzNRJ&G&o(HSth?C>+O=fX`INsn}5_4N9INCw=99_35YTZCsU;fd97 zLpudZFLx=ij>>9TKZsFmD=NYgRR~k9upyn6Fzv#OuNl(uYXCa)Pe^mlMAO5ui z;fi6Uk$EDh=U@Mb90V$bVI%2<9mIp){X+1sgs23x`z0g%NW(dw;Nhs|BBr}Fu6$>& z@f#D@pOZ0&4!uj1hSL>nCBlHDgIL;P6vT)^wDs%Xmxbg`{6~1p*fA5d;NQ+$=zKYt z@OqZsv5+ieC1fFWI9b(H+n{n;h$kWovFT+YOv*wUge=5ZOR^9;(`5iZYYFESd9H>m zWI7}tw7!HLP129)s=1bJjCRB6CI<|4#VTvCw>n3x_M08oOf%qog9fLNHb8ozNlD)L znB6!45|UpOUdkmT7YPZ;R3Ram;#VFqoVEOoJ@QRb5|kq0;V$JsI;14;wWJ4)33mVU zQc8kTgMN^32vU+?6#fBH5|%XRePctSdUO8F6MwnIrdFS@7$&MWc3f$_-R0?b?Ud&b z!pvnQ@qXoUd^J8xlam-8c{=|&E)97l@I&$yIp6KT;$Pzk6c6>Di>@C{U4?KO7$&`-cl zZqi74`EbzF`|CHzMQClTpEG8F-ucWK9)v5Ei2}+z5rkLRyo?OB0{b?($m7T#&2!R7 zdJ>mV?|vcX4AN_l7!%j=^@kJD@PA~^h|D+I96bcYi5#^#t!YO`6615Y_O6Zh_Q`ih!IjFsMI=hJalLFcI~ z&7H2!t~3OV2E%aM{;i!Eri2PQO^9U&Tb$5;r7DT#Px^J06aM@Tnf1!-?^eeN^Ec}2 z!tLb$eR`@?hty1R)k9;P+@z6wBbE=*J3QLC#qyykaMPMyqp%2o;z}dw#p<(~;6dYw z=;_z4u{!v*@IN0u^fJQT04t5m6G1&6GNBxPxP2QRdK=+r%t|BaNnAp``-R{`R38ze z=^sVv^Pktjr#2?O(>Fpq%y)CxL{#GyPG68?^ywQ|YIW#{qkf1*?`J&!v| zCTo=&<|lMViSy};)Z3a9Doqv2=z{be%?7uLP9!Tb!rsyB&EML=%wM#`R~9udOH)Rd z^@HDKEc+|YUxuhzD)AWMzuMdOkySD-DJ}HzeQEkD=JTstiZpmFd?p2QWT~e~=rN4CvV!e<}imR|Nn!JMeox z{G%1&uIDkdADJhDdj1gt(gZger;-=Sd?4Mhc^rsdzedsv2M`Z>_Y1*4h_6LV>^py| zsfZzccD*5ebt!wJwjzE(>k>Y+bqs=cQTWpuhxGqwju!9h$NnRG)Ul(-IL~*FdWZJn zD$EOdVhc!nRBzc^I0v|SO9`aiZtDUABzvWm#pu z{s0b zG7Ew(e#X}JD#Xutwab)Y)XrF@XQn+<9c)zZ*|4*zm*pPS;x*M8--$1$Gt!dQGe?ik z3Y*>A)0^xydf(`p>~X6Nq`eN`>Y5?=U0X9R}z(VHEa;}nK@H9nbbRO))Dbb=jL zcZPYx*{M6LKRDhi*s82EtTP>0vsLsdu4grgMFX zr}1c1N-}(bGE}%C?SYzBqztz?GP>nM?&c}i+)yidQYMl2) z+^OMo80rve^2m=UXDPu9oSJw;H+f@@CY&P3aIzX!I$mn+@c~OCVwA;s*`PiHltyYN zLmjo==^E0zIB@D%P2A=*%#DnnA4q3`8rBu`H{kp>%Y&P{#y2V6Qy&sVq{%5xReJ<1 z^{m0X3As}5@0#GObW8~v6jRRqT@#(p6xqF&GPcoD2h9ved4TyS#myGhxweM+4g)>_ zcrEI-w#L$!QfA7r)Vip7UX|RqS6tvQb%?{gW%f>$H#W-Vj70zKkaOx72(BS1|aAb>mxW8+vGetG!DwnW9 z7H_ZZygnX8?Kl)K^Q8n0Mk`>y{f2QV!F5KP*A*OBW%h0E&qlgVkFH7{*|QG+3Bik+nBD_lIiw3hBkbNmwDrqCH?1D(ODuTAL+!wPPH+$d>J2TFVQ@Uo>#cy!+eG;qEqR~U z?P9+7(GI_?MmwmcoPlM$Zx8)BuW=<@<9&F$pjC#g4fWiWF(|Qpa#W6f{Wfd-6WaB* zYSw6J=oNG&+0lZ}RGV@V@1|a`8-2jMNv2GFcWvmgU97Pe+Se6yRa32_eS?=(TN+Xz zX_WDbqH;{_ zfK$K8C2siV?>=>mdXpzywr$6#&rMac2W>rOX}qW`MP(z6ohJ01%d0J-w?BA{?Weg; z8j3MI8)tdqTc(xO8s#drem~1#r%I|RRo3BQh7K2#sk%K?FL87G3pcOvCh(FB}WP1m~)nz*s z(^nfk6jJM_A0N3~9j_{n3@wiCrC)h$V+{3iJ_pt^H_s*FB!~xMZcTHLL3diF%JrtAH7{oo@j!+JSx?F}@7qB#No&)a3hW5m% z(0#xKOu58OEM7MJGL`0%{a?JdgXWT%!IAMd=abYQ7nl2nPdAbjmCzQvOn~-fx}HyEp;#PlZ40ZlXI)$gvKV$YhJK#S-!

0(6fVA(n zz>=8&g!+Uul3qR>^z=r6-a)t#J&G&oU596)C*=f(un8xbfHaccayU>psjqSb;iCGo z@c)T`l3oG^KzH;uiEseiq$3>3Po$CQZiIur93hk=18!6fk{8HwJcehz?BoH^J0ID} zL4aiyU$lF`=*;e%0#Stt~hh2&C{EGH2-v^l5iR$_Df@S>3KX7Ea>6^qwKnYnZN8f#OwMxv)&ROv!N+lS}e532NL;<;{p; zY{*yqw4VFurqW_8tV&awx8CF^PJUtQhRpKJVlI=(+*-Ae>ysqo&Nz|>HmWsEhO_oB zmAZt7Ne3qja?wQfDw2)b5?hH{X4%VKCeL;5%;E{^AoT|K>m6n@xj(!2?JiT(pt2tp zI@Rmcj}H&$rCV6$D4X3s+dT{UbrfrI$Em6Y72hkkF$((Y!H7IELEW(7{igd(X0PS# z(&bY^>>5Xi&G|)D>5{%GbKrEO{*Y682dFmh2VKYa^w{W8C+>M4>(GLJ;jgRWQudUV z^=NgJ!96*x((YDrXIJ*LCcJ~Z6weu`j74o^e|E%$-1F6L*2n%y*l7^$9vj)PKeyQG zujf0iA=vlb<(X6YntE$G?oB&2z3PMGDZyLWROQ0_{WMIeKu2+s^7X&&(i^9XL;j;V zJ~GC2sxpkbWW>0qDZPYC55>%%{s+1Fh`rBF^IZJ~zjgd+m_ofwtC1wNv-oSs?Z zC_{aXNUhw6`x|cDjUJe*OrjQ6#!gb_1vVC0yms8+fZeWYbSx}m!?TX2VrSzD{@O#W zHK>fW4l1@+8r;h0*_FK@e|pjb8k5*?bEjfnSRCZ7W5lfve>+#dSBqivwFih2(VPj{ z)Sq-=aOYjtn|>RlrrZ2mH)wk(xqFs5Uy3~0kSEH~GlA4#a#E7IHe}dMU%9a$tHIqL zkSCh!26!f^XWEn0X(8LK3lJw+#PJ1guUrc0NPG1(+z6MXhT7-Bm+q<1N_j8*rv**$ z2_W`0q6R3np9VlJ=!*M3dT?bRZ5x$}a4SlpI98Bvh~0XShf?C6~z|1uS`;Z-A-vGBTRF<(Ve7H-!~eS?0`R4mu`N5B*zz38M7DomFyvY z(lYD4A8B5a8dQv~;2*1~7Fck0b%SbaO>sMlanpC2HYQxbDb+M~pUS6k5`4d|f3ACB zaWleP<({P8*e+?IZ;aEZBvqw7Ij9VLBCbx2uf#pnPG$6-=F+l3#dLFxa@o~|rNym& z=xgXk-r<%(Wil+wKHfqcCohz@>nisl@hu+MIXAdJJol39`}RNCIn>A;NX5{j)0JTL zWba^93-dy6?nIqgSnw;4(RZlBp75}HF>3YsWA>5lM~8(b zl>aHPbK2-HFPdc=dFIH`z?0L+jquk3sUf!F_x_9aQjf6>0reHG;AK_ThGC)NTYEMu z6RjJSamEH^v~goe8Re&>crUMSdtDsf;w1C$Mvnr<`EbKc)=vK}j08{8cK@)TC(aj$ zZdK|dH6Ci+S$^WBnPm-XN@cuT$+^C=pEd9EuXdG|W$IctFVwk9?E+27jp zZOSX|buW$=sn~cbCv>@O0|!xZUhS~Q;cY;jvC&+2l^fKZlhn`J61VrmI}TfB9Op@> z6C>n;kP7zb9Ajsh8&y8rWb{XRl$zmfh8w`*Ax9)xp??P?B~BY|s3j`s z7Q0lF&+^C{UFip!u1pPPBpt=m8o%U2{ff01C)>ZCw%vOj?jucAjhpP7;~&CkuwyiU z8-SLF>T4Eis&eN8$L%bx5n2o#gHUqxOdG44h?R%6KCa8&T7df!DeRQ=ywJj(ENe=O zdGF=LMqdHm&?#52k(ala#y`pVeV?Oj)E`@no8uov4n1`DP(5bM#cjhvP32X*-c7k^ z*)3-8tpOUW)_OU!e(0C6sAv7fKk^urE*0lkQ7?EDeb1D1eWb*m^#OzPg_al9mvHM3 zvmf9$lIDd{c3$Ov`Iy<~Qd7&=1G%cgWvO)EmdVbt@ zFZAS&Q*CKoN;=iEOU>kE1~-{RwLPJIANZ&t&M>}58+c+;4}9%xNV4-BWkJ&RabGi+ zw9ze+pYD?_GoYC8_I-$9SQ{FO8N>jt<=8#B$kITmG=OK8plxsDt1n7N#w4j-N`Pv8 zDq85jc2EnUi!)>ufEyfwC(?k zdRYsNl)N(scIivJch_{h#abJ>Wyf#Y(es#$uf_a}N?%dug_?IIZ#Q-%Sa7GHYe zIY6r$;=!SoU$h&2i`~i<{rB2Y%MI#lfhzSN&pAE%~&seRZ5{etX?%m4f@)MoQxnM4z|Edt`(OGxWJd3?XxA6)RYmJ5}JdWWm4P4K` zcPigowPraEbT5q-??LFda`BRK{xJa8aMsSsT!qbJN%Un#wEx7$aaAc!ZP$weOI9I% zn`;4SF z1@3x!&+F(>TuE;}p7r!Fe3%DT8cA;+9Q5>F2EBf8qx@06B)tke>*-Yjp?)llq_-3f zI%jqS^n!3Bde};b>8-~z(Svw^8z)3GgT*reN$(LnQ#fhnBAj0$fHGVop7rS-!T@%` zjnbv#3Ul@yo)0cs~6OxfX6pFsXNr$C$ z;l%T%r*{Ma4#Qm;Xn)xorN1r4pK3H>NG=y0-_F0U zd?Fk~^REvVO7o|0!!)D$r|a-Uc+At`ME?mLPW~@L{-PNz{y`m1{&c>+^p{Tr=`J4f zkC+7BUkJ~HrMq~@pW06|njl7EBsbI>x?2Y#Fy4pm1|&J+FkJwmlPmmbP9eFU3s4&J zp9)LW-JktnCX3R7Lw6qjw1mf+|>J|Ls zc5yNTmu%`!6GZ$~i|H~G?fR4j%N8yuU9%FBQe0rNY$0ObLQ|iJP2awiuexPbMM)_# zCWwsZ@3LG z1M*pdz?TpN!+MM0aL8c^W`T#HpHX}lL4=!6Fq^Szf(ZW@!4cvP3(7ajYepRJ=?s!1Qw1kI}?Z@P*#DAz|U;`)eFYi0|5#MxaYd>8U%%WEA5 zQ9=J8+$fDLuw1|frgGrX)$S6vD3eVMxx1=?KXLHv5LkK?CaPNl6B<_SXGv= z3Ad=%j#3R+{YrhrXH=1-tH4HS8cU_v^E*D)*gf`@1-hD zmu!EPGc(ak+I>Ch42~OHo7A5{_iA&EwebxLbfr3fQ!^DhSo>Qy@2S1@El6DV+ret{bjSRY&t3ovry*Xzvdl$xi)G z4RjB^ncLV%7EE6k*I`zS7elWqyP(T->4w5DTg;obvmqyr-CU)z%ok@RY_>kc>L~1P zk1}pY>y%)ID7zA{){~B64{xQTiS){#nRqkw6RA8_uAj&<6L9x9gUn#2e-QLH6|TQ| z6?8F4dvi&(f<6_jHsGe-hpTZQ`B1gBC*BJ*sjgshO;4`BRsiUN_F7(zwLV2PAQj8q zM7xF8J4qYAUo$0`tjt!QYo8KyiJU#%E?eM(YHPjKnGv)yKWQ*Jt+jd$Mi=xTkvGWt zcDGQAC>x)F9FPTX<9V7}ZLja~`2)AcYTV4~8swbTW#T$F!ItUUaZ|O?mu&W$eJrfs zLp8i85U(m5-xYmf23j?xEYnLnd+0zyH_hQq@R}d&(RnwdDUg$T6|Ns?1C;uaanO(4 z?fG4Y%}n}{PkN+&WM$KE=tpL#H>j?m+f~EEMxBl%>$EY_k#q?iNzZZ8^U6?%>2xG# zMCnNO+9q`*P3lf2wa*q8C)bhABs-k~J;`OQ#23ljV@cS=pcnW$dg|@fGtoaQtEptB z94jRUCv2h?u-D~%{?lF7`Zp~G^yU*)S0QwuO19yx?d%du$DI} z+JFZCLxP*EUW2j6D+DCPSh7_aQXU%s#YEtq<)*9J}YnQnVL4{Sqc^*x3(6-hHt=1bG6ovQ0Gxlx*dy>{p|1EYHk zJDpr*@~MTS8CZaMPfCcZP{xFN&TML@qP8JHbcF!L2B!O+pJnEVqqdmZwzu+*Dt<_x@7rts#jn-8t=pPU zA^p&RKF_~|c3!U??m*Gr*R0leh+jAz#2pmeG?Bwu?VR2?g=%G)*?Ut|O{@)B5bjvJwb7*0-m?nry+`-GX_@u*RLj-x zSnHce3)!h@AzNz)9JBhOzZ}4<;P_qJ*IgCIzP6jvr>aZ+Y>@WG6>3Ythdh`K!L>Kz ze*10v(;#m(*I`LqXMKot_$+k^o7cCI&bF1lM;O}JX07LQ4{$cr+a~!PZcHyecV@;u zZKXh3jaDydNxvCW7Y}e=#WZ%dkn!aPgCdKiiwwv>5jdAYG zv-^5NhMX7r>8?nt-_ow>6dD_oi<3)O)*QdF(dC#^a_)?2AB`5~FxN7#^`VRttv6e| z37dzsS+Yql(F`{#(+6F(wXe06r*B}|IAmE9{Fd5tXU^@jZq6zr3fXFYI<0j^_%my* z-kohz`MSZ3-!^DbCTwQ4M92CN#X19hOLJWn>h0W_Pxe{sjb+Sh!dlZ>OC{U?Md(Rd zCo+Wm>^VbNgK=QHvC+GMzBlka<*iC?zZ+vT<9}(Li2uK}qd_AFmiD@|)*cH>`z2hF z$0oo|gq;GL4_g3Bb73K@3QLC4KOY(;2)7Wn6m}8pV%R0HWUzH%%VF2RE){kdAQ^~q zqGZFAo-}?4slGur>o*v0`*-MDk~H-eP5B2KPpL*J)qloKh+GRV)quuL7#j|UJ?ofJ z6y!olT>rDa2dDOu#v~rF9gUI&&h3S}I^jm!KMF(E21|WTfyGvw8x!`QF7Zr2(vvb5 z8P5F;;g%r|(WAakW*x#ku08T!nYITQg_9-=9nvikK$-3xc*YhvY-T`~nhcD}LGBce z%5gs|#0M1s+$;q>ZI7$rGObvd<`#t8EaDK5;RwpIl6yUr?eL8XmxZMQr*tVFln106 zHV2WwePJv@Pv^uRWjcgh2$?3;N5p97f<6{@(7r>T8%|X7uauRH98i3Z4yUpWhO9y} zn!i(rlmDS`zY9m?!AXWn{t;tgXf|$K_*LMqH}oBAba*R+IEfnT)U%++&|0dva40t;Rp+~?i1QGwBfc(x`$mw>V*~y*jH3I&XaC9uL-F!Up6Cb``B(G$5uPW$;bx!l;Cob%RioD4n$6PC-- z_tHg>kdbbox1^L@KeD#`jlIucp*YcFI zl4ituYfhIb{l0ul%QZ;ZG&-d?L%pW>WMEdAx75(-vKWULI`b5R!(ZB`G(&x{E6?@4 z(rUa{KN28)#(SYpxVNcFz1vi$n!Ryvzu&dUNm_*k&??;Cm5}^8aD4CLC9OipDDbT_ zc5ua5!&-5TX7HYBCtoGfmzVc=hCrudqlZ?2X4RxxAsHmCz)DC3Q-V9$&4vr}w?0g1 zs*d8T%GdwSC%qP>`%r)4?rkx?jmlFZ^;%^U_qz?h)yhicMULemM+H1re^RK$GWJXr z->v7To7B%+o>LbDegK)=wY=5}(k=d`{8YaJeNb(+tu#K@yia`JmZC}xy@`C^I|yN} zQ=j88C*!M6C6{@h!&hh2x3mzOgl?O0=+Q3bQCe-#Xpw2kWh= z7vrTWWNs&`N(TkBrlxRiw{&J3uR?p?$hACc*kXn3V&yiR zi=_W6!#f^wkNlNl#Vh|JuHW=@bxiEVii}I}n_@-WuVzo0)8Dx$+oflYXnv743AMVo z--$rqy@jA+8+wzu?VTa0pFanNSpx4233|+hARg-g#`Fl)l%c-1!!TVdFHm?UiSal`x5x5s(b%CYbG<<3<#J67!m@3 z1PEbQT80oV3M#0yr7k5b!Jr5!i(+k?RordJu!IaCRoVi95M26LRCrZepW90m`$vVE z`m!LXoj@?@X8zyrx%bT63_)U>T3%nze9rvtS?)RKp5=G8-!j#2MXUvl1Ca`;CO>FW zp!>iy@DGUpe!=Db7@OihR;Z*+YWbu}8Dx3FUS}E`d0>3Db=^}gKisDnib%qT%( zqfL*eAYOS0o#B1C-%ACZrhi0{GT=rvZ0&9M!la_!YSO;%;8wx4?>5MTQPOPw%PbCZ zXO6xsm3Tn$zf|}!zT;GZtpfBh1wC>d-WTGn8GB-EW&NqIVVkXvJ@M58)7q?+ritIx z$3u~N5Om|z>6eZ?`xRZgk2(WCu1yEkkKD~S)YhnzMSq57hi#%iZ*=(n8n-9r${Gc? z7mD|14Q4SSRyRJ2FC*RUFtp87)aZBA%7!dZKCw6Cx7hZcv{`(;j}o5_z)AF+RC}$( zceQH0>Sk4=wM8pf75_BQt!<50e3sKc2e0$p4bNoS-n&}mTQ`f*X)4#oqt<4&!l=rA zszx0r#@}Gj8*QToilQ#~JcnZ5Y)jb|?tNNSk_V}-&Amk{UoB273Z|OgQPMm$ zkvk@+jtYJo@FBkKM|%pU_Ic;lXK>DEH;s|`hlyI5P-t&%AAkM6Fkg7ZESym(slTli zbqWa|6ZAfiBKm+!P!_gVnSF8UmbSF?9(g8UOq2H-eM%uF7W?x@Dx7>P;bBj3j zw|U*91Vr&vf)_MFRrkoRdRH!J+Ia@R*s9wXbs4;*f74H3lYl` zR^PO}aGK{zcQQO2Y*HjfXS~kAYpv_YpQ(B!giSH!k zc%SS;Oi<;n1gJtrDW1HvE^;JB;Lcv+$n}QQ~2+s91PT=i_h#f2& zn?-6YZ}Xm^jdC8;(%{#i(RdF#PE6pey7$S(+3)2$_GN6Xdfr+!F_M zTt9BgjOz1kXH?8&*L3mUk@bLrb?jlft%9m|OAB{v(Y{ zZ!$cL>D_8bkMGL#ZoxD6_An#63?JI#hAl-Q(?)yUA#UXBv7iswZ zR_OqwduNEdI>fy{#Qjo;n`deULcF;v0*G9v!4v2kdNk)t`aI(2j-+@UDD-$KA#r<< zLJmi0P^OJ*in-!R5aP*$wl5>RyJrCi??8zcU{uyU^mH^C^m>v^UYtwud}}% z!d_2^a_%5Re!tZHIY#-NRt!Pr7effY4Bf2~;=TDg{GkqGFiz;7Mu_yr5~7?c;b622 zVG8C1-Cae9@{v}T^oAV!%$MscBRyf7?oKB}UUPIe=ShuzaNJkYJuq%ude`MTqTOKv z=ai%$q~W>W;p&GVCC3SwhFs5Da(j6Dh}Hc8oIdp|jk8O1S`r0?q1|^nZpFUD zilj~Ua`3R})P+fF6U&w#2PH*CTvk|__V()!C`pSG?t-Ml+tcH~y=Q(yey$;7`FBmiURAXL?6lk^IN&zDR z?vE@(#dDUyN5=igGS@N+@AGHF6a7EM|NUmO`E|>W@w5r{2MYafFk8zl-jV76A)jv6 zfr+ZcR}9HX(ucGNj~4DzS?fK({~H#db(tj2{OntnHQBuuUpXkJo-J~Mqbn?YNKjtl zLr%~qfDS4GwRYsqw$a6y?v=5b_C(11OI4?; zHIPjT%B|BTSJ==u+a9e>Bt6?U^5!dNe_XN!HRc%2uZXTm#8r)gC|OvX-7};CRqvbVe0+HX@XyRgHaDU!kTZe%R1=^-xG0G?^6t{s(?0 z=muS+8+1=A|6WDAAWV`b3a4FnWrWL^GuaRmw}mp ze1Th0&%KeeCIfRHZa$opFB?8rlv%!8j`Ci+2dx9@)^NOcGiujX?5ubi@vWc~R>Dn5 z&a$a^C(+Q#lg>qoZ}c=DN8BE2d~P}Lyfx#!FfETs=UjWuNkbc)n{fJ^`&e748}z@4 z){&cWI^|r8R!JXNi8==cAAcmgEW-P3(bf+A>wYM{)ug*t30HycT3U}Kidb(;+{v0? z-|OLbL_2-&sO-B6=)pN_ct2IdJg)V@EuY4?*y<*n_TF54;^P<-DBzN`e&F%ndB13H z-wV?}Y*YRx2~s_IifI|3xTg&}c6fzqTN?=q^zgM&rGKnR#5;TCEn?!_7&*KwGhVq$sZiCAuk*wSYRA^@Aqjf-w!08M$XSY1$o!_cuGE z3;dBqkEX8S~HGwD;Yh$A%_-W)w3;e(V42mUBh<+P`%aCHyY=m@91ydSKrZphVDN& z#D9|R@2rQM&TSDJ+gl$zWW|8u*z&+i6I*@=tEN6Z96|zT_==gQu81vH*FpxT3o9n# z@;}txg4?Y0>OTW}wzuXSir+%Y{mY7?E21#J^#HA@3u~Q-P0BFSX|vOHBGCuQ1A$pG zN6gLNLa&SRDZ_Rgz9n8s?W=muo&)7S=Vr$S&)K&NZw{;?f_?ATo%X$sYlt^?$-dXI zR*vlANZ0DRz4h)x7TmCKy_Vmax|i!UP>!xoK5+|kb#m=uuiMcagB4vs9`l%(QCeT& z`XhAZvUZn@jg`w5t_z?6e#}eg6Vs35~VrW`K?YM{>3&=5KGEuKQpP2>5vp0^--ufMtgs?D(~R-Kn)e1bRxm&zV)K5=W_6%h!ZWIT~H@ z>S?F#owzNTI}Z1S6y=B$iIgB;V9LM>ORWCTcR>HYjH7Yb?!&jmGgf|UWTn<~-tgwP zesAyjSS!Ev#=RHET6=fOo|9P7v%JS9^x2GJJ>P7RZy563-NaSRq;n_s1h9w;(v|gg zUV!#8S4DQ%`{cJ2?bLe3e?tncaRlEjYJ+WG6B4pmuc!9bYYxg8j2Nf3V2%3A>Hje! zveZ(}{*1Y_&N9I5FHksN#bLg(ltz?=uWfIA@&M+-@J*Ntv6i!NU+eU)uD3wm3wL0Y zE!%&$brffOCs$2q_mo2x$ntg_wfJtcJKkk`TQi*Cc1gg^eS2&Ee(8h#Y<7F=J^MTB zt&>{A_F^^(`F^whHP6*2`X0K#jMWUDj$sF)eenlS3d~nYyD(psYx9-sv|_@Vd@Wi5 ztNK3_Vx?}rE0Z|qPrw-;wjIT6r545v#JDX0w#d+Cs&5cmjO2TX-d|z-&CYH<;ps3> z{c;C(QobwI#-=3SKHRcSYN^^0Y@znnU+mY`qPMO7ZbEx&+I~m5bFC-SQF;Z|kwZdy zcIghSXMeXo8F%Wu&&LkZ?=6^?YOCcMwCCY>FuqK#%Y3*`PR(p7Sneu2a%OuWS{JL8 zUiYC5oQtqp*o`Y!#lI7G*4FZ=sS$@UONGCuChY28`Pj(_Wy`0%T;>7O)%Z%zLbnf# zC^gqi8|Lvp0SQ7MV69zN7=ioxaL0*{dv#dn{I#IJuY9Wgz4QS$C-g77B9E>=9*d~( z#YKaoYg%eNbOrpbfa{F5f&4%q}e#^YQ5x)4<>DWD3 z3gba(FsDOr{&9Zu!aHc%K$h(O?<{8T^5s_pR)T1xZiR3! z_ZuhL(vR4@56oa0<+?b+`$g+3A@#HX=|+Q|hSvs zSA5``+WUhj@9oJ0P@luZX-RwQ+JjS6XVcJAr&dHFmz2^d$aKCP`Em{LMe9!vo4-Nr zM)BT*hi}OomYA9tp88nZ%2|)Kt#aRYBC@$SDo>p|z39)D0q^(z)#;y_!G~sg>hxr2 zvPd_DLngEWc`=_IH{(R*y{FB1-Z0g3#s_IgcbhHX!o~h69=`D_z;8LAGCq#}J+k`l zLa(d1+-n-zBP-my@&xo$K!Q`aH>!-a^52lw9mJ78ZmF+|-=ej;tr6>m)MJNVYBoEf zeXoM<#^jiS6!_M&ja-|Vnw2TNN_$hnwsTISlKPDk++#;$RrNtw#L=jV@G|z`t&RPC zg-DBe^4$%1#wZJ<^>}0YsPx3g+U`kztnF@hzsjFCbsSCkEiG05g|%b6w>)clqjSr< zIB$WJpmdIl+g3YEU;Mmx)fcTjUS!@;VnydVYDxKMQh%R<1rR)U$kh^-m^-9JH%Xby{ar;x=6Wx^7YUmv(z9D zyNfcik#>lf>~xO53+eWx?2b}4$gu0e z%}#r)wWsNFQ*TQj(-o#TQ@ka?)X$t~QiiX%_pX)m<^w`XfPlI3iQ;UO;S1-joTm(* zzhZ^PFQLo0k)l^|?-0s;F>XST`vOUID%g4gnK8PH`vRoM;vNcTX~K-wp#*0A0Y~Q| zo<(uIEoi|@M7_J-p+SqzU(hGXeViiOKEsMkE8p5>4`fUKVBq_J@){#j5`IE z>B;gsAd?k%JYX1)hWFBpmq7Vj9>qW7F?^8@WqP+>AiW>!@c@Kbf_NVNnLy_I z13VkQ!wQ;emXF^-f5zi?JOYcl%L5Q*H_|iKHOod5dM{mvcs?yi{L6TR@*5a%v=3y^ z!UNaSLbeF=WjR;|*=BfD7NTQR@j*8-J?WOv=x_Z8$f4%F{Xv--YKh}~Ngz}0-nu;S zfm-->gPZSDMuldy@Z$zI!v_YgbG7jC1~Wn~Mag}-cYGyLU1zm=`6#pb;^!-K|- zyI#$(&O77X=omjxQ1KFZH9CenL>n?tOHT{uvu46YeG&g@CbWFU9?AB1DMMvcK&C_9 zI%(*>S~>vfmb^^NgS;LbH_|YCrE~z&9eQv5KuGxGA@0o~?(HFN+(TbTjx|uJWbGIS zoGDp57B09eZwckK2y8!>&YbTDoU4{BTzvOk%ODT~Y;pl6IbF8Pf@MqZ2GZ79IgCso zlJ{foqPzu5=B-$-5qG2;#Ep^Ndoj7=Ytp+&#AF8fb3356UGlI`&5t|`K9W7>hW+SqYq4qt zAIbYVA4wAUNOpmbgb`YlF7O$IpNnbT#ES6y2h z200$Xe)Pg8=0{#Q>HkUc5RbnIQmfO{?+dBbZwmgDGUau1_x$b+q;!=b#a#3Gzs~aW zm>e)0dL;aTEG%?oXo*53_1>;6|rr+X_sqHAd(;oY- zL!2U7qLnj83O+p9$A3~GgZ&`01$vz19YaMS+ZB1cO?7BZcTjfjhiu_=?!QPK&ldjd z`0tw*^n2!9Res6gWi3_TU(jdvE@%bAXKI;Ob3j zJu!~e;9D_Y2W^R;pd7LOk)~4$?J31!I;t3dlTDL_Kf|LRoy}G0??sp>!!Xed~=939Qo8D=AH>Ed zA(qvhEaHyH%1~!E%CfSI$BJ0fN^)fLEQf1#A0gTL^?iB?V}d38JxcglpoB`wd$oK| zzM-Tx)GEU!wWL&y$a=G>_wF4BVVo9z%VH$~Y$CxJOw?ypy z*k;?%UtOezy&I0x8|BO&iU}e2wo2pISOhn8i8+pCO+(q68-OYUW~lA0cYA4kJ%jGR zo%yQbWbgw;?=wv@jb_fwmA6RD^<|X(&9**AZa|M`AGYCCqt6i~T8_+r8j`T91ozR@mTfsPgElr*iZ62vZ#w>D(~8wo!DkSq9%zVC z$tCnNj3_5$Hn8rLRF0}it#hhmn^KnV4OL-~o;0atLY35m7UUB%j!ntilRk09>L~Rg zrVrkw$B}*v(r3zp8nrwhf}cb8OK4~X798+r;!?sVIE!sqz3VX62&i7^^P9%jey z0m+rL7xh7osq|vjMU*R`Uk?&9=1aTOc(Fy-qQ${%Lb+)Qip614F6cXzSB@*Q^m6prk42BIZ3;`RuXQB7*D*jnnAzId)~ znc}}5QoKwx*3?&PO`|?|y1EJTiGP0qrF*|r5R5gV$iBh3m8F65hM}G_$BJCd?HTr= zeUBY#Hb;BT{J!W=Grq5;ve{~_e|p&|tLvpK=lZGYHr28jv}AqVI)%b*Q(K`S&opU= z>fACZ{v`PP7Guo5Q`86Yt8<26&OuGIU*)QqIwZWtQm#=o^l39E{G!?H+R<#bO24^C z8Mpz`sZUj6ltNy8!7|jVTk)SRzrIjO4Bw>nv{PZ#pLrhkf0q5Qr}?Hr+53w> zRUQe$Ss7)%w734|kQpbW>RwCIaE$wHsGWjkwwgO^`R69?B`;q7-d#59QC9^u1wS1Z zRhEo?ITfv`4C>W%sM!R1mlWL3m|f9Lkric-mH+tE{FeTBC;wc+-sBedD%S=x`n}z& z&7OALvgWr$?^V+BTgt1PO%|NcPugq4|HQo(q-REYqmZ7()zm0!KDnh})ubj$z*^df zZ%{AKwT`lSD^+4`V*5B?ZnOKl3BMxd=Byv1&HwSMahGm9BS>#V)~R|cw0?r(#8D~cV$4VZiSvEJE)ULOS8@Jw>G_1~ z`7{{v`LG5u@o%6R3p%cdlSm5s<^9;|uiq1Xpyx0=eQ@kO1%TZ!NGL z7?W)WUyj{tnuvQAe?@_HEWeKUdhQ7&?X6n-6Rxe40Y9n5U&ZnrJa}IDTv;`j?NJg- zRr?0kJnKc1jDH0sSS!0olm zKK5PNC;Mb;J#tNbC2rz&RawE`mmsA3@W$al!404E5i}px_3rF#jpSjSi8kWBC3=JR zIrK2OI@?rpo60XyhLzX6!Z^BAdaL(aO?QUf7tFEXm8R&;mU3s(Jlq6*(H`a7rv54} z^2}2M9-NwTIP%PsDIWEaYZ&tFMsqsv5DuxgVzzad!uNiFMlEf)T~ zTUyxQs<8Vu#ZAvthE&&H*7%H=<;-K-TmO3CW1N8R3Ui7t8V}m3KlZi?+9~FB{D7?4 z{@HXNJwTqW{FZ5ZcjG25Ywx#bIDjKIWwI?4|2EtPe$g)9ApO-i!LMaqU-GHqJlVid z5Bgre-Ryhlkw2zfd#(3Tu0622oxLxr&EXyenzte9a^y+A$Vn~M-E{|2aJ%?Ld+syU zYL;r>N>1QUt7cc0XW7>y_7+twS4|UBgrxc##d}KH=e2hDzlWNStF6|1>7>?II;<#O ztjc6+pfh{B^5w>HS*D5XdDdF%m}AhPo|5}=Q-S*Xrf{rvBC5-$=6^nCC+ffN933Nb zrS&;@Ft0lhj4`d#7!wUK#&#Mb^#H%`drfk2mXo|>A)o&i`T4iXL;!Eap1#xb`OK&^ z+boyu24_}Ooy~lmGb%09KFfYX)WA%a`KLygU7}F%{f;`XW zL5v$cwi{3HFD=F^@su$EH1Df%)`epqapui3QaHjOvfJ>_r zgER0b^Pxv~oXg`l&tRk#)_A?{-#?*9pKpA2y~hq!SMU|>fx@|_Xm1`hi( z7U7xtL?piM$dSg|TaDdpu2IB0A_-yenuK@#7C=gG=K;S#?7T>V8ce>7J1jGS9uY>hNhD))6M__Y6p{4Ty~C zX7fG)@NvRH;8P}O8@PIL!eui5D4*YLcB+Pz&u|cL^u@krU+BP|3!#$ zlo29c6z>z#6va(A4BKr&*xF9#(stK{qf_*j_&ID{?%6?69c~(mS&g1ilL`v2si{M2%)2atD(jk0VjeL=PRwOO zw#K36+oQwOA+^zi!>4Q1YGsigk6$FO?7QPtAcQVvrOHBXCvyXIgPX+I?$`>XpXS>`6_W-^us zbY>_KSDIm}a@y&-3KUJfYcBJ}=eoeT^E*&6R!rR|=)o+Y2czqc$96V_gMwz08si%_ zpj5pgyQImOkCO6X?PV3Of%2tC_HmqE^Uei{jLjqI+_H3_nK(07FLYijCjI1d$@OsdY}G|G9tg_?!E58 zE1Dw9!Yjtk=hju5Pu3B>&PRz%ziFnXDQb{%?Mz8(JN0DXG z*k8wbm1JuM@>?HWMh>0N9|#9k6!>5L1@}J>s>#@LlfQSte8}YnwHl}jzi5YK5}ZDp z{I3_p`r@95TK{s~_LzlJcN|`*4m?%A+*#IReXsS(h&yYXIHhuWZ?EIvrYV7yWsBSB zY4+T2_%@RxBf8A0MuO|+`^}2^$eEAVF!wjxu04XCwAthL6ybYK;W%MYi%dhI9kawd z)Z-skatEmBZ>@_{lfte3Xl2SN+lnFK2}tLAZSHi8=5OFFi@)}c%FS`HW!q!6PsJI4 zWj;6x6V)iMv#ggFV+{3m%+3;}KEN8u6q0hHamQpz?5|Go#(AT>J-ofVnU&5mXb}dj z82Jukz<1~b-=R~uODvZ`YX0P+NYL|w6VD~iEYD8B`J%>o_}t8)C;DvgB!5#K40%NM zy2|Dl#EFUKc!|@cpmPjiRApm4&H4-y+OG-lxOx2ji{u;RHH>V2)meXhqB>6PvlVaT z%{=vp#gqXqi3mZJeS{;D<8f?B+!M^NiMJM)WnCsD&(A9A;p-bOdG`ut4mmMFjafGWXYC%>e0*Ib zm)s*v1;QIIzuwaF#!6ZqXz8zRd_Oz(}+AGeWXKioIzoTVzfq6Yk6n~K9LqBq5Y zMjYeVpL@SGBjQ1f)Z{-mNNnN|*km@`k!9q+iuT2A1pk$#L`?$smB*h~tZ`uVyw5Qz z+Pme`o-R3(O(`799{+14CqC}kfj;@lHE~abm%FCBW>^M9fK!eX?aF{@!^=U_9o-m+M@*1*#t)d#&>TpCn|&EHWL334^3)0vL^|;A;Q-Z3+1=GxQ9HvivPJn;-a4x5f?QSV#}WV z%LaZ^xNiyMR7Mn&!;iTBev~$D<7Twyfg+Rya5eDucY%{v78B=Kf&E@+O9y5DB*fHa z36FR)w?48g4s!Jre_qKQyOgBMRLr9~MuMh~#3^mt?sAsJdV8u*H<%N*lbh{`z0p-3 z9A%SQUa4Y_bCpL44F{6zJ0igKeWzIGF- zGmYvDhdd!hTffbHeNTbM4X1KAshnJu=!^dnytA-`BM&FqY2f;);>esi({uKVB5iEi z>KMuq=Q(?}D2PYo==?*6(fL@d9G4AE9PQ*T&Tri%_~)+tJ8%@wj=w67S|V`Noelkb ziJMKJbQo70>qDv2O`}nBHfvH?TGIN&b;Q!j*@+^qX|#2WH7S0V7V)w3t)_1(!*4hdGu%3pG}j)N>-c~=&aL(O@Qe9o%y8BmaPMf(7@1-LaIdjfC_7Rq2P(#O%9aZ$j8Ti5J z2R?wVi#sagRB$X)*TultvR?IfR4&Av99!SeH;?~ zBS+?`smo6~tiYo-wI`_Rx#pTIv|EH%#6nJir+I4uITP+g3*WKJdezamSZ{jL_87#O z*xvf;A!V53uruw5zqBCo+|m1pcd2#Pg z{pq2|=9Mn!Pxj!h=IkE}`uV1u?Q8Aj+YIik1XW3k0bids8=6KvsjS0nm%_9 zj!zN&td~zo+i^G^JD>z`_~jOI%y@hTZNIpJzkP;Ua|AgY$EmmlOnxLj=_Z$1N;s>WGXOh529Ocd20b*|d zBgNdITKcyn|D)V-3f?z?#ju z5B!e@I@Zr%Q9tbY-)e~V-k3QBIsfKBqR;as82Hmdj=8i0{lK$@IRyB(uri2$tpk92 z%;156Bn9+{80GBS0%I@CWN$i!o{)lmkcoca+G@nS6S~j~Y6O2VOIzO*T`p$bT+X7m z)mumQ#FHseN&Zf~oaZ70zuFu7qc=t5I@N~Wocmbk?X9MR7g|x}w_Z`%(4ficAfD@3 zTcyyxto1aEj`V&Nv7368doxX^3vAbX5DqOg>e1Lurqe~%h4I^C-iedrWsn*Tenw!d zSwB@w8INKon^>lg7u3${qBfP`yAN-U=jh6BeSa56%ZoGj1lEpnetPPnYsdVSZwBh9 zp($}w{0>1$q==c+9X5pdCay)h0PjB`a{gJ9aiym1x$dnE-~7b%CuU&RRcaY9&|hHH zR%GGpoNIfO_QI+x0<}09t^YpmVPDyOp;;%tHGNNP2%i0{QeyV~A$alk7YsQ{4rYP1 z+gr~axKP_oYE9Y8no4gPHh5uX&grQ(ZCyou;Wr!#j#KacByoSex6)NUVAnNbthKl9 zIK=hWeKmtHVy2~9Yq{N31;q=D(qHs#Xy>1vJD73dG?2oPBEJO@FUmSg> zW9+$MUp;ROzD2%i(HGvRj{=T^6!KGb%dL=Y!2tzxhEg@9l$T zHVsPzy+l&@#<;TH$n%TVro+Rq;%;w!=>T_CiR9PAe%Ok=99JTbiWSBBkecxBVomfT zpWl)Acw(UBklHBP)vto>D@*ss2J<&b;W=>U>+lV7*+pef&%WnG#_pBmu5**S4op<1 ziQ`|~oG->S^a`)}w8eT4R%S{f>%3Rl|7)C=@DT8sw!Rb6j7yKz z#|pPqeJx}x#*6Qj?dxvn1**KGhkpecBh$cyET*`(G40eRE22t?53u|9E>yp09e-F! zz4-)3PG)U5xuuWx+RV6{1ZUmr*$-!@RPJf&<-0Y3zK=Kd+mtdSzjaxaEEh*iRH>43 zbxprr{d~5vC{V>HN9-7Ba-3N=bR1`VBeryAW7Ou@(j+w>dm3`u71#FiGKbq5d-)=o zO;)YM-)@ZF%$d-gI{^DNB_(?8i=ThC2d9SMQ9bnnOKnD}-w(6C8-efS``>6ZB_*g= zHV&%1v5C8xDMGi?PCT`@mK|^fIQHmL4oiML_T9h7vfuwb_8Po@J*)~#vlw>@f~ z7&cjlbTe$84(VpuN5W>nlC6*Tv}0h$!j6L-4?6*tX=K7qfz5)Q3M=#MY8uRUKI{V6 zg|IoWvYfbP5M^5hxJ0+O(h!E}(_sH{LB7Qd(*@`vCP$4oPu7I>%5<0(?}j_2qnI33 zW3j|rb@9GmBW=Vz3+@INB$*WhtdBumDw0$pz@#%KsAWoOqZ&7+13zT1Al2``EG{?^FU_9>u@>mdD{@ zJZV}GZ>4kq%6uQjv++9;67jw8W4+*-Fz_8dJX;K8AGx@sV_i!l^9rTe*o=6UG7_MS zM<~CQ!G3fgH!_I9a}q4e$7hxe-T@PXc6&SE3Z`f95|1(;I=X{q16P>_qv@$)9>go1 z$@uLU->$F=Js(KHE@)Gh1`4T#mj^0D3lH*MYT=YCsu?Z(L4%v=Q;(1_+<|*w>1H_P zC`&iX_ld#H@a$MU7`>n2c?LJb$=|D)K*qvJ8jL`Y@NtMcTt0eWO=2X_r5WnI>KH#f zKzHOp6jO&D$@X`K#Mj*HADVHA@)BojCbWF)$w6a5Y$L8`Ivn@X&^=8$0O|gAh+B?V z<{69nS``vr9O8Z?#Jw@Z{X~d+Pl)^35OprwxG7`U$lNJr6OeWoCk*36 z5uozWSvn>ArGeAa!1&pL(=#|Lb!7FFvWAVko>Jl0+zzB0ItQqx>?_Fesp|mKSw=Pf zS<)3eiEkz3W`X>L$8@(F#lct0JI*P8LG2nQ+35gk(JApO_qaJvo{Vvv)b z<7GmGF9$v#B%a{+og_rL&glLdFexzn7$NFqECvSMvvhce4r_Gi#$-Tw#6^UNx0P@> z=tBrcD9T5=KO2bQ#6QfJ^6i-~`9cYo=ApqxNJTlW z`+vJ9-0**p5aj_7@{2Jw2|AN3-F-D7+6em8CVUmTld)e#PBH2R#x`1j6nuL0|5|-& zu}l1u$+SN5fLwMW6#*u($4@^Cl()&|mvwgl6B z%Y6PX7;1d_t@&YvR{JFy(vW_HgN6S!fp}Wj&&?*wZ_WHUEgy)mdi;N4{w5dwGaNa-7`3h?7__cgD&Foy>zeUxO>2z_ zXChy;k7zRckkcr$_ct0xtRWXu88uBg3Oeduqh6yoYP55OGqqDdzu_ntsTK&WZ~a6M zv5ZjsZxmTac>J4-JZJ8{X@0+o%m)u|KXcDbxPc8LU+X=yBb%>wK6u#d9i^5ZW(wa1 z&zwK!Np-*K+8D7hY@>5y0=`hwBL|*W)Af*=JrbO4m-*jQMwn3FPf0DRFSl{|OgQzOsa z-r}d#LAX-Opm|1xYG6vQgGr8_o_JPSNmQn`2GFY6_!zcSR>rXCHyfF6@aOxlS*%fZ51FwkM_n<0hs+(-U{(!1OljBSAfJ1?qmB zO-ns-(~7h9DI-onXVv6@mbk{+X}C9Hi&7RI+sO%@V5e!%+p+?>)lH$BDc-yJ<6akXx;03fM>bTf$4lUll?}+E7KC7k&9aQ_Go&=aO>R? zx5wT=&mQ#THDF#4IN}ctUU0*Lwy6vf)P+xDgQhX?XF_9OZ#A;v6T7Kw(z({%T||;17x`I9*>NICuH}@0tn(XKgU8BS?#UxxLj>^_s4`-fBbr>OiblnpWXC2Dy{- z*5-XdXv8xk{@eBB($zu~gj6@7??d=S=B)cUbljZ?=(syph+cGyQLCCw{j}D+!BSz}NIpgjsld|5 z)q|(F$NYXzgVXpy-0#}9##T~0rUlv)D+03$FfO!XE;{z%NsIq`Ip534`PL1ZnL0H` zGag}dM-U8_j~5ExWpf*}S;pcFyJBi@Z~{Z0|Hl?{& z5wYd~-2Kdf+(wQgU{6p3e9?~H0iB4A1?Gy_N{lFr`Sep3Y9riyh@6;_xWVxi#DGH+ zBiTXCfKJiEGf(ZXKnm+Nm#!NyvQyoF&WdPg2V^ePUplE}=SV2|1YBtU4KGI0Ig{ zCVrW1Yz@CE_(c*AXxag<7TN))6>8c6%>nIzmsQ%K9Z<`UysH?~;B$N%z0>M_qk$tF z^4j5J^-d#~ZoqXLPuUEdhkh(l^W3kP(-nB)mIhLH5G<{EdYp+8?1P0e?Gqq7{7w~8FZEwv!7${@*?xvuA z!P^hwZX+Etjf1WK;_esgA>+E);ed|8vb~a1)Y0Dh!Xd#;I=H=c|Dlh=lE51}0KB1Q z1Kong9}3!tgPLZ-KA1bGsgLCxuqzT$r27;wL>a-}QiE7A1-}tIw5&O^xOI;_D0L5N zam9CzcpvfiAJppLN1z}}*~T=V-re3>eo$KtWq}v;?nM^`$7xfrES)~lS ztA?5k*9uLB`7Jl?-3eNTS$iGOWjIRcGGza_TC8kkoxcRG*XG99$_j9besdS_L_jNQ zd+XSP%vIxtZEyVn__iyi&Q|k3AG!;4?SU0rY~|+6&yTgY_6Ogz79Q7Wcr+w0+slpm z7vpznoY~t2*X?sn^8G*U>@5919N=izdLA??!gPhtGzal;>>=)37V;$+936DHW8q#} zniM?zEjkwG$OHh7;4GrkdzS$JYG#z*Wq#SnqI!$bG0W)qT6tH4YP*cLG#A#t7*NqA zFK>d3t?A)x9@0mlmHZ`;0U=h7$%yOC3&tH{(nQ$1>s^mT_q5o(jt&bR4@0 zLq6z7^=AT^-ef%Eh%I2Y8`9&uGQC^yY)tPY-0Y9i$n?Gg4`X_}k=`tvDe`EC<&x>; z;hE_nNSGZsM;oX=6Ug-L$1~$)&=ZDo*^J|g@o39o8Bdxz#H*GLK$+e;JR8gR7w|fz z!;j_T_+>nn^JlO)0%b9UDaE;-b}ps4WnMU@W4wTQ8S$PAxPoOeek+5o#rc~DFYzgt-42;x-!w2+PAe9|I$A7xYSw z!^G2(i`Sr6QkU@=VEYZsUmdS`LKIGteOKQ6d>I?>d0HklEtR4ADm7h{$_o9G38n2I zB~;UK$(IC&uheuY)KY44LfyJv$^jaV<-HN__ISU;u}F9~A?^vD)Zw#)PTW`MuqW@4 z5Z;dv@y8M(e2wm3iZM&~uXHHxncy}90rFmEB_Z64Y=DE2A0g7)pu2YwBK%Lf|0z4% zDOw!H>jleutQ5kbptB)N#XXbm7J4F+F_!6uZPOufgE`~Zmv_P4|B=l`E%zDTXE04`NNlu0ORt-LyMn#lBCFB~@cYpoL%UF~A!{x;Y0w~s7_lbW&cM@|4hMF+O zbr3x;w1pXfe^#xWmP6xd)vhS$&ZzN=$73JiJH~ujr_umb2y+$wW!m&u0?U3Sjf^)A z9vFTBvmFKHTtGjdlfc^VYCIz-4?vjB_&0uw%qw*5SA%%$$I{4ngtCqpRtHBlAcmE& zET1fgtUGuq#Fbbk28>KE;GsVl{kvoB$F>O?P38&9ry15%&{#yx8Qq#p5|)W=MVTU) zkuZ!GC<9k2psEmkQ^Nts^| z^6fWcA9CJO-7mMF$TvbYm)c92^B?z_M9xWpoD-3AI#T-by!(p0&B!}R&ztYy-43}o z>2e%Hah9=fuSR=JjeQOn&KCeDxoX2MxraL86=B;X`1N z)O{*0lz$eUOh?^wyczK%+ff>c|A8V`!LH+6N;ay zJKea?k?{zP__-7rK?|mWC5*7lw=?{_4c|K%VbaL-q+3Fxe|O+#)<@8=bU{OzQXRuJ z-4F$VD4IKn&pTrK&SXY`lt}ak_9^0XEaL)(>7>E(8%tnG?>7ce8j+72Y=JpouJjQ? zjRNF%aLE8=?&7=hRxQt&o40Z~)0znD#QKR2LXQqvCb|m%&B&}LA=Z!Vhn!cg)!nlQ zv3{28N^S4AY{bRZm0x9^A&oOkhj}In_fjKEScd+p6J4XFRAZvg7}`}oVcClQP|GX`zHL2 z>0M}E;90Q|H`c>l0xJ#krMU^#nBIlvg@uS`oEONSVC;i3uh4m6GXhpJBi+b&gvNQn zg93Tr$$0_YTht5j8_Q-~w}XmDxdDFC$n>OJLZg3o%nLw!2BXO)B;M1EtWC|ud7@){ zO%~y786DyLMt+}WEq@_#~pBK>EgH}U>MGQoHTT+u)*}u>-6Co zm`3FA)rp^ZIwz0yII$RJ5Cr8cTeLi99u@8cMmW;%1M9?@y@wE)&H^;!Ls$=HOnltW zGn{2%xb*MIa10Q>&v{0?2e$}ERgK6PKWfxh+0Uep>azZoHslEtm}er;1I;r`Y9I2n z9@gdvj$I=jr&}6)#@D$1Ua(}@ik$8{j6m5hC49=dltzxQGC)kz=+#^ZjUacDW3 zJg`O_kOj9JRvMWe*FMJd+6?It7t8dn!?O|pErfeCtTZyOQ2bYp2)D^dfHEGT5&s>7 zqYi$=8??-q-xZ4g_M;Fu@(UQ5Ucf_tF#2}~{xkM*mJY+#uol+b!S-U!1r70`(Qq9s z*S&m)_>5y+8u|^84nUFaihEax-X1_uTHl{5KnO;{J1nmmlL>R~2Zz8Zs7#4dfJ4TN z{7N{a>pGkww94;*L(-qMUK^?Q07dCg)t#IEyuc=UIgPl)SPy*0zQ4qLziAo|IRD}2 zn}L0O&gz^6cXumdxs>pVv5qAk2*oRZG2j8lp(S3K3~L-)*TT(rrIG1<10F`a5`h5r zW8x_zUb!A_BVJhzcUSPrZp8Z@tTeJrghssbNf+_T8z@A&Obk$_XYdk_M*r@>D_rjd zjmF=|v8ox(Eylm_2*o3zZihJ2Wf|GV#4BK%3K*s{FyIQ}6|J`i5R2aV=V~wnwFo?d zLNl!k;FWRu;iD{GV#L;sYxBy^4PD$-;B3&kbZ!4E-sGKnR4 z=n5{`hIn0BqtpSH96?;JPvp0-9HDEJZ775r{?Zt6hV&ye`gaE|Vc!p$?q8EASc8b( z96%LX-<~@+XZiA_%LLx#owC3YXmH{n?qBqCF}%EN`JK3Oy%zD~&7@p>aJ?)5Y~fH3~6QCI%?eGkA$d zqknhc0OF>g(avdD&zjNP#95jNT|b1n9pavYWn>$3Jpq!zfMGhJ=k)?daG1+0S<&t1 z@;_uHp|wBvC~V^ktR==v$_p+gE{-?;-g6F0k?k7p;J1H`xMRi2dAbmqg*o$A-46Es zd3RxdGWo{qhR<8Ma{1!VLu7J0HI5+<+-_KDWO||J87+qNjO&lk^NegH)YbJz zSI#qzc5(gjEXtQIKLXJBjRx-y{@tWc%H#F?&^7l*4qOJ zMDP4_H5h_IShg=;gG|WyO0;9?l34WO_~S2HLv+9&<{6jj8U)q1a`9cb=~_7N-tNOB z|J&9f#`_T?9+`%=G>)+>xZPU&ihqemrod&~$2btc@eq2JF&lmu!g=Cl{4Ip-3LYuf zCIzHVL>wa0<&wobn}WlF{SdgM3cIvvJJxY=C`3o*^^$^QlrItSq%nS@^dmI-|D$jS>q#@A zYmHEMaP7f*?`-Ws9HI5*0FKZ*_go!nIZ;krPdrk_*?DK8cP?JCq-$rQUDmPJqGj6w z2VA=A3Rb}X-StGBVeGP>Nn8+mE}Dffx7M!WpYdoy&qe))^w^_ide`C^L3w zZ~@m7T{##1D*KX45g?oXLl-JH|`KaUE&VW?dS6UE8~t48572SHQLet zOLSjLR^;S#BSJwRyp+y2xb~Drt{>9iVceTsi0;dSc*gZP*AskK8kru?3XJJpi0&(t zR%12Z>&kj$H{x}LR^zMCeGQWz0ciY2gLeo2?!YM##>BBoBRwhi2%7oZX*bx$T#p#r znroB+dddW14}`so=5MJ#&`rr6JBCH8_zw`nUZc&01Z4x zJxc_)k$Xl|&&;=8j*^^4U*|n9EAL-(J;S<|M&b(M4o=$2*Qr@Xr4( zI(EU7^e@S4Xq?|TzGy=6iSdq>acH@x4&5JJtG^2%j7%>SpI8wf@za;#lhsJ2EBItL z;&la|ob2LV4e4Sp6@0>Rs+qqXpRkR)iciGwm-s|<`?>r-51$D9(Uo<~iuqloRsB29 zRss}fhgn}hbsg3#bW6j&_x0V=umb)y*CMP(Y2;W>gNJb~^6zt5SwkJ6aeveu`=CqV zY()%pi91BMpUeOAa0kaC*C53GU%Cep^lM$BbN@SW$E8Xu(!J!Wm(m%^zj4R;`xw%i zT`KF2;C%VFuRGYrU0ru{AXU{URr!BG+`;wdm*S3c7wUJu9Kzt*4zeThJy|+WopDXhIGLLNv?%4Jx4yo0%Uqmnp%T#o z28mq4tNT_n|NG8$%dya5-{bh;nunI|ELe6A&S^B)!W!F`@n}4-#`V!Q1jzJ^dm+l% zGOiJ_;btDv$n+?~#F*X=1i0bH@-bb;Bb*Nl^pXc4%y#^b)}IMvUZHXajv-74chcj^ zc!bza1w&uA_-EM=6fjFrpdkTQFkge0c$E3j(H-j}o`nSsYb9tXSD<6K zrazSB*9>bgXgZU>#kedp$1!nUD8F!`9?m{N`CFuUA&QdArQm3jT!2~xL>KMnM8&ey zgiM37X^AIzc9W*N(+MFz3wKlFznV;fzn9i1n#o$nYValm+q9hz87oJ%HH8F`_h%K#tP`ZWyrtJak_SY^i}XjSMHDgO`97; z7@RjclUX2!y4=)=Zabb@wb^ys}%xs$Ek1 z8sqtwRqt}#;~LL7{!L#O9E--M?p~7w*B{K~pF>|KdV63=qV@f`0-T3dx=3HQa$(Mr zoRv9US(A)R@3IV~m0IO@Sd+9p7p*EoM$|;)DrspoHnkUIi96~h=010LLGDwzgZo;W z9buMduFAb4H$|m)ebqa2mDE4gR_5N6eO2x) zxp(5WsTh~|~_Gj`zOQK5(f3a?*xe)#ujR2l1^4yVeXz9*`HICtGxQ%-encg?y zZ^VZa5x_Z_=^6J_GvPL#`_{qTl|5BY6k;yoN+ZieXgv3wjl_?@kN3~=TUd_JbKjmQ zpK-k)(?iq_#^~Q2d#cXv#aTYhu%?2hGx@SS4`-R!raadTm6xqZR3g_rvTH+-bq?O) zzO*x0Zdl)p`bzRtGP*8LWtLWn0X)Qes`1ZRRZniD>e$!b`p5QdxiR~OKzDXayE}Ks zG`IS~$?+Z`N%kOpb~vwo+@>n8HauO>$|I3 zxjbjVs^wCIwNS5xc7W>HW!=djeJSm`Qe;H~N}Le7M%s)3wgcw@#-XKq3M{*b?ESau z{s6+r^hn=l#4+0q>G55e-na2=9JdSM&VrSO@n~*@HKw;40dDxQd@L8^5iWo=;;bET zcLir1M?9nOE?Fi*BhD&7;(qw?yoHwec80U^5HJK`(#Z6rTSB9Mci=46N6=_%F6O~; zXBMRmh7xCWjBgkBLO~qI8V#Dx?ylIcrQv&SSmwt!#a)#gOWGPNFxa3dOkg<~jOcpEqH&l!|+Cy5j_`VFGxNIt25c z;~FeNoqWJmcSSB&T;VkXbDuqI9qkyMgf*CwdbU<^=e^+0%{xy9u5n+IhVlakmRRq% ztod5jP8w2UJ$2)%>7REN&H7{WNF2oRO+RTkCTZADv}P1eB^#i#cc|N+ZWQ{fzxH1_A7wavU)p=cG`+ zgKYSv!%8F5y9yr0^xTH@jO&+c5zmMdO5yGbPIwvdZiSUbj#WYrY9u(T4&g% z_sO-*P*Qpxj#2x79x$i_PJHTf_gC9zgiSYlCnYIflQ%Zkc8zTYagwe2wl?dZ4b>qY z*&g^j(MR}g{4U}oH|#)IemBPo`#k$8=ROZC`|)g8#%I4=2)hJ!C2RrggRtvhx4~|Q z-2uBBwi@}=SJ<eQ6vyGA509FZ)_nmo^)Jl~z1^y<=DrN4y@_vX8(~!rZ)>7#`GMR;8Wno^o;ZJU2rp9IY*Y@S*C%< z!1Mih?n=ChPU8KA3F$_rT@5$CL(bvMx3hS=;cxtobbLn}UgUSkd7kC^4J^~kfTbyb zVmlny{yzTe{6m~RROup55Nmvb-UG2bRw)LkBcFm5V-Y>e z=#CNRd2BN`Ecb#-0O?K_Zo85XD2+&$=vUy`z-3-1h&mKUcfi3RDEY#3L?<)D+_`!4 zmahc*4^9>#=TjI6?8jzw64G%yabe-68~y_cQ6(vas7m5Qb8r0VkZnje#~mStq=5Wx zy4mjtIkysud;s0LTci)SNFPw9&$?uMj$1;mwFoEb(4)gF9bT=&YjrqFhqHA!M~AoS zFk6QUb(pKeB|6O0;YuB@*5MCzSfIla9X_bTM|D`L!*x0=*WqRzZqwm*9q!QKZXH(Z z@L3)1*WvRzJfg#wb@-|d-_T)=4v*^am=2HYuug~dIy|YvPju+lVT%sibl8&+1a*A~ zacnYBcc&0K0_U3O@GF+{#N%Rnkgp<}mSuto>_K?m;lOPU^@>Iy;6iIVVz968>_Uv& z6}X}Qmz0};CJq>@{*(r2#NySM1Q{>%{9+3Hh$p3)hzGZH0Lt`2?_Vw?pLQ1BK~{M( ziCgh7S~>t_UZL}RDZ;WliO2ZHd7ip@j=+yIi2RlqJcrKnr6`0O{?f>NrCUOye|OCD zEK|@}#XQdPX(n{u4s~nuILpM4&hL1&VJuH50zF%M5OsB7*|aO~%3HK}Ntb9%#&-RV z_hqdT12`ZWGtRJ&{gbWgo^u6vh1I!<58CbhV&6~7{r~KJ4}4VBmH&G)lgwlYNiZk@ zA`S#35dI7aA|RDX2+sg2XlbQtWs;CMQG}F#M(dUdM2lA2kbnk)Ev>di`5VP9iZ0aJ zEn0Px7Q0ks8@rHDW7`QtnO1lCeZTkJJM(4;OYFu!+h5Oo&YXAuymSAbd+&MY-PbS2 z-BMwgJ{QbRz_)qkb{$-hqa*7n1|=X<{gubm*At~ zO_08ShVInnHZx)UPS~9#IcM!JIW81b;i4cVqbBj*g!>%dw6DXnlNl)ut{dDb83lc= z7ysgZ6`%6#)0A0eV=1X+K6EktAjkec*#EJ86eu|qFV{Z8eCI_Zu9q2yNI5qXsKya4 zg>H%Mr$F(`hlf>8j={j=cqKoMLB)?s5b{&|rhPIDL;&M4yj)V@i9fCl<|zlLO1A{p z)^w*KF%SHhF8x)y%W-X$r__1%M4tK(Z!PXsz`PMit@4!Ta|Pka6*kMwbV=jo=@!)U zLij6C{FGZ!tAB6E)7YJY`TlpMN-R>FrU&;;vGL7s(nseCp)xA~qtY zZz0Z-V!l1SuzZm^k!xAm9Z)OMPkn7#a?%!7+)=r5S=qwM70b+i;l^a`L85MK>X|<` zHka3vV&NGe#lyoDpxleFuDK^*KN^AzB8u3nWRRi{6-svzDI&{f?jnOdS)1lg>iM@= zycjru$h>qRY7q0%jC=7c?r7Ls+xO8Fqt>{@&|5jz6O7c^GmM8$1a0PglY{4V zdR~ry0={x>`pn40nS@4LOIBb(j=fp;B;aJi&|1yot&~?t(2M8#Yxg7@o0_u4%$Lxa zW`F2Jk~Y-HHWFt$g|nt6q@&>_gjy51kd zKnaUL3sN#`ocAW)m+(!;I{W>YZSzySYRQ*gwivKlQ&@szn!`sep45dX}N0*;k<_op|P--%BpLXjUmykKEuNLu~M z)HscL;$Z;CuH{zq&QERy@Y&g6c+p0bbxKN4#5Mbk0?HHu`;}D^`{D4w4`NBk9mb;^ z$_HBcHNfoyDp365-w6y__%SbvpE?IY*asCTe%Hann!l}ZP~I_r%$MSK8?LSS z;}}u-yI=Cl1tly7zv1Sk z_-8z(w?$IniN9KS?okd~zJw&F{(HuE;yFITf~pb*4R)xq;9NF za$NlAolJ$gU6wBjraL+=*i)il7d^-7?x$h-5dq%kiMY&m&WUs9!Oi;h0lCJaJW#;< zuL3fhWBme*V6J@>FkC$Rlpb`Ksz6Y>Zv*mvUSELPSO%(qe%}B_!%-imh&L6}a_WG6 zV`QPWa5)|#FIiE}#hY5rMdlOBC-LOmfoOP4xEQApFTA68F?8PWz~juaC95E(1XCdRmT||mO&Av>x z;0tCOq`QF>-RW`Z-bQ*sWKFuXczJ0>1s0{})0a-3qO9l7ZwLAw(f~x(q_hLoLaQ~} zX|SBu^%LC+Sk_N`y<(~u%yOG6j$ZjP@n>c0H3oIYamBhLOa!8~BjAu%SAsI00`^~z za)7FMQ*mvbzbY|VaQxB_Tbs!IH3!!SV)qrm{>`)%sIg3v#sSB@ z8Y_%PcLC7a_pgTA15}{+Q9fAtwSphV8~L%1Dt>cuji5>p0gLh9lX1Tl@w(HkF>ls! z-wH=F{5ZadOqcm!-jHqt_^fAS#1&gci+4=fKdEug@o7T598gl(4DHT#Q^^6gare(c zuQ1+%L!Tv)o|u1cZ7T8N4jG6DloP*hgDtXNrD`Kika8)e1h&!4Oib@2~b@ef%c zN39}OIr)E7R+z&)Dl5#c-a}adJMPOr);G5Dygfe4)n`_2WL?2`WcAT@Bca(gI5kALqJKqkBNvR>bRTA>PipcfeNbGt_-9T(R`d(iO{!mqhF@k=*?t^DT0&3FnFzZvkb@;hPSXI+oQ3z8H@*0JN@iHo(m?D^O|0?{5wvLY0aHs^XDa z*E!r*dEm)sq3XFV%g?+aC<3*}P*KDcwcDQtBlS1zUnL0(jSl6R>V!A71H-V}=ky_;#ZRVTd zcfS4FUSz^Lh7~_c65`V8-y3o)DwD|Ge78TkpEliTkxZ!B&GhJQzXsK*s0+3+* z1%i(fED^DzJhZq~nB1cwgF=R&G1Z=JeBOi!>aF{poyFF>GNY&awohGV^zz2-^R$-w zhs-#8?eqVW%!uE($wf(zWrnmdT3*I?FngpE?)f{o(@dcpv(5-VlV}VO=XzwcjtcC< zxgPx@=X#6?cnxjrsg`69EphCIx5?ul;(yftReu=ge1u;Jzu@8tYG*wQvW|fQ2-VN< zyfm{OdvDwJxq9cYP)%5%YCRFZKH+(f-K|g9F4j4kdmV2#{NnY==lTX=ygqpwc=cp` z@;2i2M4z0AavVflu20lji}N(sP6&#?+i-XyuGlhKykpAV8|xG1D++(R{+R93z5ZB= zgosW^c5U-9x%s>rnGkCbG`L!WNO^K+@#5QQvUuM2X(r_M{M^Q1oIL4^mg!^U2P$!9 z+C|21Vb7-x&BZB<4OjUC8L*3AmU-s%pU-#<9lqPH+8XgY4!>L@$FL23;Y6h`0&2C*@jf4@K*=QTajfyy!EJ2|74Hi8TlYfi5P+^M#=P~J zHD!(2^>6{$0K8gUnSYAk95}7~sDtsqk7E^EdLc8(|7IY>MkR=VR{XOp3RGJ0IwGF+ zxL8F3Rq;r%or=IZFmHv6W&WRZL;>WFdJ_eTpK>c|_3sVYWvwID3iHV{t_PldZdyW2 zozj{B<}VhVA8R%Wc2Uz-cao4zjZZ$1XXsf^w$s|1J|z{` z4P@?}EtfZ4G5YWU*s>4nS2$pZ?HRAPYr}F3y>46kCHHn*#|Eh% zKC3Qxoi6&4)gH+@ejh|UQ9Dy?`qKMnD2Rf&SCc%)W2 zUxS2N;m7%f$aK3~qb@@JW*|&~;-}n-TK#)N&a+%mFl}@1i6mmWnO_rBE1ItEbZE3) z2ScKlXBCuTU zWiW9Bk!E*iSjqM7-7p;$3*PhFRQ3EFoiwwqV&(waLJ~QbS>+Gi3fM>D-JiIe5o=FY zEzj-2Vl(Q-H)(_qCDGrV&7_hEtb27m4cBZs)uSg{!f+Xh$Mufc#Pl_7gT3aZ_*eX{ zh07{$_+2Is{3ySy@`n3btGrnZcTeQaR>WHhRG{)iYLz!3I9lOHS;PKyE_u_8Ok9d^ z1&W_?D{A%c4SB=*h=Qs;(}%W{vEd0~ZTxZM596vjq5R>qy{Mb(N>dD|Epv1r#R0sbk<_9p|kWN9=R#w~RyNI>iUHjvcx^Kn02)<&c$M$imMmH?BcE ztK9Iz-4nU70r9>HRG{*t#)R_!ynm0$T1Tv9whimqg!r>}l~gxFyIZH=aldFE@}ZpI zepLb6)4Jyt@<(*_$oj1tvf@$1D217aSE3mRiul(Jw#K zd~-M3pVnl)nVVJh&$Iq{_EcDb>J!~NbL88_TDI@h>p^$p?{6MEIGsfJI z?&{k)B+<2dZb(bgH`+HkpVS_oHbJZoooNNtX>Gwi8lN<}k$r*;Nk2oLeT5cZ_K z5YF_t8-5qw@Z#^n!KYpe_docv4tu)ZvDQAftGHPI(3a==(0=Nbu*d5t+%V^tVa;2D zoYc#4ys&jvE&N*NzoqGH`*StZ}b>7$W3Oe^GW7sNGtNx z`dT$G*-nsg461!g^4jxUch?)IjsT&e^G~ z6OYm7iMb)SE#tu4P@#)uKN=o$aA){Z?eUpf=+R*Csh7k3wfn=apf=o=g?xFDCm-_U zb8py!l8(<=+&s7IoiDx|&hRcOOzO-`;$Atu`AwKTk=vVLkLS(sH1E8kd9!{!DB}S4 z+HOBX`ik8(+N96UcDBu#$=-JQ8`oYnr*PI)v$F%q{z3j5{S!s(F_wGG*o)f1+xyu2 z#ig%+|9$OAPxkG+)UMUp>e;d$>brQdPJ%HLtFZ)cGg2~^EIA6L-k==)&t?;+AHDgv{%AoJgIs7G3@q!&)tRhnL*H)-Fa5{*-Lt{BH%0Y0d#Y>3Pji`!HM9E8+fo9tgXT zMl#Y!^NwhrefmnBcwX7Vp?8V{*oRb;J^!9~xLWV#!p?KlofDoZ~G2&|6ue zn9w}1ZG!F-b6YqkTEnI|?V&hMM5vPZ$ z2+LRCWPbWoE-PCFPrmEdYvx3st2GAOO@Ueyuzy+SyCYa!xG-VER87n&jK}^-9XhFE zu?-iT&lD(rRElxFr(GR^@#dSC;-B#t?gv`=@i}34{FZeSPo;$*kw?<|faI%y{ECzV zRNb=%*Vgj3V)Mc|m*rLKD(0&m2o{wf0t&&vItEl)@w%ES#CuHL1gheZV!IT9Em+rA z!h>rA>M@u<=7V`dx)Df5rhXZ5Mfq90#HC7yj^5ZiaZeWo^LgT!NXE>w#c#H_qj8yk z^DLRDU!pksg>LfIBRgR;26gnT|0tkxEYRKAGiuFb@?(odfoIRe@=MZkWH9Slm*HZq zCH&d)QQ&*qR^WTtJj0W9%rV3@9LIwK@|mL?pmcvJ&dt5J0*03>2PoaQ$GO?>6)^lB zT30%~>yCGqCb5ZF$A=(&8oMd_jA~QXD7FyR8ar z!A)+e7vfm%#TB;(R%qg^x4W0(1aX;RQ|`Di+4e^n-FWHKLyFD&Xi{tnsh{Dy+gFm} zooRy<9c~`!C1%^XJ?1&=q+Rp}^`V21K2ADR(@v5OgIvQncW2=|2vVdol@$Da(!Yun z_Z^ZH>l+cD=pQ|UIEuGpUOJHJRRKZxAF|}NI!`l zDK0uo{E{L6`fJ7&uUN6HqGaWYGU$PO3ZJ!(0ZlD{bC*?0QVtU0=YM|RkmJ7(ka38- zk7I#U@uMz5@xW!|n!1CY#Jd^sFgzmbgzoq;{B|JHtOOC@!#~TSfN==%^Y9AzeO-i@ ze<~g+hFJu{a8R$#wFl=6mWkz$pNCxt7zKX?il1^TYW44pc{n;sn1Z#&&3QI9JW*vs zP|mBd;b+gQvEkMpLjFlYC#q8J2Yy_uMBRznQ0eBK_@V}NoMfFioX=?+$L}5STaq5&a9}oY4A2Wy-$0^Gx(`?gECOB)oCoB0jurrK2Ks@E zfC1oQU?p$`unI`~g&?p7xDNOruok!h*Z|xD+zNagxDB`ixCgiwxDWU|@F4Id;343v zz-HiK;1S^4z*gWf;0fS+z!0zt7zTa>q=2F=Ng6N%=mBN}y}-#pAFv2G54Zs62L^!D zKU4vOz;(b{U;}U~a2s$Ba3Am>@DQ*Wcm&uAJOK;=!$1mL7cdQ&0rUW~f!w!nui^u8 zPr`i&<)R-L09FF4fI;9oU@fo#xD~h!xCgioco299*bF=ZYz3YGhJaz9=0N&Des?Yd z=mBN}y}-#pAFv2G54Zs62L^zZK@DQ*Wcm&uAJOK;= z!$1vU)dfrgW&l0FY@io78R!ER0p|f10R6xKuo74W3{Gt-x)-J-~gygTO<; zX5bNEEARv`1PlXj@d5LJ1;81=Lf}lG0lW%W1e^t&4V(kK8iq1f=C3WfrQ0keR^fg^yI0!IR~ zfm}O}2Ic_A0LKEy0mlQqzzM)yU>BEE|&u*1E&C|0Jqh(NJ|K!O z&Zt50g)Bqy#l9WI7jg~77xr8zzL0U;r=a*6iZA3HiZ9j0;2l0TTlVss>!TEQdT1=tCEz}Ny;iEWwnyBYDrnW zq^x36Rx>G!L&_qNvRI@n8YzoM$|8bJk?Bv7=}(dAPm$?Qk?Bv7=}(dAPm$?Qk?Bv7 z=}(dAPm$?Qk?Bv7=}(dAPm$>t%k+z7`o%K+VwrxiOutyBUo6uvmgyJE^owQs#WMY3 znSQZMzgVVUEYmNR>6gg#OJw>bGW`;neu+%KM5bRN(=UWcnpC{SujeiA=vl zre7k{FOlh&%JfTR`lT}cQkj0KOutm7Unr850enSQBEzf`7QD$_5O z=`WJ$FOummlIbs!=`WJ$FOummlIbs!=`WJ$FOummlIbs!=`WJ$FOummlIbs!>6gj$ z%VhdxGW{}{ewj?aOr~EZ(=U_hm&x?YWcp*M*_@CLrU~WerqrB-M{CCbzVvZp$(l7RqZG zpSpGCj+E_7nk*^nGopKke};5tO6rkxxTM*VvTyP}3K~-OO;QRDQm%CgCNV-_kN=ezDm|m5nT$9ipl(a_Db&@_PX|1FiByEs%i=4TEiO1eSP21&O_x>eH0CEX_J z4oUY&x>wSDl0Gl#K}lbd^pK>lO4=;xVM&ij`nII4k{*-vgrx6D8j`e2(y*i-NlJk# z+Fw$aqxuThdlZk4bt$()T0{N!lf8SkjLqNh>8?A!(JQ_edI)v_{f(l0GPDt)v?yZIE<}q+2C@ zT+(fl?vQkkqnkxjlXdlw$!9d4^7VTfNg~hs|w%vXONArh@*><+tCdO%)cY z35M@!ts~KuYxs;&!sn&1793G}YpLepm*eJk1&e8ixUFeJxWMZvg}bDrG#EaUw;`PG z4Tk?4)Cc-sdD_YU@_PL8uFx4T@2-5Nuc1%KYwm9(8fi^yZ`X3X&5zx`*^zL#WXZ5D z?fMyA+80a8vqBzw<5QcTn&*71I`MEz;@~$fa85ovBjm6@R-JYGAD{YVQ%Ruo_RR%J z_}bl#Lx%b7Vg2UPfS#9al=>@Q@X9aqXxV>mhUKWY@&)Gim+iwUvI3) zxP0c=YqZ3^&TEov?!*fm{q+m=0rm`ipgu?+Y|qq(*oNuaxaD`v}YaWsJuG@!2d z7*QKX0|#N)VD8W4J6FqBmfW#)S%?=6^oaoncOfS=;S6<8dT-iRdy%ad)#TZbC zzzC!{&Gk69X^ca30Skec-XmKwu0`3t3KTydJgoe(E&RBhQ~Va-+R85o2m6Eq#cw`5 zto(f7$9QrZ8R1s}Kk`$+HP+3_0jl_w;o8b?9{73TM}FK}sr;?NHN;sZhybpACMpN0 zN-KV!>4AK@ubX&`Z;CE6FdJJbmN^wpBGYBLm^Y*wfo-TX=2?MCSGg6n`hW8K%(K54 zqw+yYTgBLYs!P~VBu65dZkE@C*x23K9x^V=$UdyzGc)fs>urQ`fHE%owF0`SY~uaw zvpnO{2daSKMalt6_w_)==QY3K@)b}8^us<_OmETm+LVM@xU5WlHRX=7J7}~Q{fr9s z$h=FK{VlIpQUTMv^76$imj~b@Wl!v@E#@~>kYF~FlkWMX=zNyB`%X^Y=d(YVFmZB^&n@PD z0}z?Jd2TW1?fUzjMuTI`o(qi>Bk}O{OE_;9VE)`*eOvk0GVLv1!^Sr#s{7*1gj^%v zm~13;-fZVQSdiJb+0~&r3TI9>MjP)o_YdnA(|<bo`Rra}d$q~K zHK+2K%s`^i*BIXP*zM`hn(y223$mjPo_vG54=|JLt5(~8*1v*ET*Q3`wlKwWt@r?} zKP5x+sEDAvuOK=HUTdC$^Qq2#qGR33P8T=P-C5duGu>yUuk@mR*{zhSko}wOqd>`h z$^)z1ufbSIgCExp@@&P&wKUIRY`il1^TYW44pd5L=2C@^OFkok3h15yWPJ7+&NJd+2CfMV&lgwbAKj+dhp3HAB+=oz@Xk_LdEZgO z=^`?5$Y5B0%LydrRY>uC*p0;u=P%9=m@34)!8)+P;Q{ULtYsg=QF(==m>1MMu()E$ z?LGT0&ZHjC1DUKK%RE5)rOD4Yuhy~>44085-hZ2ssWnf2AuFKeeAt}hpZo%E;8?KA zWR5olEFbn7YaQknKtIjB1e1+lP3?Km{sKq*nPy9aby+C`X9Q zAIE9D{G+a96#Nw^e#)(=)&G-_f84itRAR_2-9oMiKQ$|w5xRRXTgkWKh(h_sd0YYc zWGM%zlvk!mu*fUf{UM`xrNMr8$x`0N@#@B(2lU+M#H8gZF%#=;$qpD1kdR1}e}6kkdl%5k~S zq+GdK)@N$eE|eDtX4!3E#6B1KCWdljz1E-Mh{UxH_wU1{o9j#3o15!2Gqs+q)268H zdJo~T$ zTP7aF*yjj1-x|z^I3Az^HR^ouu*xt#H)0;6meL(~|s`uBzmW4@yBx39Taw(izknt7h|vgn>LDovnL zEXGT{OCUN-nSsm*8G(jZG6L_AO`76~!g+Ogc|AXWk2Vc}h)kdkFZ4{~9&LCkB*U;( zb3ZtS}ujt#aA2^)5XQ|3`82Xpwhw8qRzN8=U#!FxhDv);ScadlrK-O!+S$(ye2@2JU%41&SYa`c{6!!OsIf@?*XjkMuSmL`@}#fW!Fj ziM(?m6SP-Xpz=g&m3MrOp9atK>D*pIhOSb~KoviWm$4C4)@T&E)4B0pmVslP@^M%+x@d2&3}+vqj_r!La4kCAtRmDhG8ZmiRURFu z(daR&HIXiLY0MATXe>i_x-<5D>dvN-I>kG@lRuXHo!IklKkhRdH%9(eK69b5c~Ad9 zQj<1jP>VJka(Edeu!jf#Nq49#(!=pF?Kz9U`-9n;iCn%r`H^zv6cjTvmQJpF?JI z4zbE?%HoL@ekv{MzYs41(-3e^#1+jG<6C7mZK8T2v-xh^>~8p3yu_u-4;{TBv!VL8 zfT}&yi!wVlJP~r#d{5SlVY)w#%*LZ<(S987l-a{gM&h4*a)B(P2S}OC=hzBFIuOEY zw8aQ*<;ksdywp}Wy%8?j^U3W(#IefRqI1aY z__g-ABO{YiJK~6r+1``cc^~Who_P~{Y-=1e8#iXH{SRFS zzF1(|)S@jT?HaRcHhp_f`hK3)%v>`lIG5~ooJ00N zjk4UT=ipk{Dt~I=o(EK*_|XQ*%8zGOd*DZYoD&$2Gyt@&nGeI=lQlDCbQR(%Pc!ED$# zxx4fIgnx4E)avJUX)Dr=RKxz{D8s(NJZ0Ts1e>Pdl=WeTy^*@+9R>DUN3(i&!rssq z_l92J`xAemKBI?v=i#cdLAi&E(K{EUY;!=B(LcXW%ot`{eO9{XMcryKl<(iCJigk} zMry>4fuB|0&4avSyHMUS4w3RMULFVG$9M`9zj%2Z=%GAr0HgVe8K~kHFOREwD39L* zkDkb555`ZGC0!*aNv-mj&-awA0A(BVN4dhfLr?^$!}xN<6+7oxykq8~|I6~2W1Tt- zkEL*|7p{dB&^=i>K<)kscYdLZU}qXAAW1mgM3aYP}@SC(92R^+=vi%I&!g{|@s3 zLS&6T0JF`UC3u_bsx6LGqt3{Aqdss!An)m*Ve51y4g7;&`-y8nv*QamgtGNV1!>Jb z<4a-3CFWb&Gcp~Wy5m%fhVQz#yszNfFnHVRn{VR!v5x!f^h*K{E$6Kk&GVl4a!zc_ z`as&=!A)NcJLb@WB*XZkpVyUFAvbfk@5wZ@_4S6MUa!p%?`UhGcY<2uru!dws@CB; zoMGIwBp>gZW#OH(HPti9>z?Z8^mXn*jKLK+s4uiVXbTOpxkqcEr-E8m-_C$LsXnzn zrQTNmT6p5t`9>qYX~TGr){Maa=9(J~y>z4?N$K3&WCOUo}iY>5{d4>zSWrf$Z& z=X>J*zctzTd3l)m_)_)*7GwOA2cA%m+og8RteLOFV1Nk>5}{<2A2%@8I@~ zkSEo?aj&6;`cyj_oq1Uyr`_J^vimQ*r?on2{O3U%{@1R(&N%5Rc=xJhVOJtJIgN`9Zyw|8Vf_o8Eg2y_)w$jm z`pep%;tS62%)Hjvcc9!zXwoNTglzVN`iuiMT-DeU>wTdQs_l)B4%Wu{PIXqN;s5@c zqv6S|=mT>-Mq1V)<7-BZ;cV4AZ7Io}u4LUv`$F2-^rJiQr!Qzk!g%BbdE}`8|g3er>xgb%~JuVoUuy*uz?<9LT|Bj!bj-B;$kVBE0D8&}EK^j`G zYfT2;>eND^HI7Z`hTCxDrmS<+X(JO=Y|$%LcfG&Mu^D%yrW?M{JG=)iess-6>m0e- zNIlC@_ouev+4hYr%U**eNvhLA-wrx9J9CGHoVH(~7eRXIj`eJLE%e|T_604pZjBfH zYJ#^YWOF?f_ImI=sy4@F`^NOZLpUuW-EidTmuf>D^=aG5v&nGQbTMVhT+s#xPmWsaeDt+&+QAYd+t7w`6di>N zud5-(&pWgv$HQzL=J(regClj5RA=US*>1-s=Gu+=oG$Zy#Tr%nx3{zREJkX7Si@FZ zU_6f8To_0TMs8t=BPT6Uau%RFKfuW@X)ZAuUP+W;5(#T3I)_p?7}`sm{e zOj$i@b=QqMJwtCeUW9MtnSR$Dw{H~pBIk`kwjsWhekpvsY1`R)mk4R)s_*+G>kD6| z3ws4ahy_{HJ2Ry5#)uwMaYWelulO)WX1Hf z@%NKJw4@>bg#?VBIQ7vmcTHfGrBwXBr-`NsXnJchO@LDoXx zS(Z70HIV!p4l(cT(^%=H0EoWU!jOyl1?LK3cp<2GKC8Z&?5i@bh^~Q7U_QvlG*2b?sJ#u&2 zc;7X?Q_obJvOP|+$FvqC`#dGtUwl@!R!TqPFj}ir$n>dZzD0{M-`XjN<%ua65nnSp z+n9gV23q#&uGzaI?SP(msGarvi(o<{$NV>g$xqs{2GzNY!S#cT`Nl8X82aO&?&$~D zFWT(;Dc3G;hQu8Pi96PmxOK;p8d{9Jq{L9FKI2{I@~KHfi~+`so0BjHLjKu1TiAM; zwTykwFzFNT)-g@IH!sFAQu+5FM+0-QE2v}LG+xgTxfry5zERa?-@FkmeZ4XL zbkgoaZC}Ly49bj!iEL<#ppO^tjEscfOI;Hg?3Sf?GSTay}&H zPaQemus@-(pP_r^8(PlvuK(Q0_I}_*vNp(g0}?SUwNDG@JXf=0bGoRl7s4*jpx~L) zk3Xk;Y?}wcB5=!dtg+ZUUL2FhTF6U}i*mU!tmE5_`<}a_z)`;d_4@LDXM^Km)){Ax zYRc;5Gp8%Nsh6&u)_VEYak?&?t4}y{x^e&Wor$U0_%df=@&$7o55HrKdH20l&iayL zDVzGvrIa1e_KrdRj)!ZIX8!*BjN35hGB4~0+Biqufe)5EiBgf+9(gUCanOA7kTAsgme;62o;Wk`+oESKdja3qyeZNC#$)&M?1{&!vyHw; z2YZ?|c=iwnQ7e7($~z%9Z{lT>E}uLlzhFk;OtIaJ`W2UyE;7&C&0ex{@#0aY{=@pt zqDKrs^REhIMvAA#b+7Zj#BV07bKGx#02cEx@33=UTae!nlbhuikjU6LtN0dX8RY=?6*+L|u$khn9wy z^QdE?Z6V_jsqwiQNS#a~kgx-2?Q@D>5&W(EJmAOs$&dFce#N-9@_UJ4==TZ~KiWE3 z`DKG&EBwfhd=)>I&C2f(cy*V*6^Li$=Rzb^UaSiv{2q+s*9v}2LxIZQI(S(5Wmx#J zI4XaS;+pwWdcy^H_#<>#@FOUGO}Mtk3!Ed~&t*K?coM1*&ud0VvhPz1F`BAMZJkwUmcozO`+Zo}P-zb!%CV8-8TaWlL!(y(TDmBr2QkMKOo1dgaE z@JulF;V8I8dfYRbz!4J#ey=n(eyq!mlMA3Ld20+RaW%y_6#&KeeoJ`e3%g^IQXGrVJXq^!k zmRGJ^A1rY)G%i1mwp33xK4nBprlqPxmxQua@*}NjZLO196rUDfsRMWqf9c z^itB1cm^zKrSz|p^m$1qVVp7kV$w1A_KtLO{E;sQ5A(_KWgBO<=a6jkd>}XIJSI6_ zh7U9QV8o^#ZmuEue)3Ugxc~mQ_B`ZBs82jx%BKO>@oB*Kt4qrV7+ThVus%4k-cf(C z;i~^#_{7tF*9VO$Prnt$+B)N=DmzY5wTI3mr9WL7=-ZkVfPdPcDtDotcYReqXYv~* zfh_+Qhv=7;`n8-tzwL{h=K6=`sn}JMci;8esDE#9HQXdL+#^Q$uy6lj)hotbnN>O3 z$=TJvJCPo`3*Y7Ho!>VioMu=!PSwx;b(h{G%RLOAAlzf)e2er^!p9TmKS;ko`t;Qk z#MOTxH~*=$#I_c-Fkb-q?oIakbIpITt$q-&o?<8@24$n_Zi= z(c5t9Z#q&+H^lxg56_fDTc#R|ktY}O#2h`-J`g+dRAY6QZTCRvyYLCOwFzQho=|sj zaH?^-E!CLS<+^Jj?n#sPG`4@eiu%;HHM2r`QmWC_wg918q?F%6_^glvA?>*PI#~lu z?Hldj7V;&189lhFeb6?Rif$)LqGv5-XqR@^ArVVYdQ$MQfzQvF3#4_V-QDqk+ukwT z{bZ-t{q?F;<0oxQD-Cg)+U$j?2K&C4jPT^@TqfWbU4Qq5L%%FM+2DI8H)u)eX)oEb%uX z&NYQoja%CkFYfY9E~(Xno*Wv$PCcp4=uPh+)*Ul{Uw>E1z zX4{&n9BCOEP;s@K6D`johts>J@4BY&RoDhX3`M}*c_#1DoCgm)**Vg#Wg!(?-%ek$ zvp&agJZi67cVOhDv$_^k{N9*~x7TaKTI;UP9Q~S6(~tb_gdY0NmEXDY%5uL6H{N)q z311Q*9Z@n;U7jmEsq0{I)BD=$el4TWYO}hwR-}z64m^M~^(opYcc<gr+2-+6LprTh5j0}H@@28PTo>jhFX38xO;5d z(NSHKD}K|ybJm2vTsY4)_Vn9F+n=08Ke}IOAK0ZW{YCSI&$7q3Mu7WLU+9Wz=cZ9z z{=51$=~JBR^-1;sEng?0;5_6L(z_o|2{=WWDn#LsFxAvzEQHc^5`PFm-$L zs8BGeu|2j`*+fEK}{Lvy= zS9hJ*W#0Mwc8o9MSI{3j@)GJ_F$O)E6&P4`-OUR!o0^IPsH-W({=rplJX6rG?AuH! z^CxqB*D=R-0Ko|we0+sglE6tw>QoxwAbrbYGc39;<)@tA@46bs*U?~i~Z3)-$M?AZj`A3 zGiKSbQC)i~sztp!^3bwd6YB43=YVxK43#>#-#4qf*t6bg9($an8;Elz*bBagzUN52 zDO%#-z3n#d3oS1iKWk^14z`=}AbsaGg)bdXX!IEa1KNf>Ll;`%gho8aa%BQW**!G znOTgsy|vjKZJ7tvoqYP0F03Ys&_X}n!4^WxrJ#*+gq%!H+N7;#FHH$2c}k6CI4l1; zwyGGn1!$>aII?{7V~po~G_M?|er* zf1lpfv@319y(2j>sq@SfpK%dR>ox0!b>7wT{Wg1JS)qRA;Ah>a|#v`V%QHdyE9k;$EN0!;PJf4ZD7amH^$66T2y#g@m(DlJQnR3igKFpK*C< z)x~lRtY9D3>D}s4XQb5HZTUiTYWt>1ZjyRb>Kqh!aWNzIto?bfANs|=@_dsF6$zBr z=hC-cD#GM@_5~@Pt5cE-UMBsPTTuKk!)e%N zMnLhq13p%M(=7aOON8HAT$7&-NVpk+!_7?58Ix2dGMm_gQs_m5BFjH}R}xVDNCLnbL40?HXyz$o#QB znKvuHiHHz_p8}Pxaw}@}?+u+KieUlsY^)zed>rCTFZq5CeC63$s*>U6{h1awh0_9y zo8dpQxEcNu^cW_X_aCyj8BQIE3RhR8)QQIC*E}DZW6A{88%-DOOJn1^gq9FpK>~Yp z6sWU|jn5t$1?nh;@QrvSi~d9>R3_*vW;ol|1opHj*hSB?x>H4;V4G4_@EwL|SUdqaqf~hcSW50pW@u>;@s=w-0?ccXkRh&yE`uaez;jaFOc@QFU5tw z8s|O&H{(+_Q3rZVx-S)Ow8yG)G3!LkcT21@2~>xc$p)@vm}M3(HWi7brHgSS1-?SF zbfxeSmu6V$in}Vy7FMoUws4^aRU@>I&_XU=T3WogY$49`E?v0{--M{bhapOEx2f91 zJ08W0$T)J+x5-O~ijVnE&_-9b{!xee02g%pWGkC~enRbzV2tH-=-N{`=<44OhCqQ~q9DMCHw&Xdny z^8mDp&U#zK*7>!X=WwD^{Zo%R+=t%`FY@xc8Z)5Xdh0?t^?mEo>o2J9w?5g}XB@%)lJ-3}uBGMk z4QmSw8!Vq;9T~hn?11faxaClX&3=*bXxcwDU9dTQ6Re+udhWnN=jc*@`uYp%v{U)qXTm2Q*%A8F>*DdZr<_80wS{bvZ-3)c@s9&0pJ z4|lg082KTG&YG)h=YN5bGvc9k=jJrpNM@Thk_&5`^#!7KgYEetUBoUh?w0Yjv8%gQ z?)HpW*8b14`_w&8W+Ltjpf{ zHty3pKU(YD{8}PX?i^iHl<4amS)(jtopo97I5#6s7PTiS^;)C8e!#^E_1vdvp|95H zjoPE>&?fmp$JgGTsfCu;j5dn!4HfR4Tum=`XbB_7Y9|-gK&MeZZW~@?4t=dAsUtzR zUosH8&KY6H`1@!6r6pnGc5TGF$5&Mw+OQYrr9A3$EpBD)Q1jWmHb0c6 z7Z`tS%MbZvU39g5N0$5BYn=^FuP5ZxnrV0Jb=F$#j{mS$gKmX(#=g+cf~*OBy%u^o zsDtm&wKmv1ez>L&-VNSySG={`yzo%(tgu7ayM(E`ulI}ayI;1q7D7yhik4y|M&qceG}I?VRP4v*6_&I7~AID z+<#6VSjAlwNUe9|R%NBtC)TpBF(&4UVJUSN8f=N_U0>KeG!(Syb!>~(U03YZpgq?@ zKdfep1lO=dylWt$N9MH`LXIlv2OIXpS|9AM`w8pscR_uy{%%|2Y)Ch3(3zOIdb$09 z#FUL%=i)WLOw>C6ZOvTd`PDT}p<{Q}y%0|G3<^GWJU4>+<%V`v9~lWN<|~o2ghuq1+D7yrO7iserRYD} zsU5IT)f;bgPJ6@b#gk#f%O3oAQ#SJD8+nUyH0-L~ZdiLT?0y{=S#nk*dT^1Y2Ty9T z_TMqa3DJMG@3Ozf_F(N)0PlY!Mr@WH_1dW0@jlT7^{&RjO|DJ021+KjwtWk=qd(eV z7%v^OHAF{?7MfPgxV8qDcrOLBCT#ewJM3uai&+)Ar0bADOf!a=Px8`wIOZq1Jmf10W4>msrz2zCN%H@n_Uv?(G z;m!I|ecwjd3BUj3U5_6}Pr=oWyS{ha%I%>R`qyJ~_ZD--V6FpJcYU<| zxo}GBkS=ZR>aGvA_un-PBfF^@?HRN`Ji)-4!hdb~xE*hXGyTrS*NdkL`_DJS!z+{h zbGw3NJ|nq!XZV)Z6k~45PhmCrkpCL-#Z3q7CVg_okam+3?XVhOkeKiW>zY7%}Q8b5Oz!pA2Z)s$@(?9oo!7FPTg1&9}#xT zl#Jt!vA)lo9>3o#$p^>1llnG(>0z_gUXJOVtD!kf-}De9E#7yDyxHIsdg3#ur|x&g zz54|ISp~;mPn>bMC^7#HXTu)8SK>9_D{+krvQp(oT~iCpJ=B0pA{~)!^%Sw{?}PKIPFfr=Qzjk$JynN{)=DUA1RUe|LY8sF?)(e`mke znDVGr%X)A=!q6Y=cj4(xHR|Zh=|}cEzl$|(y6u1aj1}p~>u&vXU09OJROB@ACNCuuu=l(pDFWu_g3sPE>?Az_8w*5Mj+-@q} zGXz)jkJnaR`lqNP$Bz9@({LDj_81#u=?za)^Bu98^3rfQ)}DCM6e`0_KWHZ={vF#B zv#k|4(I)Cyvy3ZG%B7Q~`otBBAk;vWAOae|k1{}kN-JKM{VL)$sYswI9;vDm24~|& ze#@S92-S*6m)Fc2(v83o=vNLzTv2`&FL9~Tp`$l+*(inu93r3ZMtsa~*KCO-YKAwf zN=6QN|JxQf%Ql%6E5Ho*S=A@kzG*;KC&w~% z*YUdO>!Q&`+Be6!7sa_NoB5~gpl79CUvju>$KTCEa?$a$k>Sxh75mQQV(^!9!;Anb-h@8?*tK}OIPmV688KNPmKq!(kXkPef&VRlvs4&Ij`={iyfmd%n1 zTiGnUb0EX7bt8PZru~K#_c_q-NK;6mYv!{%>Y8sP9f|W1Nwdu{%5o!1nr*ZxzlI<` z!i~e2*!~fnG29F2hRzl`;fWtlC*1Sz0!+r70Ep;>m2K;{VB7lao@xWH#~TUtNr&Hp z-j^1x)B$e~C#U@qZY|4JPYYM*rt0nWu(I&O{=$i4v_lW9@ro5M-+6u@I0E)X>w|A% zHJe~K3@2a{@0WATJ-K?{YLm7iwoVXKP6MI z)i;W;yYat9U#7n(T+@-G86sD|(YeR)JY8gbMbuD1ro(u@@o&QRN6S9hGC}Zq4Y8Q2eY}D9_5WC1I%H%{+OF&aBZoV_H?wO` zSzQ0W?f`fW2T+9qACJ`whA`+#R>f{Sb9?Fq-;7=ilv_x4eV z?Qe_-1rug=1utuEzZ~^XYhJVd^V`23poaR}Yi5S@gd2=iZGXZW@BUqjp?7~`jk3Oa z0TzLSg7e$H9+(+&AXaJHaB!go?_2HK7}o)P_@5E~&ESQhv;-}5q*@y@z3aVQ+NJjI zCAR95`aV0^@3?$#ffg!Qqgr}K=E)ZOBigv>T}O6lI88;X=QDxfyPkO`6`a$uW_Gz& zI_h_{d#`YyeeE5Ej;{x9Fh+_T*pP!^Z3!}-hIkEeHm_d~+>!&E;n4Us+R*C_=lZXr zgjs6_7+Fm>;HgfZrmyDwwM83~5b9@l@m<%6{crhRzA@CSVH z{W|#Z4lVn5OEbRt&arV6d_;eK#MSs;gLbA(ZPxJgNUQ(hahn(sRc(7wGTMNTMcd3o zjox5vKVAqcJobjwT?xBSB-k4V9R6b1kvSAPO^Q7hgO$@Z*6EhP(A& z(2ItOR4L6ft1(vQ=#x~ga0Zj{M=@@+hxN?~8}(cr)~H%my8nY?D5t#-EKeT^(kk@8 zVA`a*M1J6JPpre6O(^nR>U-esOO^h*0w+-ck75+}n_PM&O;dYo-{S+lZo zHA|!NvIl)KXpC(}?n9@7X5Z7q8}1xwOLy2BFP5nVj&YpZ>rLBI5A9L|Ht9MQ<0_^t zawP1QQ$`G-MUT4W?{*?QFz zi8Bx1hW0&x(MBCwLS07CEd3AK4h-h_V-Gx#rj4+R_SpBVewpH|M%+}4xQgZ<79=%u z#C3=fM+;Ndb-QK6Ws2Hnxo7QK(`J9<=f}-?iet*GlXg)~kqiI+b~DrrIdl5A`}boU z+7euspE=#W|BHbEIE!X=*U_CvkK=q4ocpmq;9UROapZXGYZx!u_~~6sc4&=PNSXHB z_BrkJXZWf16V9QBpKxCCM#5$dI?&g|=`N$7kEDGoPBhq0>0p1PQ*dK`J9mz5Q}dw7 zgQa^_v;%Xi3BBVw+?T!e-`mWRukLc~=2cCB_Up@@c5Uvv%^Yh5nNIXv&yJdcGhL^5 zUH0^`!TO~3whLj48*JI`T>btxb|*FtG%lF4sen&G9gTxUo2u4f4##2C;@N^22l;~A zU$)y&Qd|8I==1wNVb=Zo!rJxs|3__H4`N;2t-ftW$~v2^St!`%ihujR>ZZCa#wO2; zzW(=Q<9cVeMy{r>MX6_+>YVLO9blA0oSo~0Ns~+#e}`uSupcSFmQuhN{9C;7cpdvV zY__pI6nZ1Z!*)=c1>_!_`Zz)tZeqVup!iWoZRO{J4vhOY^5eaV-&b*M!&QLGok16u%X?w(^?>e%Mk*K=G@DkCmU-!VkAZ_H6Tua!~)ocr4FOpj9_mh`sSd_$g3n@jk0AuL|*A zP?11YJZl*k?1eJ2Cw8tr7;gQs8-5lqajDXwqc?Pe=5|}9;t;yi#mb2k7=BA6Q8Rp+ zY9txX@7$VThG(lrkl_<8Zt7;OcCO@awR2_o^O1&&+$h*ncNm*r^BmPNB9wn>w3r^$ z9md9YiSkjuVFG(V6uNsiKN`yRPZsw_{gQ>f9o@r#v~y+t)94`}R@2#?oh#Kntlont zGj)aI%p1i&`SAIa0=n~+1C;Ko(eY10Y4Z|Bt;dfsd*>+rM*XGBcUUG7y%K1Q@bF zAOQvv5S7Xh!i7Q=Tx;EkY=#yw6+~KXGYP@Ewvb`Xfa1~?2!uuL$5KtIwzaMHpD4Ca zpwgBkmY_}`n)unz{GaFEduHwoK~lf8wSGPGyYt?&-1nS&miL@{&bz4mw?ifAQTm5N z{{SJ<{X&mFLWpwwjSzTUHbCT)O9(vqgh+oCA<}IlM1DWf!&Saryr%^ufcd!yk$$Z1 zR|xUkTpix8Ll?#=!*dCNZ#>~pv=iZQv zsdr0+5Ab>Q{t-h+D6M&`xj&xe&x1RLUxI70xzlt;o(D|5a0MiWkC!JvJ0!mtw;n(n zcm&VXb-NFIq-impwVNp{Rhky#FR44d!Ew z;A|bT$zApAtXHwS=yKYQ4?4M{)rELhBKZZ$@#+G{>yR~W=*RTggD1kZMQxZ1cZ<}- zlDo6{xM{4T#pJY&c)g=ykNS*7Iya+Y3u?oj&oU;~yHQ5yHFU&5PMK5O>*_pguj!Ll;DSS9736?tpw$QtbJ;4&YtIB7kpKuMmS+Sn~7I}CJ zzZ<%n7Zydog*p5d0qrdUifQbd;I}ls#aEHD95@yuwccFr4%jw1svv8g_XxC$Gu7=y z9EStdG+(n_2EI&l)fSyw)E&5a)*zJYChSjAXDVwJJfeBfJq>ldZa>R(HmYV1)G+0c zDt91v=U=wprHr5mP8b*wVSDcDm5feCC>bAHOFzpd@};A6+mn8_ZY zK|4+Du^hjqjDaY*9I!t@EUC7A;OMrs+EB(o1;@SrUFkkjbFK7S-c4|_HcZ&@wO5?@ zYk~<2ZdKzc_kho=Vok`8Z<z3S4-NXP(?%WvpPzY+bG5wQQE6Kfw|YPm-^Z@M zPgWz}Dkpu2`j$RDG^O!};Cz;bBz2f>Hno(Qq?XAhhQwxnaMZdcuF<~90{(E;U6IEL zzW5bctUtT|J7|G@id>lh&DpolCb#%D6|YIh``#)0mf^+LHFiix3|CC87E|5X_bTja z&7M5PdSETE4kvwZ+ip2<6nx)-ayf7lXyJx(dxSo1`TaNfEubL zXs8x7Kn>LotC&TrYrVX*?XeoUs<+D1J^`i1sUZ4T9?C6rn%lt(IT+(2Kcc5j`k)&7 z-hV&|8&E>-J@>6c8ab(L_fFy^R^&1Jjb@JVn;WUYy>X|| z;NDpl-x_p!#yg?IJ-7Ndkesk#)Mf8^_moAQt+f3KeuFK5p67>sk-bt1jwy2oYG#m@ zkt&BN@?3DB-wk>;AP^5349sDHx3TlOdY3!UdsDA2Xy2cZHa>9cAnXOVe`l9#q&u)_ zmiOHHGL7!p^GVOV=N>Ejbh`JYof^$+ZYBkNJVhE++V0rp8s)BfVAkLhn4=swlZsy9 z8l_XwvCvDcQg+NwmS`&4Zzod@QK|Z0kCUoD8=~r@y3)Cna(n*KQ}F@!787(Hy;bH2 zWI(?WYQk#Du#FtD-o0)fQZ<4%ymwVEHLhQw7S8&4AK_AlR-+vE@z7BO&G$Y>6?B}8 zGmRaDwC;67)~6Q{%TJIxscJ6pTU%sjYPD^oI=`&TC@O9L%g)G|^*}Y-I(O&qq31%Z zS*QmiWmji=^&u%IuK_*M=6OqP`wX=GmyB)S+5Y|^<8!5LYjk{DBJh>At*J{q8+9U<)lX ze6>8jDh{(#5_p@P(3a!aB#kt+$PVWTtZLE!#0rH@ zwyPZ4b*IjsqSdvEXtUZy+RHg0Tu4a2pp5<59K4#P#X}}{w zE18Kqv=(}&*5l&M?TLrgL**O3}{OUkDJoAUV1xR z(G(dTqlYIpna16qk8Dzs()QssC!%WU{q0&?#zf)x%XZOko{rk6VHO@9YVRR&ckwGj@AAa=2)Dv+95&K2fQ4e?aTIy zkeDiJPhY$r>#-`0rw4kCb_yv6RJ`j#uUXPjjLC(~j?Qb4De{@Z1zrV(wUlG-s zf7_N@mx7YXSwCcaM30fsT{(~8-XR-#JtIb1<>qdEf+-j~H(a!tDx}>xH zmV=SKymH%sE!tZ>1sPYam2X|~wX{##+iR^G?Q6UR*3|>Bif=s-`P997O(dOiRFSHa zqQAU9GR*?LjPV6q8<-ChZs1-X0J5A7RltIf#g?19LhY94Zv z-c#o&j@9g$=754V&TfqD)D@(DQrUnft|nb%fqoa??C@t)spYu(Lt5V5|QlDqSf z#<$bbj|HZ>kHz`#$hyCYqaJHE^l#Tet;aJ2`#fwhV9VQ|r`*&u^mNlw=W6?gxYcY) zv)=|Dhm8I5mrR#SIRpF$Yi}+XnVyp#oAX%5;@OXN-0Ak7+X&rb_gOtk(v0$t%|rgs z|D~2EWyndIo^F{8yGtHZ>v4j3$boaMe5XN3qEQXT%DT2^ht%OJ22L(lKiF-Nrg85q7yb%|C-GoSIL^{ z6H)))g-*x;TeKefC~Cm!e5Mieb7%rJPYG_>F4AYUYnN%i*{xTP5ko+rY#%SRP8joPUq!jkKy1TmioX%^R@c zioyWWnjrbhbT2o0@@OmQF3)2fOWbMI>zj!^71)p1k`H4==ik@Jb-&5HrXkL63-Fok zjrJ|0ilGS%@*KCWu&;jc!^Jh&F&h6#d-03dgTQKOt`SCrn-C`3V>r4)!~RhO=s5q(dmeTZWu1okBg;a-!bOPev*y; zAslhg@hlWa3?XL$pF0oLd4A3BR$ff2;4%T03X!fWd_UCF0jTaeq+2aKfFj=~ac_K&Ot*H%$$H_bFVpdT_TfU?mH?>k6!7H> z4ayzlb5c5dQ+Yw(i8}(Y#&pFNlbcX_%)z#jQ^eR0MZZs1Z@HfiALdgUrb*@N{Z8# zkdos3B&4L~&%3i^F;#47W&r42@Xe6dXcZtNQ>$y^ns?Wd<(Nlx!6#%H7M?Q5R_Xe+ zLQ+=?OXe-Ued*Fg3%>Nbvsaq@?XG&0J}cVw^<*mT>w-L_3r!A& zEYER3KG&whuYh3C{|mxwltYJS_3-b;Yw?G5ct(fGs7OBN(IIIJ@z19p?|GPTj3jjs zqP(AA;4=M#=wyU%=+KUdgZ^9{-a?ooN#7+L1HK16yiSLGK%1DJG)t{FLcW*oKdHl0 zI?M)tBGW%Zh;oot$$45|9|Yo1$bJAgn-CM58lS2456X@)T!#NTLdj`~riEkm!O+D7Ipl}K8LQ6R<$Eo9pU+<6%sUHiy9n7g0Y$!A| z*r3a4L)Td*z1v@hfOf&7?UtEN1J|7X>^5;*}nT3B=5 zbMsfRj!|DB8w#vnT2VmVs`YHTWUO+%rccIDle=bO&nhDU@`JO2X1l<)t?V1t-f!6< zud%5d`2lDqJGJsOPTg)>De7ooNZ);`Z6d~(1s2g!bK^{x?<`;qjjgA? zdr`kP9um*}MVBYjur6BpS74o9F_2PIzF1gV;5h1A_)N&wLOyi zr)D6P#hs<59bGt9nbjo9$}%1)XH834@vXD%&K1e3wT0j8)l29Km+((0;d`MHO4&yn z_?&n`%4uxiSz>n0=)%{V`_CBrQNNB0Xpw`GjV#G!Cro2dZkK6dX(!*Vv#NZBpB%HPjfR?JW!IB1S4FWc)l6m##=q z9wL6oFn%BSUBFMwLz}cbA3~U24@+xeiDZk2e#iHwNR+{$XPu)w&4%R^T$(-)&r?zMr5NjcOjU{ZD|D zPTY<9pyZ@yCF>$V8P#YmObFQ%DQzp+&G5y|W>ss~yg_ntd?hJ@_w3p-jV8qTNdY+e zud9yrL%MDK)VAOP*c9Fai@CUR_uLGvdFXYLX~mPRISDVeUIhxJK(cjE@HmIR5_UQ(Mf5{m_rirok2F}<-=qW-Yrye1PH5^sIe9wf*jsT`lv_28mqz@t z-gH@9C3-n}>|fO$+t6&wIn`j#c)i)0bF#sf@vA5qP>oBc-Z$z%OxwvNFMe?HE-83b zxhcm~Z^?PJ!IXDw-=1d7C&B$bTAX;<7fv<0+`8WJI7t*zNt6y8= zSaE(|+LpLm$}Mf%SmS6mL)+D)-7)x|xZ4bTGVtXApV`^mBx*jZ&3DhFX7b=IfrZ>8 zrEjq%&*HCENVQ4rQ$V?8_t(;1BIV|+@6zV~)D<|Nz1%c0u3n=`?-(ffpX;kZXMeKm zP)khAq_&yWpiLPj=cE-b55Zds?yIb7^cCm&_z$+N zux?0Dd(n+3^DVooLKaEXcfFivlTxL5Bg--d)}rkl&Xd$vM)}l9ZH2H(;tf9Ti#af^ z$O`#9tKT#cyaK^0pJhDXj`VuY2`Trt4b~@|kJB#6q_$uU%XjeLdF68!*7w>arLR`3 z>sj-x7tLDB09tE-bm?iI^>L22(zdD{w!qIjq&+-2AU6NObOk-tYu*^UDJEct)aMTC z__su#OopyKrhMR3HO`!O)L0W5RlYCFI(O05Cd#tULK~4&2))7o zJbIW|LvO0TRpFaRBRAInoN07RDHi|r&EK%y7tYc5^XA0O=8cYw+tXNA34yK3ODXYZ zpC0ny)a=^$vrlDvl}EnJm>Zg8PifojyALUM(4vZSelutLjXOsdcDDcS5G*Hc99|5~ z1Y0w7n<}uTl*bwGdpn`s&d*+D!|dJJ-uoa&yBNt_XWCA2G?_BK*%&VWq_%ZC7OCMp zrJmpDtg;3+rOYUhhVNqXxiw3B@gJ@UJ>wW9St+FAisx3c#oblBZ_3hG0-8+mH|&$9F6foz;9f6`g}>>j01 zu|7_X0PogZSG}>&x(=zgD9T2~G%;JXo^p-)oRs@vgB9UNQS&Jcd-Ps9sr}~>D~cCu z3WyChTHdIBrRkDF(?s?>OM_+H5v8#?yZDu6pYo^XSgdv8_H3M5`r(b+QU3#P)G0Do zS|36d`^p316w|s)G0~7>e3vP54)FbMYZi;M&!a7u1zC&dvwYZ&h&X4uMHCv4dk{rcTeu+Fw#ose1Jl%F*E%)f>lY&a4)@yQ=@9^8F_?PyJA!SI#U5}c~#`cc7hbeZKu}u@<#CG}+J)PLa zk4}dzJ=I|wNIl!QSUR>lpE2ee-b)XkrQ{+Fw&y}F4f{eX@F2FJumc=EOPPjyBfiz> zx6DI0rlp&L%ZP8SuFHt{SQe(k_Mr4NTt<9#z?Y0L;RL?x5n#l(6Zl*RBR=90_?F<_ zi0=sSVM{RN1ir5$#E9>w27K6l4B;!qJ@JY5;pTlN{K5%*YZ1V7WAzByR$;k>V>-tF zScf7!7wL`*51_#JH13V%dky9DB8=~gR|=KyIozWUlmMvCj!H518Rkictw*K{xrs>k zO30^`joyfNh2Px=`@DD%TaW5{vwW;~md%JS2pv{AA~VDpZs7|%V|Y)TZD9-8;4~XB zuZBW28!iV!nQHOIvnxLD2{o=3Pd$Q~)1LoI=tZ@7?w1?m>kNLj&9B8^Ln{$~u}x17 zKjTjt{ERP_Hg6rj_Ju{=z{OmuPi;SfmZKI>zYi#?6 z9G@G3i_J+I#Y}&{`FD*9Z~-0qx>&N z`F|7TKOE(MJIa45%KvVZ|0DQWUmjdMJ2QpGfE=NOIKAkDmaFoUDnw$V@1j7D*y ztl7}Q&8JBS8w}#W?05K-P1AFT0*1`wXa%B_Fj$Hf8YGt0hHDZNo|EN+o)E4D9U=U+4##77(@%OL55xHuVH(c92{CDP=<&rk!(qBXR>0wC z0zwP~(h;UVMTqC$A>wq6F2Gs|bjrmx!H@<3*l(Smdgq`^b&=WR&PtxW-kN4ej z&oP&(Z|hL&!o;iU549?ZGwXA}lRY(OM7_Mjta4I+`Hbrk8G6}zsk*EVwce3vQ-(Jr zf`@weVRPVEs+5yalz2iK8GmBMps|CoM{}~ez*g_-Fb#&r`oTkBF?&rpxbM`-rjz+9zXIGe>iA>WYE>w7pNOa?l;C zpj#2Pjy6FKntCpUtt0BVgsw}(49328eZ?`|*3oY&gdFtYiYMNE>b`rnFNeLO$KLG+ ziRgUTJWBS*t;zDI_~ZSlm6`sGH4iG-!SQ@WIkz_p($J}@H1u_BP~80lVO!PkQfa0#BWQ7;u8KA^ z^M9t2Gpw@NwaHQJgp{Oa*uq?hAYUUxbM@^i5(JsCs%GlH@seZ8C!_>=Z@ zLZvtO`YKmd3M@+}K^tbvsuWmkmx9f!`aEbED`lB7T$QW-lu+ry4p@?3%Cd~DP}0`9 zD%nyNAD*&#gNYANGn^^-H($~g3+&EZs$^^XFMA79hvk~i%4pF<|5e*?AQ+romK2Z& z4;(Qou?mva)MJqrx zMCtkNQ&+h**~SbB+Dr|!b~MJdrVpf+q!CM7C3D@`<_CU?(!Jg>yH2xsG^`BuAu|Ul zn5$aYSyMp^JBurpLzb%OWQvjzYY8SwQ%=V$9Uhye#4ERTxIHNAmspR%hUL|pQ<5s5 zaXm8?yLjfgknK)a68+A~zWyII&pG|;1qqdD;84%rij$)6v2CxabYNHQs%q3(x@ky% z#kuCDqBPhGORVfu*|#!IiTTsoP+O*LNcNYurR)y3M?;0y9+cr@Sk<=)J*Tt~&A8 zei1SyKmK0Y6H8|-gS=}TN;o3ugVgG@Q5zxinz+WXI;pbHn!ansH%sZX{$qvppRaXT zzVV}0k2y9+v;O00ni2HrrOIw%4<0cp7FH%q!D1iMnPP`;!Woz(P5LmchW3H1EnX>% zL$eR$J$sfWN&Z}>i|7?XN60b0F8SPwV8G4N%n%Y4c_2&ObH2U zzg}BEs9=A!jCDaaB_FaWHH|FMV#uQ}sh9!T#F@(P8fOH(dU@+{@7C{s-N?S4H?vQ1 zvVX-;Pljde5Pt>6t?Xcq968c3w(smZ_Nqy3M{7`5vZIoHsuY?>DLXF(?JG?<$2+dt z(z;?LJ~p%Jo7gX)jwkrhD$0ruR?_^5{yzS`{;R5;mFzE9txxjzQ5>pHfL?yN-U*!m zPCxw>=H9S`m4lNRXGoIXdoH7l@@`q1GOO&f@=gp`?^V26TVcg27Ca-GydBpDbQ~{q zLK@C!Ba2knRx}l|_HJnB%?R1Z`ot$vGY1cBWDR({Q1L0VPCslmjWxHJ;wVwJwvLoM zvl5iOL^}80%Csj)&3~{rGmy5!l!s7vT&pF{qUr`%TbJoaYPWQ5eK}M0g8qO^jP1Bq zd)$!i_E4G!RSg4c%2yZmRxLV>Eb9{(oGOhjIN=(d88~$1=o7ux7bv5kg#$L79K&GU zJ9cv%EP!omb=mi$Mr6=F=tIbZ1+W~voxl7YuO<5Je&7?S@pgd`c)M{*ug51Uk1ErY z)k>{o%KND*#jn0!3Cj(}qjMwGaytTV$9(s2W+17G@AnMSJ`+ys&4hM=U>V=f0lQBV z-eQ|=PLXo+PPlS21CK%Pfj4We68rdx4$oG|$4+$RGA-;q<$0lHAPe&;>k{=eJ9xrl zXpwOZOq*4e8K{T7r?txY`SLmG+;&KMIja&vx&`7@jT4Em`IPBTgdL~EO|k0fG4l6i zoRTv(G@U>zW;Mrd47dI}^-LMNF;TVnM7_*6Lw@{OUp#C+O}v#nL<>fF&&HMs8uEHa zp-Np&0P>tAu{<+y?F`lqTlf6-cUAD6-J1soo`$?KiD(dsWcZ#Ie6B7(|`GW?%9-G-Z zPo!X0ZGXLny(_Z^dRJ*%(eBUEyXLKA`5$be78Fs>;W_UV#xL85R9wnF)1a;BgkF{0 z>O&pE7S+(|{E#iGOkW&qQDMzjbPSfKu3C82&SS7g<$^sb(BimRutPONfhDRU+M@bn zw`@_x!4}nRutmjQF$Gi^>qpfVmDVrZfy~V&a8x~4o)kd)drbLgf2$?KmYcOcb1i9w zbnXpx6q)iZ<1HBjcW5yWLK+fwFVz^)tN5m~pLIWBnk0>e-L%m!tL=@xwwmMqfD-qF zO>Ob*t*+Pu828?D`^ruE-thvX+w%SiW3Mi4TU(R$c;@E)IMs1u^qMY*wYGfNVk)%d zX0FXz&;F{F@D8;cDFIV{0P~bNZYWBb2~NGWbu4FTyQ?M=Z!vUwtc6Un$7gAZjJX{# z9v`eC9h`Z9t1)Z6C*vOfJ=Lk3lfXgq$3x4j=PSHBdMNU_Ng<5CY>bQ<8;ZFtDkduw zGZ!(ez0P*?LC!tPxBuB*aC++9@7OI^AH*nqAcMyFYO-q6%TblI<_)a>H~1*Qw`^rn zVEGQq<%d&}pqb(s7t&1ZY=7vGG}2z{$h{jjz0Q1_@^^07B880sRcD50EPXQ!cD*cE zHF34n(r}H!_0kDdV(%+kpK(!!bnxzp#W>|XR|@?sQ_c;v^bKr=#B!P<<+@G?x@yXM zN?HrLnu)cbN`*0RU-8E`BOJ{wmYNR=9|0N z+A|xMSKpGt_xbo>8aN5KGV5$t4ssnbr-5s>Tk2iZv*ERjY3!e_*q)ZAMN2u4B0BI*PaJY+rD| z<-ew2CTPaX2P|XLie1!Ofl@wxNUVyq8YRzaosDZ z%lT8c)y`M&EpRv2L(a-R>-w%sdjd6lATsYgJ4Mcy7rS9Wx9>)OfvLr3oqo&#`*c$e zCv7sdlv|!jea7`>is)HcO5%x3&e%myN~W=oLQXvst1h)?xukQKsUuz*xwH0`RQAKt zcK1&9t9@5io(Rt{me36IfMLGo{Bky8ekpC6vs274nVSY~GmSyMk~$N*ZNr&s<{I=r zP`m^+-yby_*XUZkfCI999m_`0SBbHCw(w| z*M;b9Y5S&Kk+s)rC#fLm(qmB+#1e{`7!}iAEuKkloQ2Ud?qx^9vTV zOpVc2;T#Q@9b^xaf=7Kr@$E1z$I`%6IC)7;aWmR{OH&kw|EitY8Sd?ab`9PQ9*a6t zrOj_yAG1bYXWn348w;+++&auVDmB|$khGfg3O07j_}!}Eyu271z{e!7LJG42xv;Epb zSn*tNm2}T>)B4cffHCE{eDMyg=86m-URt|ZM|qg557rVbIvayT`dDmG=n1U z_IZbDYoqv+q!%7sZd_bTgx5-&ePPOY{#vQD?V}x9Uv6%8ZFZ}?H0c8iVcYnLGJex0 zgMRq;TeB^c)Xv1%UF!5>JY(mE-!{+AwmX%Arqqpe?H)wV2g^(XBgp^dC@ zxl!$1w_{?l=r!MoircrtjlL^-RC^RvdRi?j`?h;i(ngNDhp;}E`Lzgwf*RjOz(b>>oJ{76LNTHuUj-(q2`2G%e%U=BY!D_4VH|^zEp%!c@Gq8(bz@ z&Z(*Y6*UIO?QmCJ9;%l|8|5p=A3k*Z1c%^mL1t za_AD}&XQlwa<}b+F*0H{)C1G^eI!1kGkk zUiOZpLU+~8DFK&hM2cT-F z(?1{K18Vz%Z})KROW;B@Wu_JK$*)J%z$@D)7PGIh{Wdj`pN!-9dd#M##A_PT6v}tc zZldJ)Z;Bo+8d3dxvwKta@Y43&8qu>jZWC8a*|Y1R*{9MCeGf5}iQt@*>Z};?9PO6% zk)xeYB(08X>KnKvjb(B-C2meyosJUke-ZgQ9)azL>$Wl`sp(aW8_MLnHgkS;7Y|V^ zW29`?nioIZvx}?tPuh3B&^Hj*YO-kW_uq{yzpR$uQXhvmC!Y5kO&Mv*nMSdK4(#I^ znjA#g)nEBkxpj`;|IOvb^Z%Rc%Xt1OTna9_MYxvWT1XEZ<0k8ne#YIdL;6{E9Jze1 z?Pju!bod^L;BUfFO~{QkU4Xx7a>4|8vZla)Vkk9aqxxPTJ?w2d%$HcyC**wqUv|ox zA%Fc}f4YrO5sSlMCiZRum`YwB-KHVrVPm{QGY zra^MLNgB2ETX!zIeJ&tQELB)6?kE*6jhcV^vfHImbC)hPa2VY?Z#iP_7JNxK5DeQ| z3kQcnLmWp!F!7R0!t(S&K=G3C|48GTpC{g=eDo9Hu-a1{`%$cZPY@iU@$`_Vg=u)< zXj7Vmi;r7z(NRzH5%eSBn1=3hTtC5u>`+`Rp9>euhTxDp<3^l7f>6V4C=G9n;XT1~#JUJO%~mJ#AdQpN(uQNZ zvbD)B`AH~=W{Y!AsE}5wPmqG5lb}a3zrPv$j87AtT#xq{{ER;pYDn$*pux|0o~dh2 zix0EjX!+-|@>QqBPc-=Xdy0LsS$Sd{cxPFJ25IXFXib&sMH`w zXv}%x?@FFNGQAVqH=5JZJ9VE1C|@6$Uh}hmX)dy~UD*o|^BvRkIno{B=$|G$fb^4& z2uJ@NxY*pBezH|BfjCPon&FQT|t>{Pj`(-$nUPM){kg z{O`ff_am(&4^c-{JnaV<1@zS!6RbqW8PGWMg}91zS$the-WY6<*f)ykhiBeMuA;7` z?+sG=U=3O@=Wg;ag@yPpVgWU5`c$`tilqWgqJ~~JLYjX%>V!NqY&*jJgdlcDbiW%F zNPj>2b3m^#{>l5&0VodvPY#G8d3g#6vo(6aa5v}xVWtkVb(l*CX1ePD$;&g=rokp1 zPQWlEFU~cDh*x#)!~ZD#Ly;czgW;=nNcuvV^>+w?_Y5KOZDYI#{CN(*5txGs$4Js2 z34tdY!;yG=I;_&6%1easGrHdzr=?3H!~|DCI9!s}>u@@TDeCn&DJEzdh2CzQ5pVH@?aMx-+Ly&HP2lEY+Lyg-Ag#+j3Tf`7;7_H8d+4_& zgeTD)#`#mW2O|W3Vp9AWP8FmW)XXKCN z6gB-T2V3Y$nG11 zGjv+L9i;XUGdNscE4PgH1~->`&n~}q?x3oI2Wy`>d+)V4pR-Y(|K983TcK&4#f0v`P!k1E#TZsnN3ZT0`^zWo~yWTkTs{@5qY%t?1>8V=w9^`2cO#aW9fTAv#oQ= zR|{|IuneRh_=BW1Qg4rPrY zpG#Te-7EJgLzS?FUU~iEW?HHA2JebWxppO*r`|HUsljwf=e}9Zw$XoTun(KrY#n`~ z!8U9fC3IDpUrYU>n8PTKl+#d8`CMDTQRQ48NQv`PqELd(+`4;g{?W+AlvvjQ`CR+( zW_k3X2JJ85Oc-W$8L zl558$B`o}wzk@paGo*`cPtcA5tf0nFa(0)i3ggD*)9mEd9l$B$BVjwaK4m|4 z{)L^~X)6o&N~2H1X6NLPmE5L=Y2ZiGtmL|UY$peFAvj`oxhA!p-bKtZcn@X2w^6e? z{GQEJ>1{37?GERbQ_8Sqmo(IN(lmbH0kpmZ8{m%T3fONnx-u;d7D;J!c$a2Zl{Pk0 zc3C6r48u-vBjyE_M!etXhZX?v09D4Q7L)D1rbf+T@(;@?-``(}Z#-i)RZjY#eJAw| z94Ht4=!FhDc$r#GRj3*Z`1~K6eX2%*Fs?e_qCSHD%IQ;@t>6AiX9fsJ2zy}8P=f%4nt zO0=`*l2g#7kTiGDK4@5Y5U0~IkN2*ob#ODRM^}Yr70o*M!Xt0LV-DW7;I;(|uD@Dy zQ>QM_oL6K)YP9g#H`N+ua~+a!JlK4 zX4U)s=Kq4_?tVq~QSHZL)`#guzmt2_@H5Rq;K&FevH)GubfnK2+q}Rgyw6GBT!EV+ZMe8Hldq*u+&hE5oMNJo`&U)&i2iRD1jc2 z6S9EM1<7=bWIHV*Q(NyRowH7FGsD`#R;O+oIlfEV$d0N+SVv}h+9jUUHezR2wvng6 zUM%d4hioG|FK8Rtvz54@^&dJ4Y&BNZHgY~}BWqOoe;TbD*-x3q3hPW(|F4^^n;e15 z^jUSXY8#oBdO0G-*YmByZzSk|W*vFDY8`o6nPweX4p~R;Rc(cJWGz3Q)MHHJeEkjd zPK*DwMvic+Y9HC+pGNHjA>XadM&HkxNujG!t}UPrl%MUyx#d=8Rs09LuTC5DaDnB` z-aF(Ec3tBd>#THcykv%R2;XSeDS7=1&H05^i~^%gWl`>FX)&;=%#zkZwjMp-%Nb3R zt*^0OcbInDKlZT{ma!ICRMy_X+>Ca$)w-N(r7WKH(7Li_Rr%EmSXGvSe%}u<4j=V} zZJ7(p%Cu#UbMLLrb0UUV>2#-g3gVf)H= z96SQPBg`~*w*HGdUpxid88};ojpfSSLPFk7o(ffp9y-YPANs2;12XYLAQLYexHUAn z_|Ep6gPLXLWXv73RLpV?*%1%@*~vb}NTbg}BD@}{T)tnbx&v5qvdU`_e^A(7*3zo) zIrA@`^JOXYN!x87?xK{r<}0MK473jJ*kchyqwb6WYlpm zqu!|DptJpzLpV#@THd7Q0*x8Z)$p#O02atc-dvvuE6xtx0y*tC-@Ai$oS&+ZM&4OZ zOU`RlOU|Wj*Y4hq^XJ*S?XcyXr`mF6|Cp|>Y(<^F3~B$?rry<6kdVJ(2k1n|Dtu@A z_=C(<(*n@h{%z>1sG546Qu^VD9gq?Tt=M{3Z!Y-oNN4+C=!?+eQ@V^#Jm{#hZZz7T zPTiqtqA2c>ce)cZL7`103yI&x1v2(#@HWq?nvmY*P}HzDg#fCXx=gRcheI z+F>mCU%>M?8ShZ5(b@~?mG(SuQC98o?p^hbaR*@CtI`CHAMjjnPxzHvl`QdiH5?A? zD9PAOv`8`7F|%P;DHc10PVDAUrZ7?c?p=U#W#L+kYd$VIY!^hFN!_T1YJYXuGx&6w z`+|g^Q+~xLR)4e6Gu!BilneGCi!YG8eaIYU#0i!r@)i!lb{TfN&I=V`*iaMV^MKmR4e4H0pV0n9IzsWTj9HDnzdgtR zK$T5o`B?8Po9Lssm3SUGTp)qpaLeeBGluuX`4?$w*lGHiza0wD^e-7sG{>gq z#3rmRP}@M zi3u{KuR3CS44rccq59Bd9C@hK9Yfocng2}IwRNl7JQFk6>DEndFV)Z4a9(BhTWH zSLWA`5a}oC{_66Q`l{RlCUuO>`KI}#$lorF2y z8zIE|bP(o2mKC&$&!-b&@-5K)b9K0!5a}N##Ch3MdiYNWM{4r{>r*{n#raw;`jb3C z*A@y61HNe!^s)x8;wy z&bLq_!ql$}aNqUB7lb5zp1vVi|H6SB zsgC^?LpS7JK?M6O+lFa)fmEpaxY#YMxael%GPa+pBHRcgKH?Sl7UCWxm%~VP96uP=At&;RUQ@q@6w5=Y!ewH5 zkoJ&U2IMXTV)&~U^JP7;Y={cE3PgBAzA!#Rka{c1L(e~IO&uP4EN$3bXwAy^(Hv_w z?6_t%I<84c&-f1PQ(W`0p9@Dk*}?-zKih)oInKG}k;HHdtyx5X1ddmIcyhI{=+2UR z?p`pbWEt*75`^>JWGrM^4(fGb-y-b8aLg5IJmyl5?q~kwThMJ4EK)ZaMqS)i0qEvf zjm%!$R)JS*)Cxhe8MlFF}x>eCdh=rX}a}3jb=us*L3Hx-8ILW4ZE&r zCg&c$gP@rM!pYVCgXL(*5igdhYI+0B)X0|5owi&Xdzz}W&^U}Dnd&1Lo;pqZ>@-tn zx$F+j96zC_XyzASt=Yv=Qw#dPOf#vYt|w{cYrxl&G?VLAH^$88nPwW-%SPIWVuzeD z{EJ94@rfUD>`&Ngh@zP~*$UB2eK=y385)I=6f+e3zg%OAC8qmgdi=(W?Kyh+1z2OA zzr++%n0iw9fAhQiLiBR7-rp~_#{3e}8P|jtqL=*MHqwj>tue2T!gnEhITz_Z>l%}5 z7U4vh2tVr@^D==9P~bBJskg@Po}iapyM>)a-8=ZSHD+XbO*ZQ9Sz|IS-$AS~`-d}E z=iAIEzei6WUSn!xD?~1}(Wsuxi(wc^E=A~PUteM`GjH7AvzM8dH@>^;%lowkjrb-H zJ|EZ;On7=1~-!wVFXSyMwPq_WHI{Vki8P8e1G`!6c=D`Ss zelhtdxDO;8mUybm#lMj@f<-8_mSh@UTw6}V#qK0%Z87eRZ7J|gLAVj09r!pd*;kC; z^Ma28!K(A&f3|k3{tJBk?lo*#|V1+Y|7deJp%e)nnaYOP_9^i4Kc7 zG=dCkGw&C4&C50sPK?xOI(!}I9LEmn9MkaPs8n#ViwQb>Kkk`MIDxMK0YEFyGMm7AlzODVIBe5Pp@eqiV3076(?{ zr0e;*$$^WXZynJ(N(5amd0rY(wI@ayeXI}k#$!FbR8aO_^`?m$EguvxuBr>t`W@3& z)+u{RUSOO~@k6wJN}A~y;~vS#DH5=;`H>8B5j8%wHhZ35xhLi;l0UOJUP*#%-U!Sc zoJY)iJTIU+RC-}tljkx}cgp}LC%7sstIQ8zMP87w;uc4OYqArD(eOV-{ZA8#0o`i) zxC-+sb^V?^Ga>Gu$ftniz>@F^z&JaI;GSEhf4+DX*iOO;iotd?((@wpe~t@uf0YI@ z9jODyE4!+gAGYD%jY~Lzk7LY;uf%|l&kB6E;$G|e8irQ^inLqxU*O|BV#EhYQ#D_f zkL42hzK(m)=@J0dWdpg928q0QUSy=_w;&?SCmSvk(;L_6c4X8YUIl(f@S8?Bk+1Lz zXbkU(`GIp**ooTHLO35p##>drO5ri7`PuH8W6g$LSL<}rP`(5E6z7BVaB{W(c=UL; z8gEtgJBcJ}KH*Vlr1)Y8;ut4-r7of(NWA(zz_t2pAQx+P2PSd8n~aQDPUD)rQ1?$K z)Yj~m>dXk;r0sd#=3O|fHS&LGI}cs|DSF;W+e1eU5u{x|q3E%d|L2LHf@4rPG4iA7 z`i%xU%rv|>%A@yRwjs=oOE`gV3IdFDxY&TtNY|tHUtYy?MFJV1z!$y$vf=`Cy%^7Y zR=U2zkguS(ghskzPq#M^7rh0 zd)1t@KasB?NWC?N_XO=_eT1E;JuT!PxyK^*zN7b8a*#FOk$r@;*Vq<1?bQaGk@SYf zWEADqho$k{F%x*j8k%co;_S}8x6c2&RNKGl1}|Iw*lzQ(J*qWo#2T7sjsMyA?n=)w zXt3BEGm>C6tmk$$K2K}k>FA@vi4hu2f4>6y#xWC3f2Sgh-AmBl`*GhD{hf?(v(-E8Pn7Rkc#Zg$U4Z`1M>-?@Jq5pU%!|CD=`Z)ZmuXq5{~{fs zaqat4Aon8hVtd}4zl`r8@ENj*$cLVupuds4!5S}dVJK4+%HT+kBhzbp9(_V-K09wQ z`xy5)!s}{{HfDryYyL4&{)zCjt^~afmt9|z>!a03uEp?;*zp#D5gXpxpf=KP=F>C# z-Q&hy`uD7#^T%|1Poz%kJW=#~U#m1Hu&0k=RZ`x-e)rw_ez*Izy_QzrWYeW7%43o{ zAg{x&_PvXg7;u#&ln8E;ih`6P^N~j~^3h zJFe*ckIe{k;}TBbn}Pr%&E`2O*GHUFIDZIy(fc1iMcj?JgcJCp_dhtNxRHqXST2E& z?`E6>`e6KYXAYQ-bSv*&^QMKfxJ8WALQRD)Nv39e1;(P))?LsbHKl9|AY1Z zY5XT{HNH#!6Md{1sd{)&aupu-Ee}iS8)Wjv12@;RuglTw49FIt=y9;_;jr8k-u|3^QCR!O9l#W6 zw@r8}W090IuKpp*yZidSm0o=NqBm0>DMuiz3w&2niy$#As#f+@Z<2ay@V6^ya+JvL2SOj zp70Gwr*(M^!x;eX*$F4`U4sB4zMU7?6P|~3#y#P`hu3+j$P`eNiO{(2<%fa?f!urL z#q#m}SvKSwavqd#M#vY&X9!YnMLzWO#GbG{A_Gx-S|HB>BjdGmL5@?+Y5s6~MyBqH zCyu<+d#le^JdDR)GS3*em#p!2 z+&iyiUdgvO6I^T_xYQ#gATKWa(t$kSLi2zVr7|m5cUW?gl_~g_MszfkOgmryWw$iPF6xZ^QS7m@t$D^EoETBmZ($s})8TiEM1UgQrMNfJtra{| z(!)R^)O74`q!mWGRSZA#7Ea_9&CjqI35@!zMLI$w-P!}s9)xl2#Eaz<ajx`l_W*)d1oEi2tn3iQ?pC=uX^kFF|hu%XqnFmz3 z`n?P^p)tHf8^jkI!(%*R5MO)@->6km#2AJ=u~NR*S!^ycU1k|$@mzi&?IcF^OpNK7 zrpt2oCM#w|8u3Ac=cgspt{yaFZ<-=ynJ(Q63uuL~XZ2Boxux7JW!r0$6{Y}1801F! zmWHP0^Jzh*p^n%`biEJPIerd(xRaf;9k2YH@E^a{5;TH!+=E2oU&U+H6^*#XP}gGY zb1pNElhyD~=pr5U#29JB@e9z1nMh}(5wF7E9UAdBq~qDUaH33vMjGJ)@;wN<7>%ey zx&Z>#CRsEZ;LfsLH^4Zg3W&k?SF72Wcnj@i|WYa6zYaDr};z8UG!TFjH2FWJsa!wW-0nu^Pa z??L$4j=~9ilM!IVXZ&_!Sp>dl9?_GCE5aq5z!%LU`WnjTMk1Dv;?Xn5g@`gy?*u^TvtI zzV4kvdoJnrJTX!0h@p8R4n3{od01jCj#D1o8?Ts8-q2x5%vEmO%Nf9?WUDj5_X={A zm{vEkV-&Xvvr{^tXN+UUNV|<~#5$Oqki60w)+qLmUn|}XQwaKc5j(X@7tFh} zq~|E_=j;5LeMUGj8gmg~q?MGxbR&#wGN$2Wq`mN}j`Yf--xCOYlW}jvmx%~;V-=r~ z_FjW9BdvS}{(M}*Xk!5@oOl((CB*zWH^#c7osqBrUuRPlX# z&C0bMmeJCPj~g7tBldDP3SY4Be}uJYN)f+G&o)QX75ar^`~Jh%bYU8@?2AA@NEg@~ zqUUjJ8pnwk@6r2Gw;-JxmvACo^uE-i7-%u8~h;c0|vpX!8 zKT=?>mvTB9l9iHaE?noY4~*lOYp8$TI4-6&)_;3DNnMR&(sJR%_>3OMUqJ%5NCYU- zMUUhAyE%>*14nnp@m8ek&NzOqo8x%?zxg<3pAU^=3{B%WMi2dz`T5S0f5tdA50*}P z_F{fcs-t%$9IL6R4j$`!DPZ`H|EneJ>{ohN+cYmFI z1~dgOG#~T39$)b1eVfN=>C}JH|9|-08}TiU_wK<7`17;}D&|sFthnd+Hhwo#9|u0W zLTgl}qrU)`_L+nmxCyx2ywRP&$L~TTzUTCLnrmLJ=>@)7xJMLvpyqA_=*~R-DALW* zpCJ%sA~b%7zXneo!Y=k5&hG&?(g`Q<3BQ2G@SgY%XSu>I`iw_>{b(t=`VJRoJgiU7 z)5dcu7a!wCH;1rsz_V*JoC6+z8=>bD>VN3o$V}^(&Zvq$=O?g zbvfqpNm35JuQQVHeN8%G+_N*%1@7Pd!|6ik+qy@Ob3a!+AFM~=#2AiVlg~y1w@3si z(nYVyefn7E`2VzTYxchGjP+-bt~+b;{oP!X7o&Xt&fnH-tI(Pp!_zpl(L+CFE?-)* zq&su@I3Zbf@v%&PL%4{sT=E?E=vVKJFV0u4+`Fy7Sr0zhlN$?c_1Ea*`Z}!FrR-qC z)>NOX1biLme|H=E<5*-cIYHH<@PO&7zaTfqKXJ^X&b|Qa0M74hDlwyQ+!@E77|Wcu zjdNTv{2pAwiFB7Cz&O9F`n&WnSJ3JgGyE*1*Ki)Vu zihPkxgfoW!UJ=OyNMj)Bma=P))7dUjE`KDfH#;aEEVo^E}MkIBpLHsAhi zt)fEXo;(~SIGeL8@hU%kVcL_DN4>Ku$$N)`H-l$%9&qAIwerjm*SyN75k0>f_lJh! zojxag^H?#VBBNL(7}SI0;a|2U;239<8tDV~aD@}&o^-@G?mG~{_F@|{4KIEt6yh@C zy9It1F5#Gt&Wp>4&xIkubi~K92z=3Y(-tFcA}-+szN-;n#ODS+H^PXI z@H-NheY{vqWnS@ifPF!!TCoxwO?tYGej1_4WW-# z+$>(OM4EHw?TZ)RH4nr0-a8lENybbqMHHU|`v`gEdlP~mLOqv627Gt&%Ck>)hgW`d z-gv<{+bzBbr0zEDEkU{9LbSIRG`dfLT$Jaz>yJI%I^XiN&0YVO{^Mqpe{AXfa?784 z&uV*hsrlpHQ=a|rm91ZnEnoEVqH83%#hm0U9FjBaxH~825Aiu)KJLgd{lS!zc7#$- z5h*yFeOoxZX76kIj?MzBSihkXAqW?C$}S0pA4dQ!lys+~l*r zfbY!l$!A{zjQzvpvrhrW)W3i1=?|X2w)f?7&gmm2HKqCN;$=_Swl_Gg{7e5;A6v3s zZduTGe!Bc|->K5bCy>+jW>?PPW4&^oKaqC1DQDl&--54i@T!)pCp<4@^i}FQ{+8F7 zZc*ozJ>VC%*Glf}BDXT(1@IEi+I4pGl|Cg=>8or~Q%ITe>YU9Wj1v_ie zFPyW2CMVx-*UInn{l?VwuWPxzSJD_TIs}8|^M-rRUA6MznU73=WJb=YKDC1&_1N@h z)(OjTv?H!a$~L!}SQCyPw^&SdXP2+MALCjY^-}+rT9)*l6`Y@t@NsY1R4J{Wt=y;A zRPBdf-+c+o;aNJvUw~0|zwc~gd3aNj9+QnmX%>Hl16!h zr^_v##b18CBd(71eFE_H4yo=YRHZ7ns=6@2jKvrTf~&5o_Ep*2zl z)}!gaAk{$W^3+~*v}UaSb~809kzLvzsIe5j)|4?lX9nuuGk>_fR*tHHLp2XJO;^*S zj$P7lt5SD%b9q0sugUWp^xvYS`EKdsq$Fun-P!VTYkef>5dupd35b9^w_IrC@z z+1G#80?InniuSY399y{ZV>zjz|Ib?HC0RdC%J4NE?MU-DXPENpno0Ax)>+%p*-66B z**XnZ5w6#8(apxiwTWn%k{Z6HRWBu5>$Tdn3@Ib8F!k%V6)^7SD6iGyDLls#yUc!u z)y?#MY_2x9_L^t@AU(tU;lwU+60A2qV~?nc??sw1?vt#y|}AESfS_BiDlug9F)6|2YeZsKUJZ9BG$WBA$w zm+0YEJ^cTv;hsEgtbg3dcHQjijb38Mh;`!qp2^snkyJQz+t-StNB*P_PwgVruWj48 z%e(=7p~d3lnCh>@p1fu1j1G&_+G?>%!Ifn{E-3x5YFAFNr+9XbrPXA4zk&5~2Dw<= z%t@-$M#GBG`#!g;tWgWQ8|^Hq7Wbs=+7Gwwx(D@OaUo27l4%}$#|nz}_0Y5Hcg;hZ zG_+c>YvIhfGi;v8DdY3iY#Ow4fA}%5EAYWwU2^&&?<^W!#CUwV1@R zuMHxmW6g44Xw91)8(kj7NW&j!nl%%>&>d4*1O>QQ&L(1t8-L+Y)~J6Q3^rNse)YD{ zcOv$=m+`G!XNOTsLSbuCL%d*;HL!2pSd?jhyTefMD}nm^DY?4c`{NuyD1bI{YLhL-@nPY4@Py|e|F=3`MpnlH#znX z`U8*7JHR*d`vWVlSUvaQ{+uWOsek+-pT7ew_n7bIA3AdBlG4%rZK^~)7~TDT;Jaw& z3YzWzeREB3Ue$wRZ{mA6xKurKQOz1yZv z2fQBlB)9)JzF{E@rSv}DarL~wR>b&pa?2O&T6ci47-KFqI4$fIuJ4f#UU@ON$&WZ$ zj;0!w?!ealgGGCA$EDV!1;6cUXL--+`uwkS%%37mKX>{(#xtHho+WyGVOH1Qp!5;{ zA3GQbT=?4GA6n|aFXx=z3oiTjF}EG|7yS^ZO1rrzys5`Gv1@Er#dEu-mrg4^^1+rD zb;(|2+x>DissG={jJ*u^`F?otKTn6n-fkT}ed05Jy8Yd&a{G`+%U5s8`Cad5ts8Ng zPiIX$J#3Z7d;hCHJ|?iK;>{NhWd}a<-m33>?@ep>Lnxy{?9;HFV4LxElw+1>mSu*s zpT%|Q=fQD5I62o~PJ(NJBbi|l$f?5V$1y7N9M!dhjg^$=bB|Kl`rJE1cjerj zy&-F3@Sea|)J~;6xlMV6Wzl^91BwN12!Jm_{E?YsYwcLo_{F8os~ekJ{%TE!vyfHI zzBM*3=|uNk54FjB+_KKr6-(i@is#=?#xdDbCQmcPX-fQ9uAyUj5DGdM97jTPrN$`e z6^0Pzg+mfA3fUYZYdceqjd55Z3y$%K8H?adeKinRc7#OVHSjR?bwb}D;!+=u4RH0{ zglp8xbeY$Zj>qtu;mmlQh=(48OMEWfMmWRU8pJ@GiF=a1I}y)JUmGU>SSOi2 z{vF2S|NRCWhV9zH6y0B#-k9Lai1#hI30%@dZjK3-jJB+8@F;>m*Mso6yk^?)T$i3l zm$=8368a1;bt%uGkclxtWV1o~JWoD@WzCN#aEBLl z-#u;=9X`YTQ#w5EK1PT0`vaPE_$;PHP;ogCe zo0fJqE?KjB_0pA{jl^|lgBzoCu3FP(xyNI}gTuFtjh$a&oaL7LeFS){S*g4bwz3&* zgHqf1rPh_pR#|P$i#rkb-UPfWa>#Au6Dqf%sQT<+aDi3%e(#F0+l#D; z+s?)grCn!XUY0$iNL~A`fc@VXM<*7Wwx(%2ehy*goa+g<{mgZj%-0M~sGdseE@@8* z1)YmZa1=9_3J`!QpyuBghmLX-P8SbcfbNCky+Wdo>o-h&#RyQ?27gpxSKk6$1CrXo z6g`jMY0fp7Jd5iO5YMHzanFhD&zharh{oq(gz_7KOuRp$ihwk zOxQY1SAstLx=YrTq1Ih0h%nY^sG^P5i_?*Fao;ibH@2mBKF>_|>kh-O)e7rObn%7j zE{mSax99c*`+zF*YT#z|_%0d5zD9o&d~oX4;oe1K*A@Ayzksk*>$FVVn2i5aTNqsL z`z%*zjZ~kJ8T#=(XD7mpbjYmZW_@Tucq%O5xP*xXPoSONOy9%GFbKw(7oOU0^;{mkc# z?JDBl$D{3m0w&fWm{TJ({^Nk-U-msp)~h;7VJ4hem;bWwk(dR*FerfBBE}@>!=J0i zGVj)9R86xgqxn8+ttHm`Om#kdm)3fpDG@m~W%zcx#?x-=b5OEyQr21a)SYMd-PN97YM_TWtws5*cY(j%=UjRM$0w*MCA~*X2VJP1Nzv21j%$SgfuJW5hSW=u#AQ8XBpp>Q7MY3No5jx2EUdgK+ zuEr}+2xxb6yuuxifHEG4GTeB?%;|zs!{bhw&gi86LLgT3T$i>WFv@Vaw;(pFXDZJ` znTI`F3w)PYl^>{6QFMPHV81iWSOez*qUBeGJAKh#7oMQc78G z&AKaCz;OYy-ozmDULlF+?K3=yI!VkRjvTAca6iJ$=gPCZ;|DJzUOIh-*VF7X+>7*m zl=}=U|6*sTDr^`Us)!=I7%t_$j+NNKnO2?uzwPJxQcuxyfph(RH5ePn=lCPfT9~&j z`hMIxN7r+nol;~EHAWCd`i0m>QuX}`RQK7e__Nhu!3fs-j2_5vvTTY}^*)si;H~#9 z$bYk*4pr~Br&;eG@aP+=-v0#g(y8}-Y1aFX`hG5RtUy)cqA8|XL{dKoq zvznUiIg2RB+n!_0a9WibE!025)$1uUrYzAtBU)~50HM*DHQA{N-PJQmz?!MtA$S~dEN{fYcm$JetS z$i*4^v&T(}b6-fb{uBGMySDULhwY1yuhGuK}Y=`dvB}D z*_s~NchqGN?>xtGEzvBD!==c`<-}(bx6-~jepj@FmDg0! zq~&7!P(St;RB!Lk-kRG3O-)wm!toMXXa86KIJ>W(f3|%`&gHjvUl_}N$l6k9pMh_) zO~n@heD`zg)8CDq=OE&gIp%4$oqY&Pxh}T0aFPECwIJ43zn81uqg9CX)CaL4OPb@X?KcaOT`ok5s9rS_@wy$K0U($+D@J_|5F!uP@V&p31#Mzb2= zh;cH0QVfCbQb_dG!Nb%y&d|quMc)^2Etp9i)ezcw;gIP2JY-W}C6t8W$Mi8>qVKP8 z4QO;#JPCd2;PdN<_a)pb1W^&Wh6XKfz=LF;dLg{{T;>zghUdEUJWL#p6AOtxk%gQ7 znHZa8ni8bXsphz|Cdo}Lacnj@ezrQ-I_$*eTjqEa|DPu2bb?ZS?~Rzv|I`OZd?(He zQBRc!;FM>eT7gEnn)Ka&JNUpiZI@w<;c=D!oK9hUZnJ?~{{>X?hWejGk zb_WHkgfiaaLUPF0kRuD+G355etCy!Uo+Mk<(>UvEoGuV1J`7Xd^*2VP~ zUT$TdmUDToKQDW9u-JE|Z%m-XceZb=@0`Fm-+2E-pEbGTiz_;t7lU`M);uOx94fXZ zb8mq)d2vUF<(|{ee99o0o=P?+^HfM`m$xt3gb1nPd2P;ZY1*9kLSH(Vwg>Uju{mD_ zz;z=o=eg*H!nE}tahsFxKx|G`bq$+S6;Xt%x{o?8b>FS)tCy&QwuiGhXUgX~(x~g+ z?{(<&^M7uvH@PEv=FfXDsx%g($>U=8qSkMUo?$?z8_{ zwBz>f;6q=1tHeToPMyNw?=Hf5VD!(PZ*4A%`L^WQ4D+EksC#V;N79e#x0&@{txx0L z$gla(1#2jzRcD6N7E^YD3ZJjSPdGj#^~+Ls%d~Iiz~f}u5v>1w-RuXESbt4BO|XOQ zmD%Uv-W9&90yxH@qfDFG)Hfe;8JrN~k!Hi0`ndO{2!7PZw1__9gf5P_0JXy{R9E^( z^j!v=94W$>G`RorK*Rw9NOUi8-5~RDG~B5X}D|Yx2U0 z=t}owC%g=teXeRxIM?6kx|Y=Caw}zW|I3Y>)X8GMlIMak4dh{P_O%qIVsb$2E0zQ9 z6Ji?7Z)SJsqgRLjX7+KMy;`YXY*OD!pS{|CjI&p_IcKiwGg#m5egCL$7xBLd@&CAI zuU?(^L;We;5g6AJ`zo`?ub#AVt4ib}UzdrI%v&L;Mcy-)i8ZO>dDjCEHE%Z;_nTPt zkVl^`LPvk+ERJ~B!3jw`aucf#q-kH>k3@Ww&s^p^5c|q={Hi*AwV3$=C=(oT`&k%F zNM~I?)&r+)TP@Nr!>#vR51b$47j!q^{ID~2Mr?i=m-bW8u2FW>`sg`7kHoCO&Vveb=+|Xy*QCA?Ii6wg>o7g1J@~-(CM7$f}gd`rhi6zxgz6XAsYnT7R|HZT+ z$fZFD<6SBFKN{Xi|2-3S57U$&@7@AIb{!+tI${17{^uq*Vu^`|45OVwxG=hIEZOkY z6Np@w%(cK{9X=%HbgpVi2Xm&*nCUDK8h$=;t$qP6=A5BQochN0oC|;F|4KH#-8}|7 z63(-O)ASw$%oUb@(EIDbpKJEU%v&y{bNRQI z%}Qrz$EbPKqB?u+?9QI)`sB5z&+}upYp7Qd0AKH zMhk2FH|7?Tm*@cdttA@}svi)>aoTRx^_6#~#ElcuKUM;%45hE3G)D*$w)|IWD zt<7zdr&rCW&SaBx((Kj<-W4%R(2e~X;<*sp8Ire6dH|rk2>xsf*v`-~F5kVWk8_XI zDa3fB8aT5}8h{XnAN84S5}#q}i$PFW3V)L5y9U>$z9N7*<53^eCFyI$wW)6{1g2R? z^eu&lsV@wDpi4FD~Z$4m;`GEB`rCp=NEPgDAd?V6-?Xo+VJnH0cDSD%0f^O*P0_V}a` zfqEkznKq#i!@cv^S4to_!_6}xC@=GbukgrnHXpqi|28a15`58_nF(uuyj8ynSZbYsiZWlEuLN*WuNwJ&LF?&xS;_Qe)! zW%J5qPU4aVoOH{h$D2x={a=`%Xu$u;g8|q=4tXUx27dpR9G$ZDi~sn_nYN-u3XvuOY) z-B;WH*?*CJuz$M!et!{q*T3rhLw~ug!-x%Lf4Lm8&>~#8YsK#N-H`VqXISm>y+8Qj zk4A9r5_z0SBjsexKU5+=S=R-%+0HSKg@VonF^%zr?#0C{5x^zhOkA67>^?MT#1#5v zIq_I8=E5PU9Zb>7_~o;O_D27gCG@CyO9LbLY0}{_Vn(&|vGC#h zx$E@{aQnHkZuZXZb8Y{9fla>6g|^jqqy4OXJ@&%rSxT$?{oV^J&$C z(C+L*q5O-UExM>RzSFk4tcqfO4PfpnIIHZ1!+#t+-_AW;@>Eve^my*!>>0i?XuG~# z^-0(EeDhEw@M!ex{mtY45Vz}p_e;!(PJ5?6a^WTMyie}5{~s`heZz(x&8_m{-4{=| zcEa+pk4E2keepP}t0=xG+Fnyq=j%GB=cS$g2Yp>*o3hl}+Nr!c}LE37pir>bc#%hc=`hBJR2ly{ry82%mw2CGSgnf%H$cu-Nf^Q%#TY3|| zU+rBmP?Y=HU~u6AJ0Ex5h5j$jsQ&AX(SbtmX*XPnE z%`2ARMrZxkoDo_7<&HUOgQ4x{eqkm*8GFj~`G{%L4Db+~)?31;4}MZe0M^kuLd5bz8G#GMo=H`6@8z@wUHca9fTX;CnWl4qni5G8tG%YMBidu zn>hYD^reI2JQH%YJQQ5gM6O{(2R?@f)xeWhIUS#y3di3AWSVxh=+jyfzo!3*!12VB zm@h~7jrbpm-AEt)TTra;#C_V7Ld=&^5x^;%7(scuC;ZcpnI|k$>^szZ!nJvw_ylgE z_PXXiE?Qb|YVBkPpt-F**364F?d?m|@N4I)wj|pe`p3a>9{8`wvG#T|ITH6EIU0QC zj~^4)OmC|1Mb$ApU)%FZ^Tc=-2XBX6m-lh|-ZuYt2942^Ws64eURf3e>xd()??Q6z z#ZJ!O5|hNvV?4@HIJ3T2Lk`0Ui9Xf=6YKu+y=`I_GSwiS4}~gckar)ayfqyq)f^6O zdA<+kJFyF0aFh|~N6SC@`#e+OgPF%tpS}3-XB1_Yui@}vKH`||rRekG1J9NceWq>Y zJr{N@^rd49ZAUzF3{WtO+_Z(>hR_E;)Uho~K!izHbBjC&j2R{BHgi`C(tYJsvooe1$=Ar z-S|#u=&t|OD|q@P2mAFnKtqp=2cSnj@!E-xkL{}Of1U9IU7w6!7hUk%|NiR|yZK;k zpt0t2HNmbKB@1e;ih20D75;l~_QOnluAC7yDJnrv`MdJPWzD zWm*5hod}EIpV#I*II;8$?4q?Q-tO(|uZWcngaeBz&WeZJyb9&V`XiO0c#-4N+;4@E zBennO#y-@`u(lZUHZ&dm`TPaysn4g_>u=)AE2w}&^w}Hy+w?x!k)FeCb35iOOBb)X z38V4+6u{)#t1h41+}XLhb@7_cr5&tmY0{}=OTKCVo?tuQhiUs21JH?`-nN4MBI9-| zg!)?pKOxaq3lCFY9rO`jsLyOGu7V7hZUwYiVnY-{TeuLqD zhrddW3>hTnWD))Y`^Bn#LPsXi9$g%nqK`XJzr(dhGv)IMY3x5swI2HRp2&0cApI*jq7ax5NGT({NWL!k`H@FsXywUj{S9I?W zMs&^wA5Y1gA$+p1jhMxc$dQ8#H?<|UZx-5LD`w? zPtS)lG3z17e72B0i~T&rb19B1bBs~qk(-!xJnNyE_d=piWZ|ZNCNK+C*C73kCt`~x z=2U`G&Dn6im}z2NAVz77L6J=E@Uo1is{2!B9!K4uGBy2qn*%zdjjKG*GkDDd!E=bm<`C=aWgzl>RoO`J_B+G^bwurI-S=_~D*ak@!W{K@ED zcKPn_*#8XcEO&pYecGW>{?5A5gT8ZduE{x%NB`Jc6{~o5$HBs^U-bqa$Wb=iS@>4V zuLl?68AT8C3HM=j_2&nJtAcg^-h(HpuT)M|r>O8b&(DdDQ}$~_-|g=@F!ssly}QG9 z(|GMO4g27F`}s!r-pu)Avkv?OVMEwpHJ!=?`-1wNqs_4qT$`<17Ze7WDanXIcCs*w z_{3snVixmWNU*399wrv`A%N|l*f5MoEVALu`b}Xz{Deeb6dtBN+2=-mOpEBF4P;{5 zeCSID+twl865J~!X(BhVZ7-Df!Ed;}`x8hI*MkU&K9Pl+{+YlwnjHz!XNA1%dT2R; zb@CQtSrQJnCvjz-(vWH$fm{;J;BY-pATo1!E z@HDebkHp>G1m>WFOA?n}j9L)SJO9!J-PrA$ zm1~uqXJ_?IjfW0rO;^X2K;@bD97CmxFnT` z*89wO=zOL$CwJ9A)0}_kXZo}7&qhIRpVMtWV#NIe=fXpn3*Tnrj#0Us4`-}<(U0D` zb?e#bj=NSGWosb{;Sl&ytB1t4sSDxBs13AB_+AWo+>FRKkD08zI4K zzB?1II{`Ie_@P=WtQNeM{rxo$ zyT+B0|D)lZ^xrelo}?NJW}B*ssZ9{ukL39JEGpu+CM~OWLU}N!6O?M-v&=OykJ$cj z&RK|h&JzKgGHr4p$`^|OPPqn-$!8hkJb44S5W}@Ck7h*{U>VgpoxuUs{Gp)wI z|2`)3WNR`xQFba}Z7OW6M7c1rj3C0Y%d@=W2-^|Xlp-GEo7i|f^JG;i^ci02Qqn^q6WCag^Z-4Mz`Co+JFdW- zOHe9XTgDamj)`^V*a+X}Clj};_bXVH04oQ506%i&nJUxRg2qN+4gP?_8oX@58eq%x zi;rh~;yCtCmgok}wXHb^ujk5q6k+Fj^_R_q_vWtC=ck(sey4?fwmU|{Pdm?6u>98XBkcr{|a>T~s-!_9bw5;I<# zp5=_!*7{ldc}8sDwHKk`89n1weXu|H;8~?s7^_EZJzKRCGk2ZwxtO=>vVRQA_ecb8 z3TBg@=IF{?JI5}xuXp|Fm%aG~tfKw)kaK5S>%adxpIrG`PFIOtqh`;>+IRid%FgE; znr}hP_evUT16`%hGS+GF;HLszoF|j{vuwpLuWbcb~w& zaIF6sh(e}MJK9M>^11ihA_?EVISv$FgBCu>Xxjm*b(Oo#a{B<(^a zJj`~X36K_npSPW{;b&rPHFTMFmgtLm^lgGZ;?i(qI_sd%EFgwOZLZo4%6q?@in=@`~{Mj0IE*VOt_WXhYA@zVa}aGv8&JG+P+2~E+qU3^?^ zTO|E)qjLSyliIfS9a;91Jq7kgtl!A$L#uLWcHO)l->jUtJ{`a+fA3d7#Yp?Eh~2&` z1lNAl_XtgUk7eH7Gxas!2##UHnz*I4r8D;N9KSHJM6k(=bpxsS}`tH%W> z2FH7aM4#8D=J_40OJ1y72tNe1%l-G`!c3n$%Zqg{BVLo-1TOK&O{@z+`5yQY>jbx% z4&pk3TzVOT*|!#bZUpDT^v?v=6(l|2!`slzvs5-Tu}KwWw}USp*r|HU5?#u1uj;cS zlZtW8KDXG%?%4C%Wvf@Du|{>~3}@R_8gut=>;ImFA>1>>JTdJfGmlulMs95p@{0dE zb1-m9?eCGg%GV&*mAE!-9?q$!!htB_nRTHWau`lX^m*5yJ`a7Va9{y$M39REiy)_i z1NS0cI%`mQ#=#!M9S#Th&6Ej8c3;`Lc~ z2JZ^otxl7TEXpe^uFZ#UZK1{8**`;^k;EM2a|RLT)H>UY`7I)m?Db#OwAN16p^V%RnW6v5AHdt44b6LV-&q=PwsM!YY;2}zpBP1|D@lrzDs z+jLAH)8Vx}W+8xhDkS0Gs9F;sAjk#p?h$IO;X=$cs<4@H6Y^HIU2UghU_Dq%if#SrcA-x&rY`e7Y5KI{4I$csIfc zNt(z_d>VkT2Y$oZM6?0V6=mR}&+t;0rhg{ziTRPB4}bO|>k0A5JTJq=7gTc-U{JCf z8<(zLy>gY)W*~DEM&N}DMqtih=Jey4Gnh6t?XxKE)tTsG#3-Qhgq|alg8T9mMqt!r zj^G2=E@M8SHh2E*-4EDV_9*)-yG+?fKOMBz1u!noZ=r3Qkd~Kq-)ut#PwGAK7DDEG6Owqf@Gx=b2F$e=!4J)1(t7F7L*{c) z?G>%VujrtMTyt#L)Yk@m#6{}MapF;KgVV(t7ohcU4eCn&h`ty^Q(q_ah2cki^k+Qk zV`s(0#h*Y<2N#)$jfg8GX(Bgq@c@)Z;0ZGUr>N=YGM|_R$rD^!#YkU0FB}qmA`3VD zGl7d{eNDU#{WPxMP7cpf|DjS6qu#VD;Q!>P@Pv<+`F}N;Z-oEfE9Wa4i~o_>L7bfc zPMKwJG@e%hE=0Yv9D(oibe0sU$Sx9l>bz6;Ik$V1*(bOFUCP$OKq3Dt&lw}RHXaI* z;CC7QA(xZm@iNBMxw?5}M;c>XQ>Im=eTMF>`sF9#dG(G0pmpwLdgowhr!QQ+D{N<9 zM%yp6(+}ya(uyVvTw^xNynmj1g6wXH7PgG9x&uiH(s~vXrv&#{Ud>uH z-@rY_p<@{!*04B9dl18QqMjy@pcek7KH@Ut5l4Bi=;N9|>YEBjS_|jZ$M9uv8pA{#meL^cL+XD!%D}Xoc(3Lg zN{#2tcm8L-6XLmPb5KvI6V7X{DfHqy@mxWv7}msSdZ5~)axYoYE-{jp4XXYW*9j84 z$eAZRFDK$~{%4-A!+$&;4=<*Sm(2KFH>l!4X1e{TFfOitv3+S;efgQw(mq%6d0pT< zxSqeZ`BGy0n2OW({rauIKuNefQczG`0IGp&C@5G^aBV?Bk>GpCo~%&cD*vC}0^ohf zu5jdOyiQz;c#4g=7yv8i$GUGK71yip zfgjs2#-U@ms)OV0f`ZpTV0jc0eKqhf^|iq6V?1x0cqRO(Puj#52u+ZMsE^?-4j2Eu z@J!VvHX(xf+)g|<3_m`X{?y0+@z-!@o7%xN0bht?LVP9(u$a__O+&ofREYkOc;p(Q zw0{xsu?e1R6KN;&x%~f3gV`qXjPF#>MYJT6=g>0~ZDOji9;Q=MP_+${M8p%Be*=c> zUgCmnX0kqgULEm3lav-MaUDMOB}mK6A5G>Pq<*iA?;Ii`^CXNPwwde;2{CK}9K(6d zHnSXDNIeHlB%3L-$<(NjXfX*1<~n)`Poc*Nt96spqKRcX%h~Ytpb3GDeuBj*IcsF^m!%G}K&f$C?JQq3}d^}!u zF=b>1+Y+}uhdhlkUZ}L^dObrL=VeVz|Gca^qzUA<=iCQZjrC0IlLhUf9$#75uHGf5 zuMYNBjw{*iD{G0;H`SU2{s$qx>!I2j*259(f58$n7B)HEFT>|!w^!G!XUuDow{77! z6dKgxXGQ2i#RUlVgOLC4yQRgP%HbnpIzvc&DG{9Fi`|B>&9 z7>{0#hAJ1--Rg%GpxTPXg*JDkVmkM8u9A4D&Q$?-&-nrlCgCGwg^!7GEX95ra>zC)^BhS&_+!Kg>C3<>1@|;x~{Di+REB4iBcHCFB1*jN26b!!KYlV5j3eQ?e zb3k(2Qs>-9M+SB%KH&Kmo4UVRM4nuuw9MS@i<6A?HemPyj5;mms20-5&;NxVzo zVPX)!l`VB2rlgBO^Kflq&?d;~V9;K~yB4?`AW8|a*|bXA`I*sMK*=PT*_`YUdO*@t-PU;y_;rh@_ehW1Ap1Ng2I7=S9BgaH^e1swwe+P|1#3>e@8jXn|g zFK)Kj+c|n&66?1R+n|x_(*$YxuA17s67hN|bA5HFoI+HutLJ%~%Y{#b4OCL|(^I70GVk%gQ7C%&y0 z%S%5!)%r+j>lu^v+{CIP-sTkLy%@zubc2TPJ*%wt+PpLYN^++=>meYZUKOf1NrVkG!Vc zASCg;{e13!VmTbn#$Ss#>9qaZ5icDZe@~h=eml}bI<`e&lvd&e3-Y(Jmx z%C+%XO-&o0MHDoIjjsj_m!(m!r&P%S%EQ;|2R!wf^B#rISvzj;4m^EZ?CQZ_g>MVz zK>XdP+Xn;P9LF1l@SMx;=ng&|QZa6e={NxuC#d4^e|T}gEPq^+U0YaiTi|y89X?Es zd@Wd8Skh2f6#ZFYLG8bO|6iED5h`)0930Ws1?7(7uVvvI=a&^01f-HI?(dB91c?`m9|`XbO5h9C7YU81iA*QQ-F0C^gmkgg_2&%c); zz_*}tR1i7>i0o)%VB>F@aZu*}He3R#p4>gxk=0^JP=iCto zh==1`T{>SbfXx5MGQzo(DV}gk&z~%F@w3tKKy_@qd09emu97Csp^JIXxs_sv^S^NJ znKIX$5vMr^UFXOR{9->fL3({qnd|Z4_m1%$ zry8pXySjBgSgNEOAKj3Wud9INY$?-a0hN_$Q)^?$k%@vgP9Lsg2|f{@7QR%af7WFx zThD9D)ed3HiA`8LgiYwhpNNq^%)@kSH?#bwV;`RIzN2gF-J;%yw(3-evQhhF64_3z zHJN;8Lagf~z8@3Yxc`Y5z<19$bRoD}IM#2m^@wd@I3dyJ-3MC+eY~IgOl;#mGZQav zg>2efqVG!ho9U|@!q!`icqUd3Ku!lMY3r>vlxrvp>W9!WnW#FRE@KTqi|43k^ z`TU{QQu4iP;u}j)s&zDs%m2VKMJ)C1!!1qRuFBIzPJC?}q9o|b=9+p=ZKRo}>LpD+ zbN9dN3q7>wXy=uIb1xXvB6go?=QS`K4cmNj{3XHRrJZXywLZL^SC#&mCokz2nq=oy z@3?5*Ik7Cez&@kr!R6MZ8S%$9Zh598r{EXi)+c+;81VVW$CtEP6R(dx-uzh8Ko56^ z{WAN~Uo6Tw@6~W?bRZOX{I;%Vtn%OV2Hp#=e&&CyFCU1P+Y{9K#m6^>Tle>G%~`a2 zaqDAER(W6V;~U3j|Hm(857gi;&eB)!Dp4`__D@)TSx@j#O<-#@fct4}KDN;+EnPBk zpv-TThFh03ZGI-)^uzw>K#f1Qv_hRz@YrqGsRm-b9m)pXi!ihS?jE#}!|uk$j$1IW zvZg(wV0|j}%bB-Af`ygvFtP9e0>bd~&JWn|)5Q@Npg}m^DU$Gb&q> zQb$NNXDHaY7g2`lC+oYlUT;6yY+uxKbzN|=)T|x2UeUZ9pHEyyL~ZP7U5SsQ<4cN5 z*@H6?77ttm$8%L~C&!;sYs-PNdmy`eZc$*wuEiW>)s*9yqnt7|eY-ZMUt$uT4(zz2 z+d9wp_0c;gh66Ye>hyWVIE~mhk-KPp>U`oHg>LJkx%+&xX5uudh>|CUr+=35d8#nc z&-Z{;{vW-UuC*#cyUz;$vLAo%D4b)vCPZ7OHu*fMaJ@QD>RRHOs%x@vVDlhhRBY^M7i+%IpXV(8skY|Z9aM3ph*CzIHjE;55i+!vUCieXV zayr<@M8ptRNYX@ZVqXK4a}04f>|2ENajm(K=o4AE>7NPg!|9N@?4K>C07sw6O#ihvlgL3wJlvKOES1Q i2P-p@!I5?=v9XLC*vK+Ko3oA_HYoGN9cwf&^8W+FE&S8~ literal 0 HcmV?d00001 diff --git a/lib/libgcc.a b/lib/libgcc.a new file mode 100644 index 0000000000000000000000000000000000000000..b3207d37c8b33c8d809faafe3ee128ccb926b7f7 GIT binary patch literal 1526062 zcmeEv4}2BHwg0()b4hNJn|~OQ>J3s0h?s=%N6XVBga8)hua+t`g#00~0YYx#AD%5y zsio@kp{0GcwU%1y^I4u!iau@8ShPOt&-#Me*7~PKYsKDZUZT-br26}w-JRXpnZ4v< ztx6yB`RtuNXU?2CbM~A$v$L~%OJ>w}G_;(Nd1~C9$|}mHO{thtHmxEaFExtf-*~)y zT3P9I1HU|zDEJqmZ!9DFCeFWoFVQW{MBghU`u-!%@$U~1iQ|VqA-W4RKOSWs_m&d9 z-{XO|iTL;#c=GY^mFDr^wM2aUV*mR;_FPRQAJ1Gv^nQ=udGmyz-2B zBu^sZ<2AsCd%S@<^09v@(fd9Ax{C;hkG^3Zf$Pb~M=VUf{F}*FbUOKtd7gZufcr!Z z`AX)I?~`-PW8BN+o4A~Or@l(Q$?fEuLF7C08S>2pzuC8w?=v{&ZzkVj9G`6?-?A9_ z>W0YIfO>p1KR~{V&LH2a$H=#KH~G32k?*nv%gCRzi~RYQlmFN@ z^2axl|5G*OKV>iZ%g2%bG?dSHn*5dX$UpO8^3Q#O{Absaf58LfKkrfUpAXv4KS=)i z8RTDi7WprFg#4?k$=|tv{Fk8opDW4#rF+T0VK@0Vo=*O2caZ-EwDI z|E*_`{|7%I|9?y+|6Sm>1LgNrkpI4Iv%my_5VePauC1{Q9HhAB5a*f$zad6d*qZ0>7p}<^l@jjHN){ehL&lPJz+26o`+a zz={17n9xFjN$nIUZ==A}P70inLxJi{3e@IP;Ou)Tu<&6DockyRKG#cu`r|3kG=>7L z;N8A~0-YNva4GW3AEdyB8!52ydJ0_k7zH+OrNB+wC~z~5Eqf_&J9urwu^sLH7wY_U z83lSuDezE`0>5acz%Ngyz#g>w8_4n8918qCPJx#o>z^*9!0S^fFo?20L$-G=r@(uc zQ!ucVf|)l`Fb7BePbhfo?G*gPb_$m4q~IreDL8RA1xp{HV8u%m{PfclJaah(t6!sF zZ6^ii-9o_y6DYWN2L(U(JOw}BM#1F=DcHD?f*0LE!PTcza4qUy@+t-YxtoIPCsJ@@ zjDpwhqTuE&6ufC11;34Uwu0B~81nADh=LD~rr?vyDEI<+{sHamyN-f=sMr4}1>ZWJ zg8Lt!;KB1Lf%-3Vm`Mg~sio(8PHZDqlyT zsW}un?G_51`8b7UZlTcZP6~Zy4uux(rqH>l_qmHGRQEE48t$dgO7Q!_atf_|mO@>3 zQs}ZPDYX6|g|6zQ&{wun2)+`!;SCCX{SgX%^IH_!Qb?iizeb^df0#l)MB6+36uKLA z@7qD42a756&`lKjZ{&|{rcm#b6nc6Qg?{q{g?<;M(2J1ej};Vp^+5{#Z20Z%N@-WzVi$U??C-~A>U6A zQn&~C?)?=0MLC5Z-$CKtNfiEd3x$7+_FjM-f4G>!ue?FwWCw)@Hd1&fLg7Cne{03!2kmpRKjJ$^_qi7jr6c16x31cW@%x#o$(hka)Fo`lwxq~t$@1l%pGbrQq zdnu#x3CgHBi!x?EMj4-}rHqA3DPzeql(7`~g{vuJMVK<0ZlR3Usg$v%kuo}7rHqTg zcU?PWeDO8PxawWX_{uuUxaMujxPd5R^W~KBZ~H0Z+ntp0y{jqX2Y$-9{Y#W_=XI2^ zBTgB2@1%_T=1@itc<+9LG9E$w$58*5sQ)zT{|5D+Mg14i?#owF#y*tyq5dH1zZId3 z{TnFb-EUFEe-=eT2PiV)8x+ZXh9U*M6ghVyMV8)9k!9m3Qn!^NP4`d)a!1z8qe#c& z6uB7rWsg#1{j(Ig>U@e^jr_U+ifp=$BAdrjHez1-rx4%u1Z5tr4f&#&Hq8$PaUKY(D#UEk^c_)%h%Hg$UUMD z`QXho;;qp%Vn6bCcTlE(DrJW5q0FquDKmEtW#&IjnIkJHbM!fsdBT&FdE(oY`Kb=d zoX}61lP;pnipwc;+J4IXbSGt2T}_#@!jw4&`8hXJ=AzM*c`ot`?xf7R36#0wHp*-s zLz!)*l)0vtG7|%oc}W{(u6va-ztl*X8^HG~;Cn6j-T=Ov4^rk$$ZxrZGH=bK%pV}f zxRH5RF=g)9Oqut@D0A2Gl= ztLb{mYR#mqHKQr3<7Udb82M$$*YBXLtI8?st8*ypx<@H%Qw?Q(?Lo@=<`b0lokf)O zy$;IS`UYj)j{JwncYyER8!78Pk;I?K>k15DC?AQgq!*6#deL6ushEihgB)qSv-l^m^nswo&w^ zbrk*f+Z6q72StCdfujErr06!}+liw0XqdS;(~aQHs7ihobwC_tj8z@H~nR{hFft7g6-x7RvU$O4%Xgk(Vhu=MBovUrpIX zNy?tPpR&*HrtF0g%3iXGvM(4(*%#hI*(*+>?3Qhm-8PT1*StpAiR&nP9m>9V4`p9* z9%X-JFCny1_NF*xZ?2^5Z}n65cXKHF`;#d9Kc1)T|2#<9J4RFXJu@hK7uxw*CT0J8 z0%iZdXDIuB(9Tmel>J-C@xqmq{o+*0-Um7Qx+(jAA;%ji-+w1%9|Zor2Ph}>GUbf8 zj&iaqDW{;Ha*nx?a*jKRa!OvMoKLn>&ba-QGqIa;%5R~ZslcChC*_>^H08|fq@3A> zlyf%Vh38Pt64bo_@P#*1&Wf>=)3l9pzVHa;tU+1FuPNu!APdTrG$Nz4ioHwUa z&R-5t&R=h&T;BxB4L(4*nM0JDb2;Va2PwB0xZ@t9+!LB9_r&8Vcl@iAd&)-2tvH`@ zr}b0rr>~~mGe=SGtWL_E8>QTNn<;nEBb0mImnirAsg(Qq-%)NO%33B;?&=Q8?Er1p zZpyvvLdso#Gv!`YL%CPKOu6^AQ|?dEZqKEZyZa#J{vw}pAO8mB_JaP`sQcTUl>5ST z%KgJ4%6;WY%1xd}xdUyK`{n@UVjh-zU_ZrtITQ=tNU_LBisg)>Sl%{@6_rx#xU(pB z{1X%#a}LGEHB#*4mnn8C@^a+U4^V8zI*Of%yf#L$xtl3=b}_{kms9M#9TYns`SKcy zH9SnQmB=qb-u`Qfb)HADOOPY>#ja?l*oGmBT^pv@^;c8uM&u76|8L0i*liSh;tYyC zeI3P~0srT~|3%>bIEiAf{)A$$)l%$@jTCzuWd~29*n4+UUf^`f3qL`5*<&d$ww>|{ zODS(uE#-XzxRUcIZ|v_V?_`us+DUm8z)fF4d7nN&d1qcvd9z-oyt$WC-r0qexA-K= zJMSlycm5*E`}|9k*N8eRAEdl*E~UKhL?~~|F3Q84G4F?d%DWSEJ31)uz6#3Q1^k0G zl=sl%l=q8QDDRi6DX;f!%KJ@>@}7N^@(?5PUIN{#yD9Irb(A+yPI+$+QQm<~l=p5i z<@>f!e#TEIKkFRI&-pdw7YLwzef4% zw^RO?pP>A&eu?t`WfJB8Yy;*09Busq^?rFfT!RO*sunhH9^ix6e^;B@tBr3rDVnN~{6LPk>n@~%e|?t66ub{#y_fp|$GpKOJgH%}kYbvZgp9<$bOND16U))B8=e*jf!eYsc802D*8+X6)mi#q9u<|(Ng5sEv2G=McuDm zM@9cOmWsa9Ohw=GQ_(s;OxA6I2BIDta7zdm+nH zd#UKzF;w)z161@P%J+e15_S7g_YKrVABx^V-S?)_$j|~BiP$zWdO3}Z71GF&=hMhz z-=LA7xQ0faxRpkJYC4Ua&`TpHEu)bY>uBWkd>Z-bTWDm}y)<$baC0Lxa^6lFx#(>g zdETuw^89mXul*-wW6%9p+3=6mss0MI=0Ibn`rT* z^~5Haw5zf8;za9YoYgnguV}67Y6Zd#tyjZcXq8#v^F-|e7ai8?IKr!iEp~JvuSl>qFI)s*{RXBy3xg~%_(vfnD|v) zZ7!(*Lk?VY7ZxzED?805S2me>n+3O7aKoy0vtYG_Xj&`F*wEMkinb=ZpAC(Go7TEv zsaz>$u&vXkHb93NgDVw~iMv*>>44&;O9sNO)hKChy|l5}a4pmD8_QeQnP^-OrKHO! z>g?!R-GCCATRC4hSb>aemaU@Mv5JIb70tF)xUh;k18Fm8}RTjpj+Gg)zI>2Hq$( zfi4%sgQz*`ic%ZF{wI$z<~86^#%u#FWt?<@yM=0Ns_($y+R$QH`-%jjf??e_Gbvz0 zB2wVYWDjezaC~Os(3XYcGZTlFEq;7v@~c@ge^K4Mxr>+7)uDqkT~Kp#!fYNVLcVo% zo%K8pHgsB=YG2ddu%>Hur-c`wSy4b{?e_YP*3QeU664&$uek)4&HZf0nd#4vI?=%6 zEKVAY6R6e1;KanNNL*6iZn85@g^V4E6(+W!4W}j+0|G`>jai~vSro^Y_Y&Rn>|VB|u#3rnqj@H? z)x=~nAZZ>&lI9t5ahEi2P`bFd8jv&(%9f_K_NI=tJd0rU+n5#&lh81Y8m6UQ<&)4b zjT#2MRI8z@8cG)coz|#y5peA^Dq9E)1Bwc4j4gtVu_drEwg5K9Zr{e(&D$8gbw>p@ zk)r|!r3>Jwz@gGba8%$>*+O6jFWE3djuA8D*cn5P85@+gof(ua$gyNDlT6tF-EBz5 zY?QiNkw-yh<=C@H>}poIoJ?V&?Ca^EY<)T?`-(a!Tb~ZfzNQY!rBAa(=c+nn&SjNw z9&$JrR-*He#JRK*oh=Ijq%-~jaE3ns&gcig8T^>c9_^S+2Aq)(CFq|R6&Z3d#}$>! zT}zRbY!%uVTUj>7zG^ncxk3&~=Z(HtBZx#L z1{DXTu`jocNf4FWSH{LT7g|Eu%oDD8NrFMga}3aNPXly3$0W9W!z6Ztj*BJ|2+B?* zGeEf^l*$bOlp6x*L^PwW|Of2b&iQS;wBMho?Lp;Vx4FQxJ0w_1c#1dyFc7sksD07v;A)RyxjlyE_86Ai zGw2n5a(f27R1V{p2H-As25AU3VaJtB*zqNc-gXy@UV)v#xQiXe)jx*i{xK}~k72og z2E8P|L9f7$g>>Ki)Ou5~5@7Q!(_3*p$Js3M}CsG-1i?6k_!9V;vggdMsC!VcU5VMkHw(Ok<~ zMRP4{-JL)Um*!AGffdcQtc9t|sszHVIUwAc<0>jswN*^z+)Uk?gV^F3j_9ZYyETVy z84Eu`v*?x!PNJHHL6Ak3YUl=P+)f#8rLeC1Hx@{K)5vrgj;i5 zMQH?4ST-@Pq9ELwgV-)jL2LzfYYycu%{3}E*HZ5ugIem{oocCf_o=1c-6fRU5!ZBr zdMD&s2t{!%^@`$vP#aMc$5mWv;VLS^tvGbdr5JQff!&Hj$JBC{;!y5_6N=&zisBH@ zTq6=@a|-O-LmGMlfm@S_dPQ+SxGxS6Y9or`xQa_pTt!8=6^D+w6oHN@uv>AETP;@< zB~N4& z3dJtfnG6h0u}jP{R9*7aL{Tr#MRb(bn5s){3WN3)U8<89P$;^D$ZqAT^BC@wTbDeO zaVdspG73V`B|^GNp>$83+dw0VE-~*=b;*+zMR7o>ZqHP1|79W#qcx}KQk~X7LPeJl z*{w@;X2YFw>r$QDKvG4Q>g)y-iY`&b-5H+nxUL7Ps0ip%A%QAYjB*t*qtTj%B9(yw zL>fv_r8?0;pA=Q9Qyr#IHK(Xjo$Wv}rAO*~2NX(wP{pk%R8bL%DluD8RLK(>w<>u? zqhYkB(MPu`QB75)I`iR9x@`^;s|dv^LE%;<)Zj*_^B;(z^hlinfkNpI&w*U_#B(48 zp{Nq`7e$pk#c?Z+=QtWhYg$vKF*R~)SDg!SC*7KZ#418jB`8$QxmCHg)!n1Dt?vG; zZFTo%ZL7O4pm!+^^a||O;o4S3g+Qn+DhdRJ+9uQ|Unx+itwLEcMT^qS7NwglN;g}S zZh~In=WY=6O1aX_7PXr|xHSueyPI4^WvaHSbTgrJGof@7d){2OiJg%O>~0bCE(t)d zz)Ck0YBzyUn^d~VRaB;Gt4cQ;m2NgF-NZgUSGTZdQ-R$rg5D(o=oMJ$W~16oAk-$6 zZgLfssoJX2%|x@?HxtcnPr)8LSGTZ_N`c)ig5D(o=oMJ$W};c~O(4`Jm2Pqsm8sgQ z(#=Mtn~h30v02pBEo>xHV0Vk4cS!(x1y;J*sCE+wwMnI$Tt#K7w(4{f&vcD@K6ydh z!8y}G2j@(;9h}{ugR+}+PSfbNpk=L~a9p590 zz~|s}1xR;_4w2A@X(iOnBg2IR-I!ytf(-a`zM#^=CJxDlB0rK*+pyN9|RRMf& zr{greOE-89H;+bj1sHdER)ln_I%Y57GzD;7wX?u!*FwJk6a3^=W(TJ$0Cy&u0;J_; zr>fSfbYJFB=?XAz%@hR~_hvdyQ-FNKCbi)qiarKNH&mjkbW7!+bW?ODuo9I$BX@Al zl-$AT{paOi%>$<5jF(zr2(z(P{nX`!UT>oTW=qRk{yyP+I?`dm)F)xg&9KdjI8H zAcs!xzkC}c(P{k$o$dhA+NNAr?Z0&EBFLnh7YC*FU%G*DsPz8xU5q+%$oDNyUA_PE zy^BPr^&fOv|BV|M)ptCuKP=In)rdBL(`*qqO$ESdvT$8h$6VI~r`aOtpafN0jMWDp z#_D6T!NH>`eK0iYYn0Lws;vxZ6;;CN%0Q@79T>gQl_9ODO8j(XAg(#SKnq7HKO;T8@-(x-`3zVU1+$)+wLYS5ZrG9akQX93oz8=d!s5kEs zK|!ZC?h!*lr|UvmRkU@1x|*?g1y(TBBMT$F#DQt43NnJLWk5&U5k*yLCDB1?3X#?m9V$&B(yF3Er6~mKg4%d4 zFE2V(b%lUVQ;59IDA!dL!gW=gwBRVJN^6b|N>hlm^5{@$3X#?y9V!nYbcM(Zkxo@z zA)wO~BCklwb@k5c3Xzs3MOA5a(m`nok=7_3Dor8MN~J@kDFkbcx`jwfmQGb&A*ib< zL|(g;>#7Rjx&mizSy|09boUb{Mk!CF7^OUyVwCb^YIQ=}SivZbm$tcrsWe{Tugaxu zEx?P$x?Gt1s}(Wx)=`>Vm^(mqmoTf40G|_<5`FR)yrVu(m57Pjh&d z&dj0`$I4|4&X z#!s55+QW+S01u|EK6o}z_E;uW)P^W$V&+ik1DOX$p~Mst%Qh5V}I-nW|G&SBN}QmFPSqfx{_E=ejCRnyCtQ z(oEGsX$p~Mst%PVhBQ-ks62$w6(Y}6ovOM*ir+3kMi6-sBanX9JP9Cz{)ZW5*s*ag>isz|1c?6T1lm;;u*30Uo9Xu{t zFV$fr^pH&&)7%_9X+2dZ4{k0Vo>nIhac*jF@jO*0k9F1;ujKpkpMizJpJ^|Gv!CZ{b0lJDAZdzTxqOGZ}>C&c#u1U#d3o$+#Fc}rbuQxktQi$R0J0h>`;-)2YQ0yWr<_q7S*>Vnr2xtUe`&1~^cHDN6N6H#7XG|Ni|ZhyO~>$J zhGnU$q4Z9?G3&5nvIT4STWB3kiOw}0O?3_Y(}7PNkdARNLr07X=hZH7x3akY;-)$c zE0NdLcvn#It}1n9Q|mg{)J^6~B`I1oR#%gPKrs32*=H~HYS#lVSDES299LnyxF)J0 zh^wmFhfQypfS?l=;V$of~Lu+$uLrr}r21TbD!;6~Qs_{8i8NCD_ z&9u?Rr`Pb&sKgqK4*1$!o$6_ZG^nhse9Bbo|Dn`R#!gyuYNiW^55{UZ%q}!smj^Ckk{M&)C2KmqAbo{( zsllMWV-@!g-(tWQK5Yy>Wq`3+#^7UknA2dD&t%BeoX=m{^-NCqUZjmNImsB46Mt0E zCNe%&iTQoAib*IK^JAuND#i&q<4d?!STU*0Z{xa9_6L;CUAWLBaxil=%wi2wqhXe4 zm^oD{=fxVPM#C&IF(TwHTqq=zFqVW8#*$FNSQ1JYOF{`_Nho0~2_=jrp@dN+oTEty zj3Oa0iiE%@5(1-0$b8(|U_Kf~k&yYgX%=e|0;5O>j3Oa0iiE%@5;7mHEk#1+qtPf5 z)@Tv}qeuvhA|Wt}guo~gG9P#A%tym05;7k*%@R#QU=#^~Q6vOLkq{U~Lgu5jrAWwp zG#W+1IaR8s0Ha6&!>PC=xOsH_c*ALSPgLfl(v`Mv)L0MMCDI zwWUbNd^8$G!WvCNU=#^~Q6vOLkq{U~LgwRco%v`OMMCD|rdgs%2#g{jFp7l0C=vpr zNXUG&wiF4Ok4B?N2rIN=iWoD2Q6vOLkq{U~LSPgLnUA}5=A&U037L;ZqpA!;a8Qgp)8ARVPksSkZx?1x!uHmA>^pl?-ki#5$H)-<`YM;P^#v5ex_5Y7nphJE$U)vHdmu*u13>bji$L8O>;Gx=D&4Kk9Cp4+r+!9T5OEk?b(KNS2(;WCHIshLHqiPO( zG#X8FJeyS%0Fc9)U|aH3@-HBm_p05Ew;5U=#_NkGpl| zqhS;YnU9;MMw1X2MM7W{34u{01V)jN`Dkq^5;7l+Mv-udCLu72guo~g0;5O>j3OcP zaktKVG>jr4^KsKGu2nq+7)3&06bXS*Bm_p0kojnBDH1XtjYg5MMw1X2MM7W{34u{0 z1V)jN`M6tWJ{m@mkolN2V*drNl+HD7%_Phm4YOFo)M%I`ZVYb06wbgXoPkj|^NpLv zN8yZH6ooV2+PG`+osEW3IDjVJek9P%3*^yrOrEVH$g&ROJArvIk0K53^U<1EuO7D3v`>Dtn+*_ON}G zJy0rppj7risqBGL*~0-;_CTrZfl}E6rLqS~We+b<*#o7r2TElRl*%3`l|5WRWe=3f z9w?PPP%3+%RQ3z!S~m(J0HHN2L`oPdL`oPdL`oPdL`oPdL`oPdL`oPdL`oPXL_!|; zt1Ct_N|#Z@afy`(naoR}TC6E^v8K$$nlcw_%3Q1| z6MVF`R2jiXqtPYQl*uwKF(p%I8)s%^fs;EmeWiHW_xkOXu z5>1&)G-ZO1A|&`|7*(0zqtR%}Di4Gs#dU`;tPcl>k`_FzG^tc3eICE2aTml3S4+8?$;}UQ< zGOgLoR*WGE*0Tp+;mfV_^=&4-IQLJfa9L7R$x6$2w2Y!cnw6%*Gqw3mw@?t(t2D1JGRPQv%{+! z>Cpu{$hs*#yuc2%Zb}ae0#99fJLbBpdtCx2@+!2R@_StZCj=`TJT3ufJ^SEw37D_Z zwJzR4yb}L+e@Zj{8a}~yTjpB{r&zn3Pchy~V0`AOrS5IPWff)9rc_KRn>INfFDorY zsr@^(q9PujT5j$bj>ng0uAeop*5~t)NIn`z4n%ajSrDo)@^KWQ5czkmt(_a0OC!#k zOV`)Qh$X^A5 znP=eOzHvWdI7Z-*`7K4IQNW2L_zBo657^R~r2$vV%wMH&a}7WmmWQ$VeE4xTR=m#9 z+0wOYMH#k>C-5c>-ibf8+-4IE;8 zZKcdQ{(Iv@E5DRzSmJPV*VC+bGt;@#dd=*fZLwK=-!b0byZxQPf%e&vAI%?luk^h? zzuQCO_xJj18B6cvm9)=}qTYK*KJs0j6U`=uMPeWP+hz|PO>L93yE8^MHm&Gd$$#XF zw`DkFTDM?k6c(h-_`M*j!0W!u6$R-vZr293lysIET~N zX)AyS0cGOg{&BlP4$)Vjs1d*!d}1ZRPrzQe?rAbd?pM&IE4SvjJY>sb@@LIBDS&%h zzPn{vMC{9Kte=l{zEBP$oSr22m_qINSeCe|7n{3-EA$_H|F+?*j2*#Qf>@tafp_=}pWg&O-vZj<;{0^T$1zhRp%(#rvkkBxbDS5+<;RxqxqKHFf#(Ou z<3e!miqmda9X3u+pFTb9JIYs00hKr%>_sHDd{vLtQPfE_H;<$2Nb^~iStQ{Ts?V}d zq!XK$2u4;eY*Y2wRCE=nC+aW@ri=55m4tk%&$guLvz_3Rj?aDrbm{o)mNb2~67n4{ zI)Pm7ql9*yewaQRN6R8M3n5%SYxRHWzofX3C`ILU>Zi6Zsj5qHlnWhq@tUMis02Q>N8zBwthb7(s^3> z3+*)7P!Jk(fb|zC+Iu*M;I1PW-(Q7v6vM`$cU~L3P z3`a4JIF4~RN^wlbQHf&?js-ZD;#iKO1xGuMkF#~kS3lKgY7c|fWe`_bwa!#@s&z75 zI@Wn3=w$gsyPOM8Vv%A1763WiXu2Gx`rll^N`jw&z4COd)6K^X$$LLozhX8oyoh0* z&9Enla-QL3OE5Tkh$nFRkQ&ZkK5PjG&k1RK%8@lS*U2f!CU9RQzXb%4n-P$2_TWMHZcOp^h8 znbzTUngk^9C0e_r8Q({>fmRtv$Us{MWuAJPh)Tx5G3*#~G>X9pq$E5+9Vd=PF^-z> zuFSf&L`z3w`p?UzR!lQZF^wp;&Abw>DArqC%Z%hx3HD8$5@LP;H20yj~!Z=!by4 z@((gXv938Hk@tewy7f3XGDz3jef~KNV?U?D(vEvTVr8CnSfI!`#9nOy1 zKVm!P9lo+13)s4EH4WCW<9cDoxO+`|@50|Y7T-`A7`@3Di@#QRtT7fph5YDPtlIF= zvDj-Y#-Pi_>ez4_X1N%P@wM>PO)DFl%Z=5-;nrQIP8K`NhQBMm89s&N8jG(OpsJ7i zdLgg1iCzc@F9e;;Q?$!DhEO{_pXRvBJH&Xb6G`wBuvh*; z&L4Q65|6ul_sVSx*c^9F!?aDd5ip&K@AF&J0V5mEV#}sa!y7uBhPT+DdAT)<_3x#g zs|ILh>D}{_Rl)hmnW4?eP;R7WQ_`P%LeG*UMbAz8qwAB6%ho5GmeIgV-Sd-6mOR~e z?z#8&tg4Q_FtMgP>Gxle3iWJaUx9%SOrDo4nC$Px?7MGffLo@4fA8Kp=nMX8FrJhBoc}=1!7&FyZ*&(|4U#W# zAO~kN4}{+QTvg8A9}LDrIiT`Q0RG^(o_PcQD3?80ys+;NYkdPWE8|z#2b1&sAVt5_ zN3^=n=ljuH-6tIP)Q{ex6QWPejnpMeX?}7>G>G=*CugQ z5M3~c=Wcz$g;mLruk`-94iQF|;?Qr?Q%9&Hzm{uHs9+`N=XI{`M1k@(0$>{Mx|!`Bw}qU)VnTMzm1a z!?4-L@=lhw1igr(E~N5DdW;gZnz`43VY##XzcQ^=NLH7;VcD5O&)+$JAmFb{J|8Xa z36zW6-}k&9S2aKf0te#<_*w+stxV?NO5uvv{OpyF_l&$<+&*HYN);J+C#9Ukh^o%W zQ_-oBf$7qT43B^=oybswg~W8$J~v}1en9Go=!b;TPCv-Vz|1)^@RKB7>s*IO#jtof zF5qz}aj<{^7=O@$ zuSwu9TI`~()^fYZRbb-rZfMi$M*N$0GuBhB4V%qQ4fCH|?2@iFr-=Uu#x7ty9@I_d z*ecSn(RkWq>s8s|qw&2S(YXC??Angb8`|48I+?fR6FsAo1?O%~MsvT8g9d)Le_{=y zY`7#jZ{dl_d5bYlO(`};(<+SWGcmqT@7?l_{|O#DUwp^^$M67E?|momN5J71-wB*| zGe*JUo^u9#Ia>$c3*Pe$9xeMnfe;%()UbtX> z@`*`12mcz~*t6@cy=#tt<^d5Eb3{~ZzaOpC)*|LtCjA8Id^`J=1$Xy6-4_j2C4&pw z?`PQ{L5^<*z4^oL!ojJzzw4nm#^0)T#4QTOXG}qaJ5EHn5Fvh>Q7-fb^8{se38-Uz zPqibSyguinh?o;|ELZX0@{_WQXc+!L!kww6ne zMRbnl`uE^!Pc7KPbwhg)L8p#3C^GH3RZ{eY)(z-VU;F)swyA&LzqKzEMEf}$m3fv% z0~;~F3rwCr(0%T#WI@5qWPSr;>X=!{yrNmjSkwF@os5)3mB}bsv_WRM_bI!rcwJ@b^Z+c}GWcim@_zLs&iWpb<%%M-; z#ZV?+y^8fi6?gIVTR-&4yZGu(+{aLuujZ69hyHpe|*`U&+h~jTtAe37c3#P zeyH!x{C!m=7-B!B&-TZPX#+$Qrz|c4<`mOxz{lQ=2-W2zsZOd?fia9r*9oOsI4*!Toc@&NE9fjYxXQg=i?ARdXGG=Md zH!)6as-D>M%rR?{e`v47l5P8J!OIv`XJqVQp3L#r?29v=>izuwU>2|AY`|U6irVYo zmkqT9S$ucnjf(eZ+?*cf@4Nr({gKxh6YcTEDgOEWk$0#^;3_K@Njble7bwR0U#Oqb5s&Wk>tln^ibK2H8|M!qsV2r5HQPnrByy!fyV;oadVwjeu@I~E(f{%p8)?0 zjyMi(?;Pac!NEFVnAh`Un4b^+Czn~}Uqt>h3BC^Jzmni@aT1v^EL}^vtV=Z!tjRA;~4h@O>52E+_2Zs*a3<*{7t8Iv(V58xQYM#S`fI)m0||l z`0FJmwE;TJ7+k4a_INvL8fSNcK3)`(E8+WTrhv`i(KtzsH!X&c-N>@wBQ0wLhkF5}q%J#Qw^O#r5G3 z9=06ka^f;h>YQY`fpvZa9k(HmJ4~0(xWj&!&YXk?p>EI)Hz(-^9j^q4B;*sYSFVpc zU?Qc%*&oY#V84es8~PQn>8HYYU9QrFKbPjGH28B?>pxzH-B&cNRNRygKf`$0?1^gG z{`|Knzv#)lU#%IsH1XrU6^rtJJ3sle6K7%-d}eaNVyyekKN0J9#aLm)Y+(Q)Wj1E; zrJ+42sf-wJSPJ~ddrfbFbR|<+{|1SMPleT})}M+_wSJ}>Bk>gc)EPOi9i?OayoJsO}j_Rig^5Jd&X~=-& zvi-9t?@6}(yeG45+s}DgwtcpHVcTr;Jkq~cDlk_s$&K^W(Q@^z(!7F3bKc zR@&yxPd@0Mmt4@k11p-9eOD1y6OEZn-az;Kl05~3(>r$cfUXjA8(zOmE?TsEu$Z6i zL}Le{SZ6e118T76%uhabVgS$Zcx4OT^Cs>l1CQhR+KR;)yzVpkc-+grTUj|&i73K6 zD-DQa%Evo)Y{7LEDV0B2V~ik6=})QXRDWW+bo}XU(52%~ooV{h5a>Q(_re($B$Rgg zLHZNl4aoi^VAG$RKfIUxsoB}zlK7DJw{#mG@$t6Wqx)MlLv z0>iW|w%Od@;(m!>xbeTNVp`fy)V9NikzC_HTP&|4UV$eT)pP=ObW{ay#Jb@6OTYIh9rTcFG0S$DX_qI|8uFV1DHgQG8&1CEpA1eF1hY z_(}%WR~7fnt!7SV_TD<^^H<@Cf2=P`58>%Qp85|G?j-!bnp?fRuadUEMY#n}Z6EAj zAAYJ5Pf5yre$;q(!onwiWJI6c3(V-ldpg=@&!tN2REZ5yF7thT&-Me|2e%DIqC5Jc ze!>otJ9?;Z_ku;$#WQ#H^cuU>d3VDVkSg5M4OxBVzE9u14{!~!nJAaTmX7tcoMttJ?Av;=u--?l_4UP@I z+G>B8wRs|QsvPQuU~=W=+cS31DJG|g2{0AZFn9_TRqy9P}=DSIf}JGMjpk)UW`Ty z7OU6-7JD(4Tjgbtibp;HpMmpLC>x8M`OQ;c-iy(N^3hg#lLD^=d;`j_v&z>iFyp_6 z^2@FAn-tibE10X0&CXtng!G)J+1_j6!YX?$63#9N?6qLP*oKj4l?o(0@2HSUu%p7R z;woVLspVzjm7TQa|7DXatWR#FG5|Jy`_EPLwd?TK>ehtT(-ci`I z=!;hRi+KzyIldR;Q3FD~n<*#2&%iGkWGyRr0B|7f@x=M=J)``~N!O z6VLqEHEv@x#kh(Z^CCTS`K|(cCl<{Bnibu1$WEoWs5-m>73-BHX9;tZT2K_vLPo)tVe5e1Vm+v;d z20ZR4fS*fwh#0<4{{_1dqP~CK7qxm@+{69N>@5XVaZee3pV@<+li51UeGKovn;)sY z0p~d87a~?fbA5ZN{keO%ZeY)6pruG{#IEPuznEuyU*oOk*4|tD0)E!?T>t!JWqca+ z+`V{aGB0mtGFHGkzP5UL&jnOH_(eZ<3Pi819@}%lDDK&h`xfSo?fHJ+Lg;T9pc@S6 z20%9h+G9X_06kB~`S==+9=&(ZUniXT_JX^vt*%6T6!&v{RrrdmFZaG0)Ak*%Zoh8p zHUb^3ANt~5tflos?RQ0LFW$%JL1^sEp?QE;?{oD2*dCl$uOC`=7p}t0^+Pl6s>9yH zsuDQy$8Q0P%1h#1~J_jiw9?dpBjVS23f`3MMyZ(us6MGrMaOL*T(^t*OqY(|SA(unR6;J=@*hy zRyLV=n+3O7FrJm01*XZ6r)R3RlGb}yHSBi~N=SjT>vGk;#OILQH z3&w5;ep1hU<|p-AtbC`HKgv071fI8Y=Se+;|4^RPJ7cLiHb#uGkB)FbAH%(h z`iwq*u->?H3GG3t@|?b^1Py#lXWH}3z8k+BaXGQLY!&8Bt!Y(^7fD!*I@9hJ1XeES zRLf_&bS(c?(4}Mf@iZ-e3+O(|r}V6Aw)`CAtQ!HF5eiS~*|?oWYx606`DF1JGObmM zsej{B`fAE~lI=drw)+uyMsM1^{Cr;6yZaga$NR3b5;_+tm8~0LR}di=HmuruDmvBH znJyh$|3`aDe+K%^w$3v})}erHTgOv+#oW!O^yO2mw~7sOA9h#D(Jwtgxl&4HuN4vv zp9(tFUYRZ(dp!?y>5R=!qoD<$QM`mb?96fbwoUBVQkTeE19R3pH^y)UPs3;*>>RKMk>KC`?v7_ zRF-qp!dOQ_OQ!BD3!7Ya)WV<;)pCwnm}w>Q@B53Abq#In60PR9i+B_pZnwY-Z{WkWR41C;oCGv`{NU820Y?Yc!z;Vf}eoB@^mcC&BqP#*v5Kgtk~aW-Y=NOh+T&`X*?{e z6yJ><-YU16U2<6^jnC|1%f#1p2I8e3?|nNws}?Dhb=C+1D;N4#tuqy!YMo4%j&<_0 zgmkR)WeAjxbuRgct&?@lcel26!YJ7~I}dNnEKC1wqT9_Y=CaNQ@qG!xjtaKW2M15U zUWkwP`b(kN2je%Dh0c*^_%xM;rlM0VloocO2myWew47zlzbtp}1ZG^S*N}Wie9|HEuKgej$&!e32)G<=q zV!MRN4m%H>ES3+4kNEeR-Exho-^8vkwpg}Mw%AP)95Hq+f4s-ovC^eVWwlEs8a@?Q zTb%`@qEoGw>C&-Uez!jztKFZb)waNDd7KkT^h3a2`3GsW+-KEl4MU|S2CU7+-ZV|B3m^?XT6I@+Vrr zUkrI+e{ipVdvq6%zftr+{@1rcNo7-U-g12)hvzy~CHQ&YPcS{d1oC(NXXfcrKZF;k z`;Fv(K4z6NT?EG`aWE{_UD|LiCsY0UmqAj|RiLt{!+e--9G_T8$X5!OSH(rz1p!$1 zj1w#8EMFB46tyEW(q{ao<9+vlZlPJl_!Tm74o9-ng8;Sz!nPAbA1t4cL+FHw`J0WW z^NE!NKLLB?y7$Q(xnCdLKQnXt?48F*f^a|h`ijIb&yb9NVz$B#_A1K%xoZ85R^7_g zU3GkpvbvV0w)UnDRORc)`*TJk_xi`UQ|&$E=Hke(MsRxWH@-D{YN zPW64JOUL)OOY$Ac_cwxHI=+7g=+g21ooV_$|0}y!Bu6tT(?{X^#ga69y-!kL#rN@L zveeEm3WfLcoRxi_XCPj_U&kLhbN<9&*cH_2Q`4WhzH0Wv_Wew(=lS394F=w!f?MAq z-?26AvmO8TU!D`qHuian?z1kcCgaD7>Em%4nl|f{vniaNarOv*W;j1s=qvIa6Dal_ z>l@`eE->16ynl?3CM7Og)mgs+d1r^2w}>vlaf1_&Idbe?VEJzZc&6cl&v`E_irSGG zsS&^27m-9;d@m;Yz-2e#IGazbBIk%d|75Df~<8S&L z$}hR>NcT(bgGk~EmjJ=nP1s_XR2SOqANu`QHNPDT^xra;r`C1!yz`7suUrb<8+{5>< z_;@(aaHdzJ9~TE$Intb%zzr2C;f z_YwY3f_|~>2tS;Mb2$mSQvEO$o$7~77nc}{b|(TS`{9f<{jd%7((%JBpi9ROyVLZ; z_z~uZe63UXq3LZXFT~-OV_=ut5r?}s{Q&&%Dc^68`XMfZHcw6EUq}5gy&d~v++y8+ zl=1KoerS1{haWbyHPv_EpKu#mn$mf*WqP^wS%NhFcj%MyI!w`AI$378v zxbxz?1m|ogBKA$^LMaIwQhhEJof`X?E-vvC?W(bFVw$mUDR`w5`>q3BIRq06G`Yrz#^CNAEnQ+y{3wNj%RuJU1vxAs`fQ)t*Z^U8+LtW%3-`&v(;3R zeGkZQl>Oc3lkfA}>by3}*HT_vF~v83S-+f0a4?0FTksv>vCc` znO5*q*FsuA=e738^g>pg67MBijvP}Sqi^hwF&u3Fq7OKw8dQ?kDMY(mCMOyHe(YW5 zWvq2L_e_~}b*t)IR~uV0j0Xk7&Bcz|;!#@^_Vj_)oswCk2eB`ZAnhuXnSJ^PGn5KqT&$$9lKrtyI5aO-Cn_ zaGU&GitWmEzt5D?!rQQZE&fn0jr)wCsW`>2BX_SIgj$}9+;4tek;XCn=Vy(7vN@!W z^Ru<;e;^-^qdy`EA5wjM6U-?BqTzgeiC|>q!e&(;PeoUOdZG@qV7hdC{3ggJeCtp? zemVGY8zPCe)Oj5HZ8|=_D@`A7JHmWi?0HPn$9XZ`_Hlkj;O*m$jfmZo#Y}QoA3uz> z^{AJRkB{6Oipk6w@elO_K@%4w(^!3go%-7k*(~ak* z2Rpt#26a>Vy0pP$SYJPk{Uvb^U!Q*WhT{l87(#iyzK zKNX$o|4hg0E+Pr}RR7j&G>=5WsqCqljw(Fx>W@0n!$NBP{4Z6eKe25aPT<{np~uID-f zcJgC1vp)qk>^kEI@Z1nzwh4qWMqr&`jBm`S`-<^Q;n~~+#)_iq>xI%4iR1hq=~)8z zMa)XCbZSgzx^$i$ZcX#q!A9^)C#LTLT{p05W57@_`2t`^uJ576>TEf{{DY`?=#PDMG`*E*A!;hF7WIJ>G(nm z=w^sY$c0a5B+{H`k>Hy7@q2}g0saD`58nrszo?|YS;M{jyT1kSfB35l6)-Hea<&?_cs}_2 z!}#jL7PQ0O#YZY{D~5bW(%ao^uN-+~@3X#@WO^CO3vsx1nW99RNDl9RhcS~JLR(07 zWMTg+{gLlP;eo~Y>Pe)Q#=p~Ba^evF;WP?jc~yvEk@z|s>AonhaED#5{{wHRX; zFj7ilBv;?kNkvzRx}pxVVY)bGekAH~zStJ`K8h3$*{kE`VK`vXWpD}|I4 z9wue{jVbaGr@#MrvZk@Vvz{g$fp7Y;xrlk8;qTI*BE}HL!!3D8Fj56*(it20AB$^5 zCFFuN=b}w6=C7-4Le6snF-M5uoW}|j*@^F9i*3l^C!vf}(GCOeXI3op)88HuS~02k zZ4og`<__lhQSQ7!XnepB?q0_q<>K#u0$H)8O8HyrrhAij}5 z7>`E~gMGCW7Z`>Q6^G;C_xJakrnX6qO)I)q)-~gu-=_ENK#-MJU-`PrZ*au{izKdE z2@p&t>}rW1uyQWrq{iV?bfusbb+{hW#recaqFpr(*FXTaabfRF=QStp1ir%J#hGX; z59gu}jK3X6I&pYonsJ!FM0O<2iR0*hia2a~9m)%FxaP#|YuX#ubgk}W??gZz_6f?= z^#4o6I}ZE&9E$lsKn{wW&k>wMDlG6^77T^L!Sa6?uSW0HVHF5^EAaaeYDe8FCT*0R)a-hVjX0kwu{ zS2Ug(2@IS&`JquaMQC7hX<%UTGH6?d0P5+$Z^w{T)tTy`Aoz=aBew!X!of9H|omBHvvxu zJb5yEt8ZX(S*+$*!(V-Ud3o^J$v*fkdoT>k^4vqOY}G;+N4oFMK_5gCK2!n(t5oGf=oy*-|bGuDsjYda4ZefzWt3@aTN{t@V{G! zy2Bj}Mn}3oavwwzexdr~0zqKqsr)e&T`B5`I?RIU;(THy(XQ%`>E7YCgHJmCxD|Bi z_~YTMG=CVg*eszaBUisYBD7}`8Q-6h=;d#1^R-UpkHX`)Y6^d}7oLXq$Mj>V*Q!%h z1WKy@~Jl?M)O6_;UZ;PwR?%2Kp=4h4#k#Df8KkIXx@;yVqS1!LI*tKk4}| z;JW)imASotW#(`@Cr*cr9O?c#L$Y(>HzmNa8pWKJW0ahPKdAniica-cri)7qMZ2oM zE>F{6H-T3={`xTJ(utv4)11?CjOUeik%V3ZEOHtDepZ4$s2Ixjnkt5x9+|>d8`JmI zva(X^L%_p7wP`aIWBV$9ckh%x?Vs75+}pXeZ*S*I8J~SE_JyTAzu&)nQ>eDKXM62^ zwfGmgNMoeD_S3bcwWrk<^zxfKf5-^e=GMOXtIFEBwOqou#z=SVR}F~i`u5N%f#>GF z7Q6QTSNC64UHch43ku9-x~kV=S&SnZI8&W3$HfIiemRcnocL9d4H;h!Umf~NaAV-B z|0wV5aNk4{zNqf!=XXx{=_B9g@nvJW2#!x$uox@01D2DpeRY3tDmwOKQHS|3o$T8} zzEa>>7LjUD5Cg!tL%p-}GRkFsqAfMH7o#AZ{k>z+@m}!ccXs$-`Gg!oCqU5cMK0rqA1mY*c)a%h*59RqIW)^pYgs-sv8J4q>f3*Ug6nb27l~oMt}HX#P>Qj| z{0F;6yxL>`|4k$Q(F#C2MjebTsA{~I#e0HlaL#!f=NR}3k^5n2Y10}Azp6jAfKHxk2s+LYZtZkLeIJ=^vGb@c zdhI^2FDOpL^)10UUvDvL$#%o^!X}Q|BI`(KjWxrt(3*e|X`G!lnf!KlqQU;e;;=hh z%cfRXH&w&W(+-+V+w(NuU9-I3cTv3mdlxP5FFF6>{zulu`>!~EsDI_U!T#8RDg9qw z7u>^lPy_w5aTm3-f3|^ttGB(s@~ol$#yS?7JJ_CnGJ1F~>em>W#7X&H)d82{Hv|W z2;P1>bLfn_@<9LH*XN$~dmJnm=td3n*NpO&oVt(isafuU{(X>{uMqPyZGq+Iw$1A@ z3vEvaEw|0ItSN^UJsS0?Jwnbihc3E{rTp&e6Vd01hBic>ml^&2{p%;4_1)LU8uDz1 z+}u~la@MAOzkmINb$7E|XI*1Ze)sj`z~eZfQBcm#e9VyhUTB=#C_s6EXahZ)J!%5i zgvO&Ni5eP5UyPcC)>R5a8)4Bpu2RjYhJ8fc>rD@(ZuNeGVUc*=c%-i#a34hCc`qk* zj9)6zaCxdRJ{4W5REO&`U7Sy>B--V9iF`k>6kFkVe#-YKOv4ACt8ZOg3Vw1N67s3@ z7ydS4I%@~lVM@In?XWC|x*wPU`97*0X2te3QSS$YHX%IHq1NO1+NYTBn~@0h3vsyS z?kH(Ij2Jb!v^4D)70Y0Woo8dlH~fJ(tc*mL4j5?js`TU!GfBM>6&Q#7VCap8AZ})3&m8JI=^+n2~sj;b-kIvc2 z^RFQ|^2vQ4o<43DX-UKDvuK_Znq=SVyIy;%bOvIB1<&og_q@UHs?+LEnUj#i9D#-^fjmzeWhEHxfyzJPZT z&r?dN|1L_EcfnHPc}tmxQi_LAN^#y&YEeqLVJV+J@^9Y*b>4D5ePk!jWjG9zr~9tR z;t*%r{9Vqc=I(Z8B>Se|OxZ1b%k-l0Ei|~?y#U-@>T)-^Q_$f|`St>jW`Rp3*IbjL zFYbn{YvipuQyz1#Ax74`@uPm{bZ}9WoU|RQY#?uZDD`-1Tlbj9ob&ZFFN3e0PyIc# zpKrdi{*TAv&HvupXMHjDi*LSj_aAdh`2J-)LpBEmp(&jAH+A6C=2OQ!HWf9C^f~oo z8_!IglM*bTM(&;1s^9AnuI9aYLG2pt z9-Ftt%ceS0E?V#>-Mrfq_`hJm3-~{O!P-Fj7rLLz^Hw*f9!u?dBj_Ig{SE(`*tQ+y z0lxXiQro!h%GAxNiidapR}iN(VTRq)hn)@z1NwCRdGxekx&m*^}DCw8>D{6V}<;^8&RH# zezzTTCjQ}t?RQlC+dF;|a|l)v|A+O4bWcj*&u6^85YmHM;& z$xo8FKMy}X6L~B^Kg{P3#+s8E=Wt6aXVd#+_#EuA)!6lPM|WKS`iD7|#r!jV{s(@3 z8*}i+pD>5P^&s=p9Ov)-{D=PefA#kd`Z?DI<8_mngFfl!H~abR{`s%^`(1wi&;IfM z-`}U(hUHW;M>!YzdCEWjyZ-(fKYzeK{)E53&CmDv$N!JNPxlYYo9yQ^{CpvEw8M>l zzMMJk&v-x{@9^`@e*Oe=w9AwJeklM(`fBDV{|Y}}1 z`akqq#ruz?ktqApYO*h_Cj00xRewE3K!@b7pM9Ahm>BM__kC$u{`$^?Kfb;1;QzjT zEBvnXUQhauA0MpwLg&GjFZ3N;a{FH&Jnst!;D7E!T-3iDy!ZCa@JEX`|GtC8w@*^M z`9D5*7p|+vbxBsxNW1)k-^!TWCC(T$OVw6C3BW6$%?CyDk&V%7MrlQaDbyWs&( zQ)N8ff4B=H2{RnRo*u6u*3@GF^)g-pKgnFL=5RZ-cdxF%s`>T-E)9gU%QB z^8fa)!48A=0nB**aHt%CtDbZKI-}he&S#JWq`OJ)KesA0BnXn_L3DM>HN2j532yjF z?n|3iwUxF)H=}MI<_rHh%2V|Xsh{o(FGbgOmE07$&@opZ@l8~y6USH=sG{gYGd7#r zJ3fl~oh)B?d%D89tt739N+T8Wh4bA9*g9S>kLz>vVw@S8FMO7eIxX6 zv7Yn4&-=(;C46YAzuxJ4`L3eJzqyEg=wB^@pQ;#Ms`E%A-p|Zky;`yM4|c1iWW40n zzGu1G_bihNUh*TA^ahsG$L~>`3okloTrdA8ddg#yQ^`IDzS?{~?@XD_Gf$>u+#srW z`7;z=iKI#Py#gP4#`{gLq<9@YPyb}JW4u5qanuW5^z!Mu$tm)#f}fRl{q&LO)1*lI zQ~l@7JgrCdf4_&8E@x{v7u|W}O?b33PtKb1y*bl9ePsXlc%?ICJ3Nrdz68cCis-p* zhUd2FhSZs;)ipj(@v7#Yc!@k?#_L+KOKOuom-f0Q`w&q8J`r!O=Xbpvyo5I=X!s6! zjyx)Dz5ZY!Q+Y;@Q;+WFBp5l1PBP@qk;rWZX?Y2$vnXX4#T0VV_ZR4I> z;(DY}r{-ANTaNZAITI~01<&P;j(KAPd@`>$$!?o--LV0-9otZz{~C96f#V5Y8N4Pl z22t%^!?xM~Us5}-CGI?O0XQXtUewtiT~iR?j;;Z7hd-J6lQ*0xMGL;s9bd2tKJM6p zvE9)H|0~npIq|}jyOOSjObhTO&yQYrYWR|=EATlbiNw@>$xlK7sD_NB9zY#|bks%8 z_4h>=*r=3+Q)#_oI<`q4M#uVyE`m*m}WHaw#6F4i%(i2EJ!*Oh(75-((fxk=Zb(kI-rCcfr`SCIS9cDP8}r_Was&(qf|iTl^e z4s!0_gdf|4JQ|>%Wt_|_+cQ3AFFHA&pE}Dmo#nI^KeeaVd46iV)ZfPa=^y+|=I`uluvmRHFf zbmuY0^_Tj2lb>JX=YPZ;bocuCqs(#tr~LE(>gR9!$KUt&&jzkp?iI{IKi}VP^>fZg z+SE)_xD@<{1N6T_enqRWRCl8^Y>r$^H==*b>=AdZGZm* z<|w}syvO4S=Gd>o`-uYZ)y(nii@`6}Kc0UDGc-{;p{d+dgMYAIS{A7NF$s8%$@<6H zM$&3tn}o&?gBPuT-11@**hbX_1XCUtW&YLU;rhl9d2wmmms?h)m(d7~XP+~KZwtQa zJwn<)!gzM)hlSV6KzBaseUy9#NwQso1ALDVk8V=O^LaqtvEH8s(bXx}@OsiExZx+c zFKs1N2cL!tKum`ED6a>N+UHCCAX?MUfKBHC{I24LpM;LN%84tnvjxXk7yej3)`Q#9 zCfIb!u``()ev6IsdM8lQ3$}z#+X3&}7Zj~YKDn}Xa_^u1#j!R;=Hh_w|n^vxA zTRH?;H+#16is*gb`_IDNKQ%tuux$svUiaKNiBeAE!1b4D3H$*+a* znO9EUykgzj+uGW0Zd>7gKqPD}HycZutz)WuNtO@7P7ob20XAF3Yne!=(n@){Ew&tV zs@^Je%)#F2G^*Bq@OZJ+@}kE_UdTx{Kk&uM`>nw?-#7TjO)B5;fbfKF?*!3VUR<&C zmYZ&xHRC3%$I!E9gFlpCqAUF7k=z zc4B8Ia>iru-mIV0L!K3f+&NX3a>Gwjp6pAm9uLQvdIt|zDwf%j*}h=5OeO`zSFjGX z_)*s;A4uYJosXY-Ucqs#d{NUwb2>EQ=2>f3-mdIn$MYX^t{LlhHge)C>q|rE6IzGR zC(NvqMbX3OI@EfNoVKgkC(L=45ps+LWiK%8ImU)P|K=R_2|E(0qJF17(>u(0KG&{h zdr5Nb>Wa#H;_G7@&_^sN`?sII@J|&EW&)4Ay?vtR0uwuR@}S5Ck9vQ>*a`a1hzT|~ z>GJg#tvIeG@6~u~1giZ-5FP6y*RUMY&EbZhcwZ*gnRSs=juV2@LjA=PxPbSNB=^$$ zi(Mcv=`UVIe?i)?{(>Ym&D#l2Y=Q_9?Ue8%WY{65c4#f+MU9w*9K z2D_kxA%Yc4v-Q>Mwi@*gNei)2Us1U}esAo)Q^j86Gf5KtM%TYq;sj-FnEurv1^Kz~ z*mUfx`d1L0u78p4Li{92{pxT))xQ`cOMQUH3h7_p#d%fcNd0vE>j3CX^sl!83pc(Q z^whyvKdFb>TfdK;TX9a3+*kG`SC5BdQoTd4z1Ad!L%I&fev`}jTl^?JM$3>_1O`yLpzfAPW{^QS~=0Mk;HytX-kfdC~EnYmy$JG?`~Z z;@<4l#BQXXH;((|zCC%G<0QC`v_HZeo{J1l`Sg5AE~}BDTR+f zUw3x8EU&%Qcf(FCaX*(XYAvnSVZOeN?X>OPjP|{g}09y>~8>Sj8Kf+T{o4)}9@nJqsHm zZPHp^BqwF}>D(8~tOncce=ILj4`t@#4jGmKQBADol4Wd9mH{qUFVp1TU_=O*BSpyLc}|w~wvu za-w83dC}7tEiYPLWDA@;8BJdFG)BvdmKRSxFM1lIPR4)a9=%m-rdR#CYoh2F+dI zI8uE@{J}_LMde7({XH46$m$rMjKAvR!;D2v;JL%bhnIjxO(Jjg@!=&Z5w?Yny0UDO zWC?y8zmp{O)5nLa49ABzq99ctmwV~4Fxx?AGCuqwl=(i;x?_;YSw9)4mN5w&aya+n z3U2sG?koF}tH;CrR_YysV_`DwH@sLF)`>ilZ!W`BsW@^z_XXNM-;*Ss&odtE_X5t% zUT@&seDlh+ZOfgOrC(ZuwINsBx@zs3Ws6s}uW`7x0LOPZM$PfvDa*`GNUR1h&;aXPz`b^!{_`1{9eYe5skHjMVkx1!| zj_TrFWe3I|jVw6hXyk_PHpF+|)9~JICsDV3)x0H>_+N>Ycyi}LB=9Vfxc+8CMd|wJ zhRAhgKYgJBU%zX3;it$h#tAo4$cdbf&7#YiFS^PpKCR@cG10Q(aq+6iCn9IXsv{F3 z6C;yilOtzGr$n3?ZC|;yy=5u#_BCFEwK+4`8MQ83y7rdE zH?L{Ab(u4x{+g?1w6wRcS+R6&`?5BvpGnUCgiWUUtyMe-u4{Zc;p|mf;a;=njx7h# zk^kfx7DYN0|8igQH~Th8?WjN{cEC<9rb)+b{X4c#;+R^V+)M9IUIE=z_(>8v=Hd_F zIev#~3v$+lKi-%1;I_00Hr?;>GQL5QlqdU=tH;Cp6SXG1Uo0!8mMxhbODC=8-L25N zSma^$A9?UEAkCd;z%^Z04B^}Am(4W(R?AafW2W(Y8hh~b@zvVKork{N;hg78-+AbX zj*Y2DQh$~D1lGMiJ>^XQt=(U3`2Brd19u<3{F#61Pei|&ObkR1eIt2R;}gmA%cqq8 zV6gv#r@A78XMee&r(~WpSaJAA4Q2c8oKVsK;jE6nqPu?7kUSK<>wEpticd9tIPu9Y z&>xNrj{kC#OC9Um)=&!Sm`mN)u?^JkbVM(2?5SwPD%c0^Z#aFQGi7{g_T=gvk=i8< zSns=NS#NXX`sC-5&V&{9_@?bW-ygW=kaIz@@7|948=`yHifar3ctSPgE4$VmUO5u==eR^zwH={uWFVy{zLaQ4PWXhF21R^G4}ax zZ#L+nz7H?GwtFX9t#%;VUozkv-jHM+{%3MR;|~TuI5ZYD824q?sIjM{v3xN4-ZvZK z1J03>eK$;q_J3H{zUP|_YxYHdb9&P+Cv8H@eQ*>tZmaK!fwmO1rJ!StZv@>R?0c#| zS~|Vyl}Yn^q74sr|D-<=yKo@ZUojBh+nTBJFdd_a1)A-EbyGLW? zMT6C6oHOv?dsr>Kz69-Xe?$2|^!+jW&giX(pzOJId+u+T;g-F+>7|JsUAXFS(ct(q zk}iGhy+1`QNQ)M!J9E#UHdO74UcS1CE%MT&|29~@>B{CYdy95CQ$E@K7pV{47@s<$ z`;lZ*^RMck+(bNOo<5Okb(aV3Yn@{qorcZYhVZ<`TUe=u2 z1okEITXu~Vlh>DQD89GozWB!2CPr(I{Cv3_IYF@i*+Hp7k>TyGXk9mg5+tAe;PXn7 zo~Q-~_{`E*?owz-%X3V6Y*G*%wLGb(F1M1P zyG1TSE_7;}@N_2v(03sxfAYus=960;sNY1KlO*NIzU1ohk&s(bF7sSDRpiRG42`$X z`g@5jnMpCXW!3#L4%>}&CQk;)IZvATmt6q5Dr{%1Nqy^=T8Ad@%iN&FEb7_U{_}pP)R!=0?(Qj#K3RQF&zRWf>$jxVryfkj zQe~-^fAm1Zb^EpstnaUX=EwaB=c~yJ2b{k6K;&q&@qYB})y>uAU4!p_aL&NSBSnK} zPf4OLjt^G!ZEh&qH?Frd8r`$GVdIX5rg0M=?IN8|(+HX)Pk?58Z)q&L=Lyg>Hcgr| zbs%!YIX8CTYYpZ5IKy~-Pq9vzt-bNAZj$lmo0u~#Of z#!gz=TNIrP8UA10lkts=Na?o0BS*IlZ0vvLM=$n9%TZ6r!Hw^3AN-(iGGtKYPnuBA zqCqF8o|O~7-UV5Cq++nj!3>(lqQUsP-$>W<8*V*snDqCGyo1cU40kL;JC41kn{708 z!1;9)Pg06j`U%_Uvsd=S$1LiZknBRqtOrVWTMDHgd88pW5IG!mTkB8uj+=DOz@}e= z?){3v$y2WEi8d7tmLK{SYEac%8jtSz7HZJc^poCr`J?W=Y6qM{MYw)^Bi_r=ih;cx&*FO#(J_;FpWo)qe;FUcUpN$Td{yO$he>2|Uq3A>91CjU3 z_C>yac5k!-(r@->%v7orZJvMX&fo(>oKRk2m#{&VOn!w&|+oe@-n-mG7OnYkO}+Y#D0%Ka%CB zX=6_`ej(~Ot~>g8n-je#~?nhi+xug4q=7W1LOdaSZjEFZ~ z9h1B`z?@$iaF7nj?cG1J}R=2&n`)1MGX$H&AhGvehY<$v^>Z38~9OXgwe6B zd5shkRGuyyNoOJ(Uo@1BM^Ro9^^hdbtINh+hO&`sx|ztvm7p_`jjtNY#_yiuvXML) zAR9f&=fA+bvT<#;F&H*(G4oRMxkj}0k#yNu?@Vuk#YgLJ5v{)WDpHG{`4`v{&%y4C z{VF<8@-8g1fs!M%W2Tn>cSw+@yC6YYU_UgL3_AUfHH?8(f}mVje{Xj@27B(Uj_91} zO@9E}5B)f8sVS5;C4;f|{t`XsHLfkyfiHmlC20S{wf(@@=gq__8hv-&-!ShL*mu8j zX3XDB>+Wt?W-oU{65d%@c;`OrS$Idc;j3F;-u)TZ#(TOeavtv0HLt|b8Lw7nH1$N9SgXH9ty+DH^iMnf7PWf7ua$RK=e)X;Jok z=s@wI_`Y|lDPeBeyCrqsCrrIfvHUQbbd`C$D02b$yiUZPC7y1R7 z9E?tVtYQA%rd^4YbKc7C7g2-AKFGx zln)jk`g(&iQ0iKj#jqML+w=8?OZG*7dwSF3xc~RjUTCe0=egD;-y^M1zQ>w9k5Q(% z?=aa@oVq1-b$4az%F!K!Zur5TC1*S5)#BTBQ@a1I;m=)(`N^h-x*urX z0%926bFS{#JFLg)foZr;wey=mXEK~hEUjTL*Dyr8PZz#GqeqU_k@tBAEQITC- z8(xz1<+|+JqR@~wNOlF$>9Q+`PM2MzGm%}(4Q1C;D6dW)7P&mHF1uD4$}Zhbly=eW zI@*6Gvg-~**|iY$o1{F4+*di|ZmP#elU+yr1;{R6GI>v$Uv_01cHy$?;#sEiWUtLH zyXHNRx;OQoKl*AzRVsPt@eWF_-^<9Z_aVEEEbNJtLwbEM1vb#xsqKS@etpis`lHdo z2|rHtM4C$n$DntP@4IM1bkE;G_r7SttrOuJ>xYc#iw;&^haSA4)U}f0`^JHWw%oW0 zl@pI9of=51`|fY}yeqB#@VWaNB9K+FS2|%wwDiWxSEX7g&+dc7D4H@*bmaTVsgM{& zA3$P2l8#^aR`Rnw@rq{#--m5-HvEzF$=&noc|DPNV<0h}b0vl|P~2Cv??YE=?Cg8I zV@v8Qtlbe@HBde{(Uo6g2Frf^*Ud%yUau}g55KeTu8yy!J_9S{rQUe_sln)`h0XKu z?bB6z9e7LsX;LdB%2bpZ87Mkj-PoUG4Ixu&w+hzyh*+D@I~ z{d3FrB^UNY%jsEM)H69n@8Y+*aG(0ocB ze+GBC6nA+Bce!-J>WP*3g5%$GZ|jYgtmutJ?(hEV<~x6N$J2k`A1#~Qw66QPhC6?? z^l5q+&uRL@?gw$rm4uVfi|;Gi7~d58>ZvT7 z_?haN}-}1SG`jAWy;XP$wKjL;avyHwHF!M55 zfH-_D7_O~>r2A)}+@l_2y@ut$j*wHP`WA?r7dqs-x+R~gn6uT>W`4vqsLbGh_ap1Ap@J#JM z#Sv%fg-gD;#PyFrA0D$0AJ*+FzYAyaK)&DPKF_0*?Az#$*xwCb%>V6JKaqNJB;j22 z_O1Ct>dlmtb7rk71GhO@)zB(4@#!MPVwx65_*(qAAI)L(2(Qt zMLktl!n5-}Yy(6BOg`gEJay?{`L8!M)1w6YV4xH}qjJ=uVb7-Ku*5g#`r}n9+~rB-SN~b@c2C3y*{<0yEyg7 z@C#v#W6s>BIT+u+qUp-+pEP&xEyt+;48)=yd1FTE&>LiS_9N_%RQZ^|zNA+n^FK~{ zH=kFM$dDQwU^{u;1Nv>*@Cl_a)@5c8-GzR6a;qRZU1pNbL}ng<9%>>pt5KdRd>q%$o@zEqR$&&?SrY8;kr_3ue z@m2HBea?$brN1Xk_ntG${JU4LdiPDsOva~{HWmKnBl+yO>)gjVrc|)P$CvFIY?H^p z-fjxgh4p?Sh^`K$s60!$gj=%rC--H4qQ>T2hzby|>;p){AGh_G((7?d#lPH3$Lj;2 zGl?msKYa^mSr`6z-+VeQeZmQxlO*?*eaY41!@(;;wv`ld>%#hYNm|d_%Z=43cE;lr z>p)5ue^|e3S?fhhSG41+EV6>)Ew`;*41BF#eQ|DFDUQ##xEs+}ZuPCnc8&j@Ebcyj zxLY28yWg?6v$#XQfIeXrGB;UyCoREtk>1lg7Q>90p~$b_3l*cmEq#hp*zpG`rvP89w%4iYIueTnDk(|XU zJuq8dwrjA>Hz`~ke)WqpSnUWepYMaqjmW$-l&f7Sz$tv{;# z$@UeV&@mK5XFU)(9tdUdHH;hQSPul5E}ioEp`{llk!-VfBd1y`C_L(vZ6!(2E&GzI z$4{mt;QI}Wz*)<|SERg>KpB9w*t1p;`NUd5Yy~eJyA@Obd&(eeIQFa+B=1D>e6sJO zJO*p6ppo?enpr^w@TUyKhT+dzLD~9akac6NAo92x0pany^jXaFM4+~dZUnwx zBs@l2EbiD{oK(+4!mWY#CwhQ#$lX+rf26&B zz*pWmuQ;v@y@um%2;TMsUSnmCy>iX2NMT)*7JEJYlcV^XeII47gK6B+$sBu4c)a8O zs~A%br^nfN>||n(@4BGJ9T>|y=M~45Vb@UXS&u`u&S*Uj88pPQ&_JDTI35RO*fo?J zk9CzT>v8bjUXUljdK|JnCm(ewVB&GeJLeTrKpAqixU-gz+c8{^e^tT>|Lc)&4}i`j z^6g{0x*hP`)&n6BAC9dh z*D??AKq!N+VccjnF||FtFRIfTR#(lIUYL}!P0gNkCp+rYdLTwt5}1s=2F`hPt)R>T zj23%#&MW&2>-}RZcL%D&|4@!|O7PFVZ{@U=VucgpZUDt3 zYYo7jGVB_PJ?n9>9tXGMz~69mJh_&6o^e-NKAEAPP;RsunA)DBZ`{>tU?*M!Ti%l2 z<8VUfyjsi01+KMxK0Y3YwgB8I!>!@+&RRa%0uOtmZM@Z5J|iphj4Yo3>?uR7q1dyQ zkF|WH^Ep12&k3FLYBjKvs)3nG0UPxunDhMwnO*n~ik{%;F-ihR+ zZ4B00K_e^s%&edS_)`XA!|-RVpltn7jgBTB#WSUQ5`yULoY$;5ueYvUIg~lCb7$2h zytJh3&gO-wNJQG7Z(>^dZSc*!&OgUVe}8MN1Kdpc@VyUqI6KO5;zOi}6TPFN{4|IA zlDLY_NY8s+vux#z_GRnZof)ky?JdrXrEP7_3?6J#Ez@xa0f}s^Y$|T>hW-2f_eu&XWS|5zh=v1Qq0l!OVZ=E@`dn3 zhTMHF=Vk?!we3!AtFw6VEw`;*41DrCvFV-V%T}&hwr2HeT+jA88x53WUE!Lc%%`=O zR$hj(X)$d+7s+Be;v^K_VP91U(_9i+!}RhnOe@32q0xI5)5^;q0G;=+N8XT>^z@@VGkfFNWyf$geM(+eDrmYj{E2O`(oj9 z9A8bOWzv0+L3Fwgl5`0c;3uhH9rjfpu(> zColl>;R||w?02B^&nA}sn7Q~b_%0&&i6y4;6X|%4$;Jf?H!ff(bK2aI>Z?#FQ zO$twpxHh>wcVGeEmM*MKDuDr^+N7P~C9f_kx0tq=7KRvcO!NEHx+fQr0R_E2N?<@J zrmcl&EkrP{wGh2%*pZseIXnw757t{-LM+5gU_cnwZCrr05JgUfk7$Zr?OkCOIqpqC z_ErrD|ROK1(S#y@0XRqu^cAYWk^d;-==}aDev9hDVH>A{SOsyYSbfly4p3cg_NZroykI%+ho`z?suP9$1+khF(^D3$rRFt0*Isl(b zQcyo&ssr381^Kz)Oz#JR=!j9dhDDH$@?MhE&*}iQLXV#gK%N+0KY*YFtsme52H`q@ z7pxH056qk;pYsb}JFMC>OtN%U5?&mU{Uur}^~M zlhw_=rA3XYe@lI5uw>KAZ$&q~_Lj5hs^;QU>5iu6ErVkt52QZ7_ZtnRJ05A6y<<^d zq;zxY&r;4*=i$g^P)3{yE9(CaXSXyo@5O$zxBY2sN1L6gRlODQ&(}}xjYq#&Kd!el z+SofL=FIqVzZ1V={}20})BhM-7w@m^cS`H~JFeW+T)Ly9`ICE}>+e`px?>y8pS5>$ zbz^TVvj40_J^R|7bK?&eJv{F5MC195FTYhBnf^@tsp7w5Pxc!2#&kaaX5XJiW;OOZ zvH$F@?vIpS+3$?`VK?i%sLvVmWcNdpZt5+G{Y!UOZ&~!F-m$UgyUX#;)%Da=`8ye) zY^bPRKW0Pey(RY*Z!Fpr|7z@h^n>#&=10F+R#Dq9_LS%g`J9rZuhH$HZ8%|~6J4#8 z#WH1A?+b(I^uCaENvRxish{2#?!*b|>tQh*n^7L`AxY||>qIZ$go#eH3*AvC3JbG` zI#9pSWDk)ihSwJ&Xd}BXoW%tm4zP^^)_3siA#at3u)ffG>8zJdup90#@Pwhz=hGds z?0a{82j4n(9miqZIQN*X^W;?DHa{cRHqTw{Q}xVIyKt@Z25X&DGU+pXu9esB=hD;b zk|>BymqesfwSyo@WUcd&9V;TA4^I*yxFcH<&E!H5<4|5wK(h zohN(8TkD*-v(~xe=o;xxw2O&Gda8QpkHI?6=?B`-4;WbIMmoUESrQ}?Zk^X27wh~c zBkO#DVx7}cFKnGRq^ieCduffV+-!OHrb5ZGzt+3F~-upRc&*=?4jnPFt zKVP^1EGIF)r@3@d&wqS{HhTP_WKXG6-!mps*iwHrZK-cfTk3!1Tk1bfTk1b3XsJ(w za1XT9SD!kTI-gUL=pVYJ{sK;zSn4+_WwA`z)%BwwI$b{^T~aECTOaE?6HEOG zl*fBWlKScW;x3#p=@(x$wA3F!{YI0ePM#Q^euUteZ2f2!jyP|l!3*n0-bXmX^doDj zTT5NAdps?5Z?%muZk&6W`PZ28$J4yjwbPBKxu>(EZs*~WL{KzMVXOTDG>L1qH-Eh1 zX||#FHIYh7gk}6(dVO6g1<~nJiF77b`%cu)L@GUi@=T=CPSBZ1rJ-o+b5W)wX&2d- zTsD&BH_P9aH=c$oab%07nLLCv8Nb4k$y=o(v@f`Hj&W>V zx!0gs<7v*bo4Pu>oWV%nJ)O?GP^T zo-va?fL}9Ilkl|O2L#dSeE{i9`T+J(CVjwqlxNZhYy+K1AMgUK!cNeJjUlz8exs=m zAWsal56BIy;bI<0)oiDN<4E4B9-)1}5WIJldHMjx);LYT|G5VSBN*p){(M?0^00Ya z4cjIiSJPNgebp%vSHtI$6!$mue!w)YCJ5ih(ht;0<&aDLcx*VawHtArNk6b1bSC}4 zi-!Hcx{pskkQ-RT1wfD{;uq2nxWP4H{lLtbm-vQ3xcBbGJpBM;YtBr4d(iogQ~TG0 z(M{*1CicdQe>1h9x3pwzYH{7I8F*j2mOf~PFhe(%iBc3KQ zWlCyl3VliG?9`dPrNzIMnpgic{A}ND_|)F}kf)lb({C3!ySF?Js-j!#8E9UU}+x*nURl@{{xrdjGW&CrtF1v`ft|FG!CG zqSN&l(j}#G$fbUI|J9BYl{g<33zI~7CjD1C=uG;r4)jZ%xNn#qQ-}JECOw9{KTJI) zHyDPCnjn3T?NnHgaRXw)`Y-EcvtBmx6H~ao4+TR>Ly3p+RyPUb#*yt^vte5o#U4!E&P7XB!?u2?dBWZw zVJ1rH4p`WW#_x4%D<6;kWmC^sC)E>=#2%rAo!7d)6c&0(cX!0i|Ft`Ep7R^qLagjP zXn?#{_SLYmKXd9>**|w*wf86egs#)jiZ!vaOFh0xmnge>KNdu%_hY0>rc2A{TzWrt z2kKV|x-ctyKFZ@gBuV|wzyTP{>2wE9m{{5Tfxw_}W}O(W4KoBQJKxxq^K7!~p3a?-E4wxi_V*2M zT^MQ|GW%rFDPn1xXxFBec97PrOQj$>T`G}I^~a0U)TNT?81_b#XCjrhgU&=M4Q1?V zR7F?f`6-o**M&)AIX8@jQ7nPuR_W_b)VeSjyYAW<8{_r?xqh~CJa`%|?EvZQT`&svNHuhW{sY>lEnU%WST@mJMZ^oR-%IYwE&*ysF z*)Ec1V57dGYJJg$_`R|Fur@+-MdIp;s#9WJ1j<%PL4Cpj@N^}JXa%yVNk^+ypN-mz zV`}nVOYZmPg6MR8fOM+-=6#uTeV|XNUlGoej`gd@52sckbJL^vSId+7=~gPo$4&Hs zSI{Ty1Z|j=`Y0+f4|I~`zOpa5dOTbMN1;j@skl}tlJ9#eeykJupMAt7$R+W7-ZBVF8hH!xQ%iYy!Jtt}NT@s3B)#*5R}o314@#}9rD z_sAu@PCl#ephwP`_Q}+0tg*7Gvm>=BRh7DZKO$4goeS6E*lqh4_pB&c)HA2JE;Tnb zB{ei!gu{cdWpcl@n5Ja*CV@Z3X)nkkE-6kNIYj~4a3xcY{A=To>x zH5?GoFIRP^_|x%WwA`z)orODI=$~CU6KX)N$RKfokwwkSPt{> zJ&N*-`cBXp^_}RxcH+LFeJAQS-+u;X(k{v&cT+w7QRq8s{koDz*mqv4R5+yXTpQ4N z=Em9J2+J+Q%e%(U>0vC~huSr0$ScM8F{wPweNP-X?suI?CsJ0Y6MnPb5@H)ktFZ;S zFRdo~0P)Q$)-7wjXz7af88;t7bQJpuLb1jMW-z|*8u zDM-ywQc$0803Ew%i^K)#tS7*6tS3N`?lR-GuqPm=&tO!}5Ig}!dc(|FbB$-dO!GSV zJf48Z6;HrJsXO*NQ=<>dOq7-T7xk{#SJrYBTfcU~t@X6` zPum4A0c?JF66l#Ir^jHw?@9Qd-O_L67zEbI*UM$z|E(QN8mzsihc^}L*K*+6OX_Wr7RXHyShgp zh>jMET*K>0m*j?@q<-x8Y5k`YT&U8=7xJcVL3yfGB=^$2sXxaF6ORC8%T81xOt0F4 zijQWG0I@Jq9s#`*<>EG1unqA-m-zWE<^{c~cC8!ouBr=RH=RWHufY-0iEXR$K8bmb z$$A8i%_CsC){XhMqw>cGAv&nbiN4g;iTI%5t#fl8-nPUDe4OHgOy{--#r^0KEQn5* zV5BpN4>J93)JBx2qF4~DOR(*rGm&6Ji4Pi0QLE&0N-XA*s3Bze^hE2w<+imM?_Tga zH?F2%&^utd&W#@?kO&{^^P{7)G<@e-cn0H}++H9zLMS&bfc2J?UY!~-LJK}dF+$&k z2&C0dt&y0aCYjF*a4n9jN${oPKZs7pKj}>H&;H3ogY7_hyoV&IpN{{nATYuIP&|X9 z3IDP>^)T?C8zkhfaWf8WTG%^iw#LoOx|zlne!eyD>Yk0IPD?q7dpajzls}fbAa8`w z5WXMPR8jreQ)Hc+X#x!7VlC>U1g|JqE7TVR$#}gl2%^*b0@BsxsUMH2)+|E3jQWBH zaGgnCuoHA9eF4|JBW;*9`vB_q8PG|RK1lW@SC4;`#<$5M)D6^_$3We{^9TlwZ*$d~ zoT+-NSw4QWXx-JU3tF<*8Lo#j%Q!xWGnSCDbOyu+HE!rEPMwY(i23Atm%DI5S`vPk#3Gspwv(Ao36(RVuk%xAy3;8oHyy4 zrlH~{eba38IXh8iSl@JHl=n^Kk&)_~a)WQYMQ$qCj?yW06ENyFZ zX7FI^vZZTpS$y-FmRpxOGwQFoYDPStng$5FUyoyfh;zNlD_g2cc` z^;JQO-ne=V`l?#oi+vU?{g6J(4RWz-;CO7S@->f$eqDoY^11N0PA3?!F)qW3acOB= zzS3L%#{D)+7&p$HRcHJSm)H3kH9xg81$y?5T!}?%TM{+VQ$aG(8jyqz)J?h;-2t{H z9Xbq`%Sp%mbNzkc`YW)nCgFPB9~?wS)W|g~hja;U_(|%g`-3;40w$8_MwFu>Q|_fp zrp=%;kxWkj{+*x=^9L_P{qo({f2?#S_2GeV-<7nwclk)oV`m-6+mu8#UeWG9+cz+7 zh4@^(`eI){=AO4?6&AH&4|z5ks0w-3Y!*^^%h^~=kFaHIF`fH`WQ*xxV0w8TOd~R- zAf~-#YAmKLrgPStv2vQ)Z`?VJvNW9{uI}Q>SN9l4v@#^I#f*7X>lxEoWkcX}iL)_3jAn z!tGKOrIdHMc50R#S+>}<1l?)LM%-w6LhK}=NX^LD^kn2@= z{@K8>es5U{i|dnM4O(1#41O${PmlR5*SvbT_4H(UdaS&*@;Y1(&o}7rt*ua4US|gW!*FfAJ=WXf zA@TTmd%W+MP<;&JM(gd7cafbBcii7f87pPNrA)qo|F!%~N#QYt>oSA?7S|)U=7C8( zkHxjcbvUlu@(dKN<)=hKaGePNIPSQ%R-v^DJt({XGHPPIxCO@l*X9cVz`;;lXMzC2 zaBZzZYZVGC!$&Xai^wFyXmD@#ush>Fj2q`(X8t{keCt>{&+hChIscU%$*y}kf40Mk zZcOr<789R2t-sjeYFppHUaa%;N8^LJ>j9{%?OlL}bXVJJuBg1~6j{^$!pw^cT(!pZ zn-)uyvbZU|xxO|)5S_j@0O|78uMWoU`6pR^dQddqZCv z#B{aI>y@&&Dg3PCKZs7pKj}>HZ~9G(^(fB-|Jy)kg8vr`@!vkm@J~J;CjN83X@MhE zC@%#6?ur6o_@7x<=XU_%-?N#W2mgJ~o&)qR>N)V`F|RpOBb%Lv$6@7o_5jYKvCh8d z|GGa>ra7|IQe{%g8GS{gU?N33)`h2KM(3Bg6N20xrRlMZVos6B=ytv zgjZ2NdQHM&3%?5*-b0eyOV<+)fWV}mc-yd_cw&_G6G=S(F#Czz&spHenJ6!$pD_D| zMct+T;$Y$Z#LB$=#HTOV(0O+1^w;*DR_MM5o=i~T3&bRs#u}CUD z5Ia0A^^^W&{Lhm==}(l@43xb0$;KCO?zb8poQn)Z->VsjAKKcVh&1%XqBrhH4n+FP z8WZ)gKac(;`l5&ayc4sE0LFVjAE3iU61K1qUKT@NY836uVX_*IkOSJy*===A=D zbSC{v73ycwzr2p}O!}8|Kt&{lbcjt<^ka!yAmebNLtNnt08&E+`x%2 zt$41ribs6i`C9K~x&P?Y-K0w+YZZI#LbR(qZmnWv)gDi(hXvDtTOtW`YPzJFt_;@q{J ztW`XGt62ZM%`8NXm{`Ro{fmtmu~xCDL*ZT{)ncHPEWQM<1g@Z)y@KGUF23|KcLJ*a z7p4^tC1#}3b699&#f%v_ws;YKnM%fsPnCF)Y4VDZ2Wh-p@iI;Pv|PhMP2xAw{j@=J zx}TPG7b*ox{q%7l(|D1MC`!YGpF=IsLTs_er83JPX0K?M`iLj>gMHCA5GMZ=H#1T%ON5{?x^DE*VlkaH;<} zbA$C`^2dyH*q9N#3)LrF%XjN1!Ion{Gu9t%RTzFdV1A^%EK7e#4eZV%3sv~s0&Dv`tg_=PrA#nZ+HUNne+|2 zKxfi7ylSW)aLtX;)HjePhTAvf28wv=S_JnEvt|yZZb6}jlGzWPsJu)gz* z*Q!$gA<-huj24-c6)h6)eE!Y8yAU5z{LlS~(r@)A$|D1%M-v0Z?;e22HkR~9*l4Jz zUSGVS=-&8!v5jst8ly$38%~KnW}Q4Ja>1~!e^laxi4F2yr7Ug+^)W$odLKi&e0`wa z$5f+!m7opNKVAooNgs1OykeuNk0H+ww~xsU7V*~DNTAI8`p3m{htkJb&zSX$ftB18 zZl@2~GdBB@p?SuvMSN1?MXW{aA%GHA<#B5f=X%9*14g{{ID)m_%ZBC^vlekndy6w; zX=)StIikZz9dF< zj`Vm>`?7WI&WzUMqS;borRAoM16Rw#AQwMujZcRm3O6nEbIHWNs?QAyqNCqbu3;IZ zOK`(aa^DNFua4m){V^Q+fJwt2w|@&ioLYs;eZ|i!ZGuA%#tXBaL(1bhHL1sk<2x!G;~}l*-O-J@Qf?l@+m`Q;lV9my4UFjk z=2ows<<4q|mN*W1BZ{_IjN|U&9w!KkPS+TVMgJYvASeF_-vwdJV)4|&;_?72x(jU> zW6^xQowq%n%aV&jm5Jj}#%Py`w8AAx@2cZ)z7Y61G0LRlFo;fHB2V91>i9A<&E%F(dS5rfyBt5l5khM^Zs-6RF#K0JD{N={vdgD zv|}@YXOJWq(Xn~05cqizHiPJNY?5x8Ql{Kj$L7_B*t`Q}%~r~j`sp#rouDzn=4L}| z){Qc3l5fMX*&2Y&%-1u*v1vUS**d1mn`BerPhGYJ(GeG5wN<>9iF7Khl&AAMW!4qE zz)wQQ94wwruj9ZH?7>8FZCT=xGLg0#?wd|cxJb2~q`WkNzo8x0u5zFpypg*>PvdGk7F2hr)0fpiI_ydcStLuF@MX=FVGU^DZTiEwOM z>nU5uoUQOWH-qpKL`PgeU0fx_kWQtQ@;*M+({;)~aOgPjCFb)4`@AO3^0V#idWmCC zdn5boIIu1m779!Hxp3m~ww{_sf%U|;k|gaS`;x22hvR2ZeHq81wV8|qV+Q{$*1HNn zeJuDoWia@7T<3KIok@@j>Ko5Eu{CWGj7Op-3ag8U@+)jb*W4KcY2<(OddNzj>i`_~(e12bB_ zMjisWw2N}c-BgdCOiYqr!^VLz+dCMO%3yF9CapIkTgO!SlT0Bzp<^hB&U!PHufUdZ zEciP2ivV87AI6Pyj?tT8t*4LPSg^I8PKNaaM>kRxemUL@Wk5I-kJfr(GX|!7V@_;y zNun`P`=BHdPezbcq)V9~I$cw<)|0e2+gN0_cP!u6Y(~nnXl6YXz@joJ9EwG2J!M{U zfvtR)wAPc?|EN)gA8+fa049~e;4n;D>nU5V1zAP9TnnPJ)>D@C)Yj6zc1=tBvYFn1 za2Pkvk&mSq%(*z?^`Ke)wa#BVb$3oLdbQ)??K>9zs-rE|v1;C(Q~6(bUaeUl{Odxb~qg$eprrc zg68ZeaBj5wzWEH21S2&#KzT{Z$b029~+Z&6N@9*k&7Pa+% zcyZA$upWEEqP`C=-bt$MtL7nZW}Yiw6MPsyU5dQ1qI7+9L*#eLe)>X%Q$M!xg`Xn3 z7$;hmwJcrXM9#-%(PhWB3e<^SizDAEb2WGlVncX%CAQThxY2PPM5p7LbSe&maD9g% zuD59AN&R$O{~UBCxZY|wrgiN}#5MaFFG=fpdxawB$-`zi#_H)vE{;p`;n*8+4#Tmv z%(8K$@;uvD_*BPH5FOR5oO#=h^Rw}jB=yt# zZ)=YbftfYM5@;|pJqGJxBURxSV2`+S+SP*N{Pu_u zj;%dnH9+za({Oy>-j&{eo;6o8_K4+1G?KdFtJ-qXv(?}rH6GEdRZWQWJjZ11kz=z* zyqTmQ- zbh_<9x&(fb?I8YGKiWXt7KCHdslpDw z`z%TBEBlhG$A{Bbk5qIS-?f>o;eCJFwKekUDBcX#a2%SCeZ1*4RyGbXPTBG4TEq@` zqm!(E5El725x#2@0zVht(j`j}osLD)C6qGdzB(3@r~vC1<_Bm6 zjR_VX1)T{N*BN55dX!<2ZE1)_cObF=7Ttl!P%K_%zOI9>u4G}cZYxG2o1Li`ZJhNT z%$NICLu8MPI_kKr#A7jjnL3?t6bdYI%4+55i~=T^+8I zYgh#7h(}357`@&Qqj#Vn6O49(&IF@FSwD3&$xFU#LyWqEj0G_24l;&e)Y|mfvQFhu z^1fg~mvupO#0(&@iq|rcPNkLdbUkr7=&s-eeiAz7V)60RXdPp`&K+d5+~~btl_PjW z-f#`J`NqLPZqn(5D=as%jilAQwi?P9qc@*3j2nmYeIjd1sH;&1>nYUz)fB|hL3FyF zLb`-fV33|-Z3!Y~=_M4KDxDefR*73lNFA7AIruih28xO7KX|A(J0-n|>gzmGYVr8}Gp z4(`Dfv+=vcnS$AtS=W)yxd3IycJI$W>vEbjCGy+wYw~7Ye%7CLc|(~y?Q-nAQ(^XH zdYA>zDV{%F?|o8f4{my|EH^GLh)(x7l1?3|k^Ab=3)>AxMh~DoRfm`Q=_5o{IAJm} zdISc*7L*wlN%RQncd}+x(|hP8X+3YR(Cka{vXRGeR_kh(7U*%DW#_w*$83Blxg^sc zczcs#~MT9wN@Vts2~yPT-L(OX(Fj2o@S zUVK`~Rb!%M#pB{tkxxX~=;N+Q(|_K7S z)K4Fk*#M&30WmBH8EKpSl1*%?CQF>B+Y5s(CL-d^TkJ$^j> z;AS&~tR9oytE)Yx`WEecHA+6!=f{1Kg&ubohb36BNg=J8LnmP)s8(`V$#Fa-M_Ws4t2a-E-%t+Y z#yOXoui@nz3R(V`f9iUv>&5EdPwwn`Y0OW$#_axsiPG{A;FS-A@ z-zzDXCO}Rbe6+9arA7h=`C)EUo|&6sU+Efq5S{LaAzgw6`AP1pN5}HpAB+Mm#g8=n zar?LM!>M$bz#Z6EtqQ51?uY3Forxc2D06-3+mIypm3_(8Txr2`-prvBflq$nd~9`n^6{>h#(o|6Y)I}ITf8e4zjg<{3ASqfA-w*1 z)u~nUh{vF{_sH88pBaCu#U~gdPx`3fll&Tv&*cU1>CL4w!{=<0AuTDpvw2}E63Mhe z#F>`vCG%7;=**>p?nKtng`n~Y}RePyT^%-tG=fvQnaAnxo|CJ znT^}eV?5&Rm;J(-wi+|U{uYS!W}bQT$SPA4Qk*lU%hhT;zoaH?_-kh_ITgkt`8<*Y zPdbi?6E%6wo;wy9M5p7Jbi}MAxv!36)9>>=iGoaU{0ityaJDVM)f(7_V z?yFOgds# zlH6Cvv9-uX7RP+o1{PTX9J@E`Y>#3^sM7|HgP!JulVJ)(Ymab@@ag$TF zxUH>i?a~uFhJF3S^ceOoJBA%BErKj9UF!>?)1`&A$k<f9LFB`4?BjP z``tKtIMfuRB?i&yvXgWPrNAId%X&;kR(2YAOn|?@F>IV0!Wi}}^Z3jwJci0MhJE)$ zj##(!#$w*6b!@+kPiK#29}XGK&W+<#`R}vfMSnb7RzUsTQ(@)PtMg#22FKXkGE%W# zq2Z?YDssJ{L3BE{NvB$iLD=4m3RHr&6hG4N$89~fa~qDSoh~h`7bVl? zC(?^zXr%@D+#xMa?6|hI(lUG!gv}u9OUGsqosLawrDfXuL}Js>N-KcPA&hHVEA6DO zc6)V(%>u`|*DEyK4AL-z=yYt8PSr-GPtnJ^t(7*i9vDL_tpK*|Shuy(97mlIDt&?0 zMWp)(9v_ZpLM<=fx-)IJExTn1W8JgO{ekr5AZ7Uj|EcTxhMiseF;_dfYwwuq9d{;j z=ctr>*SY^y_^)SJX3Mgcr7N7s`PeMFtofp=oYAumI-fz3^w7FRHeU$*T)08k`hw_m z$w0b+W(Fgb*=>`P`DW3tcVgDgxs({^GuXJo%S4}1D|cT}gmS=hv1(E13~I5*ny z$Y+owxX|&qPzd}y2#-N@Ivz=vP|B41UWj8HSCZ6Zh{u(Lxp?;5USpNq@$}!?E;KYm(YZCCcH?OVYb}dxgHfX%L$UJ+-v}KJ6H^^=^E0yc&Ivvg5^u7F7X!+VSFiGEQM- z8`bMK#<6-4)HcmKUVQ7?mFDBcb7$2V`@>)NZk_grkHt)a$dnJ?`(Q`m@u*^4H`4y^ zHOp4cIG*3jJ_mK?n_}IW=r=BPx4b`*2;_Rz7u^9T8tHh9*OQL>=lc8NW4i+TY7(xP zj)SBRqho#K8kWQI65Q~U)Q=KIt=~ozOrH~v72zlKtH(A@twQD|N+J_q`DW04&b!3@ zmpU<5Ev+Z8(}`nc`0?Jnuhc`H6^ERK*vWTao>PS)h%a^TO zwQSAm)oy#8jRvYhS=zWW$jrx`EvA*1p=?@A=f{>FBeEH7W-&cfOmnWahUw*Dm^L4` zwwP9ctZZ6LTTBZ(jJ%xY9BmELZDE);AN!s=d-y9+QunTW_U_I|t@8*p@DHP%mCu)> zA=DU@$$soS`7uOE!mS5)E)$J`&`xXqKHlV@}`Pp9M~>pJ6Vlb@J9xrjxTRhpv-z z&bEeid?lHDQx>R`+i`U3_4$a5qtik(UZdP-ge#h=pjZliM}Zy%9ATt5ZE4#IJZ`^w^ppI>yYPtW|=2(y6pk zp6)$a4mx#oR_K_kBbuY`D^{&5{>a7!tZBJ*nKPsQnyY5Cw70JrdZbuB3Bw*hQjmn{ z04tJ?K0b01>9}v>0&HA>9~S_8X5s>{V-gntG8-3QF^!G{sSZDNT*1crob*^9!ZJ}#08`=T{tcPWHv6~czxL}pH6PQK8~YX zwod^>CZjgi>y!5S0JoXAfHc+%#|41Q#s%28fR9LA0Jzb{1z2s;)1Rz`_)*j*GjRcF z2~#*O0Aw~Uz+&2BTCBp4poN$oD@5n8%7 za$H)9`S53RvMq-gIS$-r;sVlGFB}&DGP_=YwGclN79w~t6BUq1%$z;*vP))PGV`*F zv0Yb(#R1a)mvXw&u|}CXcD;bCF*+L;;Pu>kbj?sA$GM7`B#G9MeaY41ABFV-5>heb zlsZn(dI7*^{-^*i8Y%C30k|d;6<{%KV|_+nT)?T0>HJXvg)yCp3b2^An6{Wc5ni7J zWwW2ck@;coZT<+M}AR`|aFq-7IczqIS&Is4Z^G5}E zG2MCB3!u;Eb2Gm5DSx%SFgx4M2C=h2gdM}}RdrrU{t?bB`?72?EyVQ9Bm>EFjH^Ui zuTQqNX1zWhZ(FZVz$%fzXa1;w!rEjeD!^jeT8Pxc>nu@Hx#lUobXT8N$&ZL$LTkS)ZvwwAW# znGXqs`77qmGGEK|b+6j?I|672iR{vSkn2C<>jgYu7w5C@KD4r8k+2G>|M zAQac>5CMy8i)(c)5G${b&srcul-HRMfefy(azH4q(_sR~9oJLs_qr5$%F)CqzqOH2$eGFumFo|YZa>6t+fh28dhO?s4#vU+qamTf_3bSTy zT6t~dwTV@j2iI;407ql<&fN6me0p(!FkD-!&{~Ba5|4{j2x+uNSsWmY8|PensXx16 zN!gvv3saE@^?5HvoM~BOtp~ir=@@`Ar^HEimDaDC=j_nGW6FI=jJm5I;qR8VFI(4s zyjGscx5`C6i?9aI#nzG$X7vjce0FI`{p%M&bal!#yq-Vy70&QvL4))Ho>M-iJcm5_({r> zeaY41;p6&hO?bbUbD9+7=K6{<(s~{d*CSR_%qe!p;{fX*QKDJ%FKXMJ+E#y!QDTgv z_()awMN1r~nmMYpnCH?X_2JQ<$BIA4;xEl>LAbK`I|cE_(e@zxrAO3F@Hfj?{=Lc@ zI!>1Sqx35z``F8jcG;))l(NnKoPDMA^K-DRCh5y{>;=*3vX68Lr9io_F8k_G0TbDG zJ<2lqlGFpBGm(8O4P{^XD3g6`XRfAJQ1)>|94W8tOOJXRU~i6j{As1fP+8ck+xnCK zL_9JOKho8oC`t@O4>$J2V>j-oA1HcvdSm@S^xgAQ)v3De`SjCjK7gMtKwe)_x<0xg z@;g6$p<>kIl^BsExT(PbHlg5ki4gd?*SwCS<28s*$1Cab-B-tJt07*ALleC21f2<9 zw;19zIm+-#-VMboN4k;n;x#>*9gbJ)xyZ(l%AaiCAPfc35gTB)RlJsobSkZscLt6N zZb`QsKULQiI_9cXG|Ikq=vq#h$u!5?b73u~3|Fb#L=F><(xpKVoh}VXmtaAD5-Frh z1M9iqJ2=6f3yw%5RpFQ8xk!&Xhf9Mw7hB88XKy#l=QR|*CxL9&V4L`o9zDn+(y$94|Y#5kE8DKGZYBf|#RvzF7%$NDXae0U{BBnfVGye<&} zKPQ%%bi6Kck7oXaPRA?h^4(X*tF@d)7O!TOQvtlDM|{KaYAvU1nWtJgM2KKR$50R* zv0*Kzit@OKa)~%XXoyzBDEBCH<|0m*qwEMy*E6)=oA+A9 z2Z1BqbhV#LCS0a-cMzQ}AxM{y!jQ{-i2^kO-g-Xx4n}Sq+0@FScf1PkB9CU59!U6#fOrkTW1YIe9q~VX-`fQZt z|Bt=*jjijr@&qqQNu()SVPbY$iH**E7VW6pHcd;iO!qq7j}}eS+w#baWWYOZK%)F8 zlYpF1A~{eujJD8m?|QLDpauLPv)e!mi+u0``QYU`KyNyR)rm9X-sunSq(AgbG8heD zpgoGCwZ}c3ATXjmzgzdbcV6+;y@&4~eaTb6eO0&Kd3EordwzBPRMojur;%J{WvR5a zWM(;l#p=v*E*8zoIy+XGKfU_g$t^X%EO8dXtyx*^m7!WID?^4>XPEPFYgSgh9xC~r z#Ee;4=!7&i^3L;j$djFs^3BGWUtV54-C%w>VDnFG;EfjVyGz&k>M+0j@+0@WRsKR0 z=gleaq2CwXXAW(N6OYcmHaEotX&%z%LUg`12fA3a$=CI@xrde7T!q?_sN?(deQ)0+ zI*sq`g3|Z4m+o($_#b>-QI!;B{bu^i!LK>KH^N$QP8m2{Kd0Ow9KzdSIINc}A$<8B zju4&Uu!hV6;4n0g3>>bXM-JkU9O6mJkFoKd>z+D!sKwwQ{kG_`aHz%}Rc~L3>M(xO zP@kl7nsdfuyN|&TosU7##dL7mkrsSeIH8nH9``0) z;XW7_B{~J>7>`E<4T|^<$;V@e&c`F@Vl^fxk{*Xj# z)jnBfqox^;d95YLB$C+v-0oNBpWDFPZj14vk9|l+s>O>=9*VTPQNd5zw~#_~zIFz> z7!9Qe4>`6O?nmh^nM0>zhHw&2J;RD7Sni=cz~I%Q&lxe^ z=&uCla1o_UCLYUu?1kuj*$28P`Jc!2ydPXtDW&e>b8b@v(cM67?GacD(P zi_*Y65oQTt^v3}$W;iXgbx5blo2#~L$c%i&h(r$w~*wxJEhN~!}@H=NoX&ogA;3v@O8`kdxaWi zYh@>W$M-i$W%_D~fBy^>G;6>w5#22Rh;qIstOfB_A{&|0N3w@1yU?1AP8hO&cbt@(0`+rxL37^Rx-IFJu z`|9dRI$M}OyEK2E>ZlF$S;IHQC%@Cr^%}0l0}(~Twc(oCp#!+ao?jo=3kqDT=a3E8 z{PgN`!?od>Iidr&#y(;n*UJiAtLLX5+CU`3Puw4^?lFcQKKz|OeZ6NidX=>C8@;a& zzv-_Nxt%+Qa_E0a9O`fMOzs(ebPx2?cCQ=R4E-Gcixca=zJC7aqzY>E^C@m9%~{{{ z_45#&ub+c%T(rsehdQaBe~a!9{{wYd`uPfduhGw6BRY+K{)SRNuh9J!Nk2zlVvWfL z^>ge~_VHc;-oZPAWWZ1O8ljLogAoL@Y>y3)Fo!3e-9BxP*Pfa@XnXxKl58nYIwQikv;)(p^@a?Jp6 zt==DQ)}rG>|Fetv`Jr%ySDXlwkS z6>sVqKj6ByW}t@ayfp*BwXGQ#tIVy;MPsLzm!mN(BxuuH)f&lh^8&4x9m^ICM;16=xogZ*6nx53#8sdZ`NX!LF)>Q zq>NdM>!plYi_KY!)wzb6l*wB&04ZZ@2FzMa#woKFp+T??;fC%{gSFTI*LiCOfNNVb zVAf*7#J0k`riQJb6YU({;X&Bo3Uk8kYHiIxO^)ZS835ib&H(kdS&KDZM_)8bvc416 zBA9V@cI<2SCD8-&-ZI~+wHR5PfjS?*tr>7U4=!i_5NbBEX5azWMDi)oBC6}w*5sq8 zb5e%m4BR1ZF7aKH0sGLVDo>XLzcT(=?4KxAqIfz8{GTqG&eoENATW}xN;N|p@dXqD9^1BPp}7R_4h!kU4NX^+dHB?CFQ zt}YqK$F*6D7H5D|l_Er?E0P><(pqeQ_hiXHp0%jf&&^siYmqIJPFRb}bIS|0mlJe) zZqeRNP`@wG)(kk__I;8YSu-HtxK)%j1EUOS%CpxDB={7o1_0Muqycz`0`DeBaLua* z4A-`1plE9bwgawfs|EzFDbhe5u6fmf;o5L*xbFNKzm3Z4+NuG8Yl<|GhihIn&~aSv zvv-6^+?XD2dbmapudNOcxTc5#dAR1)0eQGKZ;yF<*fi{%w}%4?l`S%qd5cF-z3yS#9I191Z;4jxY83&ioM z!51GrI^EM#n|1Ap_SfytzUpqf`d-w*s6V>0HZZyLSoD_vK2)4@!m8TIgY+>sKX-aD z>iKOd?tJjkd!LAQ-Q54gO}&G=KDT3}=Qnz8?c3Y)`JONI+}3w{&u{hK(G!g=|Iza+ zbEhd^Iq&iXF0IU8Scy6mnFepEK`+R7iH#!6l~OwPSU*hXGI3A(?^q1cjnj|$H)scR zF$!toy-;`;qtplw(G6f^!##oq2g+ZjgT7j#EJ@GMr{EsR+(!}lYIp?yz8Gp&m+)$GDB=>^*afy4+ogpHXOnvmU zZ=nj@1Fr(F+lwLh{sUvlEPjLclqUG&nff?)1!$}IyJ+~U@>&R2hQFCvTvwhvJd@?XlvQB4>RH+?D4F(0(%qV zYU~X;hN{Ef_#5Br7 zb$zU!QeyRGYDk0C?-88_tC*3vOtg7=>ca)YDtI>^tC-~uVU=gH^Ra4Pi+T)6{-o{= z%DWI9utDs$gx?~8PSP?a{dYhu5Z%N0L7JEjIk9;)y+;+N=&YX(*fYQ+|u=4U~f4Cdpz5ei@ihoxu*BPWVA%dX(9U~taIwy72PpB{rTxU z`8P;EEV}%Y@*K|ysYD0HZ1!A~sVozZ=RO9@l8DMo=VK6bF&&)vy1x9Ipc}wg4;c*_ z94Py1ola4m)FS!1zCZm{qSMSFtZsbW$&6I^@y=P_Q{9wuaJK zq&#kH)rVbPGi{6*#utM+cOAL*xl*1*w1<9Nbc+b%J12~jNF_ReH5%rVG?nI@g>V?6^Kl5em>Z*< zuj^YxSha@x%d?0oM5ECTze#i&i|B&VBHBy$S0o&QUo~yvMEurYz82$q%){0700iMaj zm03l_@=xPgYqYUdinANi#-2(iX!G&c+Wc(U=4TUFhUQ&;?1kujOUUMDlWt8u`l>py ztLv-t*kk3$>f+jnG>|b75(aZu9Fr{@{zS$Y9`^5UzYl5~B09 zG0??mI87mK%vOuHR~u7%18I^rsEwtQw7K|e!yN4&?s}5uXn*wCJRI5_ZM|21ih-5p zJpTJQ1YIm>LpUtL9POz1AN+qsRZ^7on<)pibF`~8NgKprI!T*{L$iv^Dq-RDI(p|c49|NtN+u!$-XkXvYt}ZP-b|kvx!(V@9 zFs|+O@YY zrn}M19i3YYujH9AT#lVyUXI4j&z~Ku%%5I;4!a(oZ+ip=JS$F&j}ldYmkgI~bvgP4 zMeAp@7k4VQ*Xlb19$wr{>Srm;mMFPAfLIi<$sgn9*fs%Wg!V|S){YcbJov%eKthr>$9MXMVowGU!Ogp#ODjtmPVg_ zo#-_B>?Nf>izsOO#Q)%a5miZ1)^Dahi)XFDXC(ulCzSX!uSdP^Dftsj!93w(C`1Qr z5W6kmw@9FqwA`L=!z~cq!}vj(m=1aI_v#*>R(d^JT^+O*T_674?_U34Fnc~2(xT`R z0sny$kIW^i0LKsqCaIj}oH1AV+#I6wB?9PTIymuleTh(n)j>s)2zb^SiLiVo?BSSF zV(_5{^?P2(6>FrA{#?nE%inId4F_E?d#-!fL}P_f89d|?h!l_#CY;XwUdhnD)i1_SFSw2dNzFlak@OW zawh4kLFzQjn+;M2j!?dS|NhME?5t8Aw;2C9%8|o(wndl2j34?dN&h1+(Sc{m+%$no zk(eiaIUJ$`Hu*Pb26QnBY2teTFG&m+A^!6y{|UPCyAi73&7U=n2sTdV8ir~y_x=AH}JywhF&n|!5 zALp&k1xFNJBZEhR6OYOzssOjJG?3f`TIM`o8ieS4X#lzy4W)^%>sv!bSS7!Y{{-dS zFQO_b%KFXJ$iS}}YbYE^kgOqfB*E79>_-;GGvS?(hr!2Qh|b5}R`Ns?340jhG}sGA z5hQC!i@g?isPrO=;Ev%P6h&|{PX^i!m3puKRD#;t2ao+e4nY^!$f}-5Uj`Oohf0xf zsN11J7SUYT8*fnrovvdRkpnPeT);Ug%KB#XKG|Mqhsw;XK8j##8rhYb%s-7M64JCx zBP&(}Gp$Azjvz?bOJDJpyF08!Zv@2;vZ(Nf}qXKCM;yKukqR@yi=q|*i*~CU<5(JUbi9$+T3h1W)q7g zshsAV@i_0xzYv`-|3DYh!3n&9 z)jnl?Gdf?bC18L?h%@UW2*Mh24(d)@L*BM8DO(&5nd($}x^ldDUi1+mrOdlo`;wqmuBRn)Brf{_kN^)hyl~yBr8ZK)9VSE@aqv$eq3oNKCE2?M_1hu#fM-ZeH=7vj)AV>mx zn6QD}DHtaz9OyXZd`U7y{bJVp1xPuiE8&j=b6@vM=2i!DUw>$9MX(LkE`y1qVZ z5d_<-&w^hy`fNCYAnnst;?uky^)_M1o8e<9L}y-)MqZC@MG)*uBM82q6S-)J5LR@F zfd9aWM`m9ll$jvSLlPlG=Su|8#dL7u>-rL*2&;qk@t>fa`$beGMOoj>N{M!@j>WUq zNQ7_%LDJZ|7C|toMi6|#A_!LXa*H5n5d>kyb|``%ZBo=m5Io+!2!eZTmly>2i)Ul4K!GYdTPiGJCdyHu9XEd--?9`9ZR!D)*i z2-}JItqg_}iR~)it5Oy;C^FqvwnIn7f9C%ys*<9t-%LAHw@YO?BZA;@iy)ZtHP)CS z`JP0M%2%TA@Z1?gJ{|LfkD(A9d^FV75@ksOouuXVwo?Q_(#G84z|L!9ziHYS*v>4W zuqCuF!KM3PG>WREDC;*<62SAD?~x>JY%UZz>3H{|2aXu_z&wV%?S;K?^gyzNx+M4T z&PU8%$ae?foD;^8qR+(fEExV1mrGQ}Sk2m-VQ+h3FB~zDEFdNJY;8t8hNQIutg$X+ z77)f6wj0qiIOmav&uL_8uuuPZ_aX+~Y?1)a!X!ah5{x=#O+FdjqH0}z5iFo^#6ZHH zI$~gJb3s>j8}`6FhP`cuy@hjuwzmEle>52NM}K{5wD)m(e_NI( z0x=beJ{ODsz$r8ri>S6TaZmbIP>9aAf5sQ5p;INHjum0r@ODlFApTt)fea z+xan4&Lee+%8&v)Xa1z1K`|sDLUg`_09}lR(!|&GCBzKfz%bEZWCINjl>JCYOH?OU zL-76iYq!5ebWhO1iRqBb^#U)^$z`g`i$FF?_qUH5qnz6lRY_6SH-naT?VAU`Y9vHB zG9axGS4L8qFiiSv(C{4l;K3i#?`D{EePWpW>gvfe=jWbXp_Su{87s#PlhN4u`Lkn{ z`O~YMm7Ljs=H!sxzt{9o~^%HWNW8SvYvaw8xL4-^YvHI#ez1ZzglE#xAL}K`l~KdC+)Y* zkd+n*aJ{}MSh;Ekm8cT@&)AUm73diozLzjW2iuO?f~l4y&`DZu&$rnYh)#MQnGU(s z58tDTQ&iVa2Xtv*61F33IQ|b*jHc*Ek{`J}d?%BvZ^mYmZH4D~yA=sAx;{Mk-RoB= z4q&!Kz)FgudoN4hCvc?z}Wh=A5&e61UO)k0O<+Xx~q_ux;3MbRWc$0PIWC3 z;DAK}H0)6iY&YzMBLPm$rklSy9`|WrI(y9(o=MT|Pu6PzGA@^>3|*M*Pg`%?*gLaT z<=%2I3g?tX08FtV?L?}oCie3A7?R#Y5CdOGz7HovXCBG*?+thdO4GU%nKIwL9>5dcXG>lXGb z0$}n$4SU-Qd*KLxQyYi?s9$S*)eReU>oxw}tpn4a&#{8A#9Z~ zphi~EQ?s*UU%M~vxE1t{MFC94YSYBRn%F3dGs;;)imIe2>x*Cog`)sYbu9|uI~D~n z;T^-?Hp5;p3Ls%m9R;v8E9lB+%GV}yA_1BeRKGfXJ6b_Sl6_h$C>#lp@TZLgc(676 zx#$<`*B)Yh6erBbm=~fpXKVOl&Zy5nExIT8RpW&SM*$@KSrov;#<00q$K#T>CD+UP zX6!B5R%mw!EFoPqmR6$xzGG1UlLum!&~~$gLQw!=33Um376s6-M?HYKDy%#3_bYDI z6>;GxfUts;*gJGcy?6fogv;uq0483D-hX%Na55vCZ4K?A-xu8)s;z4YuS}hC{Z##A zO~;>43eovs4l)mG{?eRJ1vc4J3uwCnsz^^)MC_@HXG(fY4n6W9B zye+Eh>YL$t*;d#ZQbz-v&`X73_m}Ec=tTR^eH8VLzp?Wt(dhqs>*c-WwejyQJ=VK- z@@GALw;ZA9fTPjqfBnbx(&BdUH}0bH)SiKtdjG6vdhmyD?};XN7hZbo7yl2VBvOeE zbRi9nNqQ#DIb)9TrALU)mmZ))9Vfo7FFh(s>G29Rq>&z1h)yFtE-R%+neJ~N{|U;u zUqn?>l=aOZsa?_o{Hu{3;YfkBl3W`Bsm*we46g}~8(tmGq_(%+@fwaINUP7acs;C_ zub;R9u7P}|h`V>ZbL;R_on*a(>o5-$dPg?2@Svf^hu>Gy+CbgWa+nwP9sZSQOeSL3MNbOtTnPU98Hi`r)#k}F`@Q| zj5vmBfX(qY`bqbV?u7RH=+An4*6Y8~oge9sbL)BLDFXpNO>@qeEAOTX(C5*C^Z7Su1MTfcAx$jFAZ2hboW4yB57PeM!&B^Zw|T+G)}jN67;Qf)d9?HamOZ zj0|j6NunB}@2U~ah#}BUFIBp@@uWFwasQxxMPV5Ch;F!K(GBStFs>}R;l^>FH4g{e zHUe*~jmC|RmmpO?y1`|~U5rIn+dMaFBj6b~8aFZr zc8(jVgHb=uXwt<2V8iN1%f z&eow%$9lZk)UDXm7DdZ(neAV7aAZ`a;H+k{zH?TLHj0)>Y8xAwH9N?SGrE{=#*M~} zUEoG#q$T4<L}f@nUNb&{ zFGXU>=&uzKn%3PB(x(`-ry!8XPG5vB{sNI=QZ$ujNM? zdWGmT(Y4OfgS||&xRtRA5gZ*W{|}sQQR_Yf*0={-CKA9e?0wPK<*RRe)z0e=_a{XqlgU z{DtUz{DCe;Luumc`uMZ=wc{D|HH<}samgj_J$IJGQRlBH?~8UNv4`-?z^@wo(ThTp zSVxWUr`<2#s_ct)Ej-{_r}77xk?5OE&hd*LpFEr0L&N{a88P{z8Tpg+Y7z1 zaAr~)|Dsi`?8;g>%994>qpp_*rj;2Jc{Lv&)5P!-TC#}vAm2HkFL0@R@$H!iX&bNfN(i~BdJQA=t zHU8;Unj{KhPZ`mr)j6UgHb<0r{@B-CPURqHtWWtE4AJ=*1YJxAr;slejFBG|*c^b75(qjNH>I{vz{6*c>g5KUpirw=DjaGw`R3 zRn(3-+CSX&B+b$O=(BlVd7GoH_sUPPN|ffT8TnQb=wd;;BQ5(Y=WLF4bLMDQD;YSn zC{1P+3G6b)MO9Li^_{bdv{9NS4wGq=q*H@0K6-Szr>Ay*J@iKH+F2BR;{HnATIy&m z+P~u`(Z0T)T^%m3Ej@Om_m+S9lVc-q_3W$FVGVLMDd|e-xN0qo-p|%c*_W1sMT)sv$ z8eG1t#O3~i;WDQGufgR)1}?SHy9}3tA#;ki(f8n4=_`-LZx|n?l+JLO?cvy}xLnS_ zr8bV)#Ni3GE}JlAv|e8BOyuRe!_nGb-|EXuuFcYC_Y)r%U2ft(a0=n`874?`mP@|e z4AJ>=6Lhg?ldtQ`%@azw`2w}2k(;j*oknh6Qp!!l)YvEf2ltDpN{X_6Gxb?KYmMBj zWZ=^xyRDaT@_F+$|kK{n^d~mC~$k(Fl!@v98>mLkeTT+k~MVAQp51e>pE>Q(IhPk=S z1ZmD(<#Th0&X)+Fi|OFR*Yzbr5mpElNh07`Yb3(*nXrdL8_({c2lY{mK5>jt^>FMa zpVq*4qO}{p`1OtGj$KN#LU@FxC)^f-<%6H&gGj>$a(U+?`!Pup>Me*Wy( z%KU|uXsj}~G8c`VUS5vIP+6Hjz4{#DKRrJmjZJ>#iLtqrmGg_IS6Akj#jWKQzep6o zm9(bte>gElV0GQZm6X3uARSKY@O#h=&~YanIA;tWrLs);4(V<>K%Ykk>BGOFVubdf zVQ}L61J>pJT@m-UlfL8oo1`**Rh4inbgq$buMyoW9h~@{kV^^o2Ay1?I;@Jr{ouOX zPyAo0Dq5kFMiLX>$;8(|UA|T)uYmu#BPS9PdZw28BLBQUx~2AY@;|^YobbQyp#%2_ zo(W=nZhr3c;>pDWmFVP2SFSw2dX`Q^2(!wWq^}04(=gXNNF4}_t>3M3ylc?}qZ~Pm zXIpeR%=n?dlJr0F5*>J^%uN%h6p4A#m%|}CV3U7?WkFpHh;eZ`-$LA1!OJ7mg%&e6nki1b1ZHpBP6Bdxkw=3Q5X#SK~fq{bpiM zEBC^Y1dmU4Et234izEoXVcoMV8H&oxQ@-vQqVwe+=wdoJvG(Nap5_B;ul&>P5?h`N zM-n_fX^{jS|4UyD^D%PPUP@G!7?S=C(1kD*q60Pvk4yM166ho?x3`^U1;`R|FFVhl z6*$kzGRH6#-5^HEP zOpxZxXFe`NbiRfLI!GK&d|h8dE5drmBHBW_?XQM&)R-EG-h$`5chIZwq^-^JohcC)8f|2i6eR3*FQQ=XToLT$qT>(qo}5@CDp3V^hBYy{o&dDWPrfD=qVqK|(8XvdO?+Kn z6Dz`7r;4PBfnPP6*lIAMAmOiD5e03oC_zU^ruoqqnlOx8I^CSM)ig*bPR> zC;PH|DRDy3pvdEz&*33DUrK;3Mnh@h>jDXKuU`>X^X%h4K{@w}s7i{mz8QZ)yP^t$ zUp0R0a8yBB;rh5T?nR5*TQ%P2c!YSL0+%>9T!OJecr#oUD>{-Em*J>_v=2~=%Lnwa zF#ahSy}amU`_ovTJHJtiSN(fr|~T!&_pbIiHw@dL<_l%1J}iU zpv-+j#b}gH_Mwm_zAm40F6%c_R)SwOvN9Y|kXEE?G1)d*nM4y5vJ&SeE5TbPD;wjo zXpug(vN9Y=kXEECacQ28df6uB1~A2AwJ+O3bmr-3v?Bd@mm&#L9KpfwUVoqB7iCKX zth6Y)rUtJKCuk%{B|5;dtd*3hEK`V^%aVx7OgApdASu%k)4_?a>uYL7SQ%6#O-;Kp zC>%+UG&Lm#TaP5jaRgrwaRk@nafF$O^53MxA_+Qc=1%GhiQ%K7pHO6MS|q`(6-f{n z2wG$LkpwA(#F=FF4Uq&P8^VzUr@9wOaF4AG0cJyMK76e*MCZ%lt+Y0zNOBnZP7tHj zNP?A&NP<&cizFBg8TJf&VQ=LS83|hvd*MieQ(cQBm}h@tl}yp?PqzJlF)o*=EOpnA zJTtjhEbM__HF7T;NpPxrkp!nLlAy$3nVy|YY(M%KEK4FPGo7z{f-a_m6Jy_eK=8W( zDYewj^^ZCqP$eUh;FLuYq(=k3w%uWlM;YTaj$L2h%nY?`FSI+1EFrfTR}o22zn3Mev^W{b&~4b;X4nfx3?%GzD`H?|b3)LU*b7)rkXZX*UCOthLUg_t z5OgseoLK)Y;+#;CbWiP^P&i^BVbCH5+MEyrmvSBpL{(Ch_08B@vc2$}kUnByYjZ+Z zZZ2P&v^k;Vp-7(=D)>qJ(jY|VO9RlwXedn~X<+fwA(7knu3fE9dNmj|5Y~_`Lej*+ z7V)>6@Mm*E2|_}+GW-?G6R5^tFmfO)qVC`?+WYuq-YQjle~8+7vM9QO5guEn7jaV zcj4!7r5}hbm=gU@bRSEEr$ry2=(;wFe9bLH=SvRIp^g(@*Y~5Hq8k_{B4`|-!GW?L z3F&33)2wXx9?@wcA^o{>4))4nVX(fP6zbg^iYuj|Xw6G~b70=1=)rLPm6MwVVu%2K@Pu1K;J&srl(!%+ok zub>v659!xK?R5;*0H5P;>?XZ8x|22EW7q!k@}ocN>yi3zbm#x~kLzRD+%EWQjLNAF zd~~bmz>RcKAGa0J2PlSc8=~`Z3%W+v^>KSviQ8AHJq>Q(Avz6iUsK{1(MpSiTkx+2 zx8bORw4z;!Tl1dO>!y-F=`jQ`6ruw*h~1X(TO`m)TE^t|TG6hJI{45A;zfUw^lvR* z^lq}d2fl-dXMgeYzQO+Mmj=Id{o>%jn?yDaElzq&M%-_c&%N}y-6EcSi&%7k{x?>D zgCn7l;r!DQ@$B1lf5UV?xWAor@cm6vS)yx&&Nb+Ijp%0S;KV3IPC}%b-k_5!bcWSD zIB;FQ54vtOtPi+FbSz?taeNfB8I5f0IJ)#zr#Kxn6zDo>s{KlkhkX^&lx zba=rc9nv!Z-y+>c2Qb9xbz(8*XFPYt)u#pbSH%5o7VgnsS-5|gJCkyWZ&6)W-!9y@ zigUg{v;!>#_pXR^c=kYraPP)|%JZvd>jwdKq{9>HNQb78x@W`EK*~2fL*_Z(8xx{4 zjdXn+>=WwPf5wf*jX)hz{zxu$Noa74VfXvc?D7e9G(6)*<3`6zo#e)JD^PAUAmc{k z#?EtNx+%uEG3{z!&tsWWqVJ&_vdr=6OmAdfMIUjmxjMb1)<#ORvC+7Z`K^O`qs1*s z#yqSyM)JozM!AiRu7B{^Ic`ihOqirjJKMOi#&xp9nh5GT$Bj?T&L%I9zW>nu4?b|{ zf%_jk6vy|EkJIw(>gVA@RA-XfBsFtq2f0xhSIW52xUmb|sEo8^+-Tg`1#VQv9x`q; zZtMa#S`;3$shQ0vm)44?uB-2)-e|j^@dV7n<9KhAxltLD#w4{#Y91>)I5sLHv=}!U zH+F#=EnbP~jm&10Z?2@)#w)S0(Z)t*+RjO8ZA1>^M&riLbE7uqgmI&BW9PY18)3n? z(YUem+-PwF9G98D(ec{mS~1$V0X8<;*x328QM;SnxY4+=)7(g_8Pt}~O}w%oCl_t6|O;-BD|fnS61PO33Z=slt5&P5|c+uQHQ zHX-~eS9G?FzqKnphCg};ltQ>N{1xl{9BTXp-xf;vQ?6lc1O9dz{tSOvae;;3V<_QIxoUUfkp7Jb@3{`Eiwt{Z?FT#gouSYa5ME$$@?gChmQAfB~K2d!l2pte@Is?Sq**6|(A zZT~NNp@w~wn~^*C9j8zfBUnVbwaP7PWag2mN&~ZqY7s42LV{DbtVR}mV<;@5F5%BS z5{5s*Se7=nW$_n$V<;@5?%?nHYwzxiN=uJHgA7?i(9DZ&4Vg#YX>P2=(j$$Ql-5wu z@P}uuvxerv9(h}VZ`Ke%k|y>%@HywQzJu1#Q*MGNFaFF%{9{+$U-0~6QLp)@UB_&e zHKg^8Jwvyt@r_*~I*o5^Bhuh5*G0*vM1ZKS`Up|i3^KazpI%)!cYy9SI7j=Gn)&A1B6xkHaz(qY%gP;=qWc*l*f%5nI~$bm0ejg ztqe~jq-~j2=H7V7Tr0Vs>yXR(W>6uKht_~l94@geb!S*^Gxt4EJt&66!Vmi!4TcJ_ziv!x)_BtF&Ft7 zSrI%Fc>5qH?iW7iT-I+U2GuK9S81Y%QW%47vM3*etyxCByP|!=)1RNt^AMV4m-+c>a=c?4d;rZD2_rt92PZCK@5A1 zeRY^C+LG8?$iQA2lFP7X*u%JCau2=WQd>NN%Nf{91CZroPrpXus=M_%Z(tN-&1&}i zEM!R0=VzhEaSF-4keAQ5o!G+#t7+{CTQNRHs=dv5|F3MUs7L zZ(t<@e`(0IJp7plqF#TL{0ZJ<9`!L4qB9RfLk~n6axIS=H?nH=Jv<(7Zs-SV(e>fq z{j2MLJDBZ>7@{8*T_WH=a0*F;G83eEh?_%nzC-|BOa~{vF1Q}612}2thfdKCB$D|4 ze2MTX(P<>Yw%^sgd?xIPNCVB~VbHzD6pq0BRdea^Sk=gOlfP-;J6G0j{NmR)qC5Kj z0Quwx!@CFGjNYOJE58q(m3xau=$zB-RG8c|@b%tr^t2tD=jYFkt;}CoiN-2(D|6A< z>E-2U43(An)2q*&Jac~T`T1yU@+(h_&8@7QUp&3KvN4P4i*)bcUFogB|KY?qfmcJ~ z}-yiTU@9!VP{q3ah z`2HrTOkXXfKaVa@L4)IO6WuKTh;qIsZiNYuw9TZah6lolEGcTI!4Z^Zp1C!#Lr0F`rP5^Ly#Q zJ%fjW9>}@*xzmd$R~HXdqLU}xN#*&~vveY3jaAN28|c45>PX;kaCbU?OpJs7&`W&{ z1U$P!TT8kZ{g37f%xa_VuUnCabLLfF<9rxjio|r|RL5m}4Z0YGG%>b)8EsY@u-(@X z+chk6@43#*@|q~EwuOx7e=}W+{`c{}u;`m9K0>%M{1t1)K#jj}^uL*IMgP0FcBRkc zp97%bud!}hw7vFf{Dq_c&2%gJ-^H~b^zq&<-zLR5CzQ=kRI|Ct+%aj+dZ(|0f-X*J zkg*o!>!9W*YOf9oehu1-HLGypTsZpQ%&bNKOYA9(XGqeofphj#l&B2;XK#T|$Jp@o z$PgW{L2WHjmL$+gT5iwxjV=(Kl%Y(AobMG47IIe?Sw!85estyIY4b>cO(;oj!Z~x4 z&&eS=UmAceMnh=|Ndxmpv{xFaHL`H@KeC9rg+KF1up|lL%J8>EJrd#Qe`FDL2Y-LM z_HLg=|8oM$@V7NQ5||m)Swq3-e`F2m@Mr6&%o?icw;$c$GV;Ev2JLG5>g+P7^VQRn zhJ2>MI;xpj+RQcfwfo|{H5{$RxQKGrPeFq(x?hZ~5cE8kOH_un!3*!(nFRKf<9! z{=+l1IU>jDlD}Qe`ub-0UbdC2y$e`H%E*7MMjrdP-{y$YN3vNyGVO|iXXrjPmeD1m z(^y6u*=vZ^`gue|~Mss*FBXl%~z6r}nhrbqMqWA8w$bT5q%`$SkvB1B>boe{7 zMyP{|gu@M3MmadN$bZ0xSw_?el+YKAlC1BbWn_{6n%d86(Z_UF(MINrMg!=7PJg}rd( zKU%S>#hyj}lX4H`M)<=jMo!R6kVdtJ&pYLPR`0ztah;#J2lBs zrv8wLxzwK@DicvG2w4*OD|WQ=v!|#n4LV*WI?ep-Hjn(ba4sDAk2JDrl_#S0$bT0D zk^esYJ>bqF|4}ET$s+%`j=*>$*PUAAKc{)zPW=+J#59rrD8|DXY6Ii6BJ$sHedNE^ zyp`oWwz8cbiM=C;`k>Lg@fLkg$#O>2zvKF-e=TBf$gpSFb24FDVJ{r<@3=nVUyIlq zFzgxjwjuVy(f*EiE85?Yf$#U*+lupjKE9{348V$Hz9H8c+z&Y0%vCDNHH*s`(f*EG zv_EHW+j_T#Q686jsk$^9RDZ^f|qWr0`7mo5rmXH#A8`#18o*Uw; z@8%ke`lCk%Z1)zlcV0JDc70U+WX;~kV2I9_f1r!$-~`@4vRQKUxt!-~ul&J@v@2+zrn}UvmwJWhH0z}{vUBUM zq=(!GOGr_b6lHxg{(&y<+*;0w^mlxgUWV9}NSkI2CH!Of3$KURn)qADinK}i>r$k@ zX^ZrSv3s*EB8&95Nfyy+W~4vDp+))wK5Tv{5!2OOG48DP*{c3mYbo0*QbzhasNY-o zQ+Me)KUri}QPL}>m4&skB1Jb+`>3;{{E;;1PL#jMtRll7^#J%bv{H3z;*TbYD2>q3 zAj%)CqQps^8)b6?^F&v1!6>SifBQZ^ZSSXc9kW?`>$N*6H*;@&kuV4iUbRMIwUUED zi|}U_ksBNEDJ`E`ZGC++9&y=L#ypWl__GLqBI?9u&J&FamhBWOx;{@7j_^mTRdtb8 zT3xLg(OU=n{qs2I1TDGfF)i>PIB~f|72qTGO>dSr!d9!c*EfyltJ1{65&meks$tI} z{MDi@ncU;iGxeX>PHFty72QJT7)#aI3rF~))v8+T>Amn*-Tl^kA!59dI{OW5uz9N~{vs_O7(D^=_DN4b6u%)-3lul5enVHLMU z_`CP?;>y^w(csB5=jWbXp%>z6Bm5nnh+R50_~N5Sr+a$1|M4XDSDyx+%!l~!eA4~b zFAe_X_2&lv)6aYVIKKWRit`t}6-5{C%d(92QX@r|4)_n8LYC1{CP;JcS)a2*bpAdD z(8Z!nzV1C#hc~@&Ize#2{0t-*XmFtXWjZ8M&eFL=72ls93-dD3X;!aZBvJ7?(c)gP z_8-^9efV#of#o(z^_=*+e9pP7Z^l>G$SZ+49G9AZI~$(8%2ML!f7JQ-O)vFN6`#uJ ze-AyR*VaC9f2^vl?WU(b@SPjK`1OtGj@~~&KKa4$?twQ6$zL8K+EC=b1fP2bzTW$d zp0?xk{QTLmmH7)R(O6|}WiA>!y}TTap|Uc6di6Q<&hzup*yLB97@KR#gZM@IU*H?L zGN=(&5z|>>=Is~ zgWD5TNm174W14%@wE}*|X=c zrHbw&!hhhzc3p`oU{A1RvsvpHwL6?Qa~sUvkQ~C#7YJXVAV_Pk7b} zpHL+u>fe+_{d3rmz8ikF$oc8{7?S=D&@oT=e%27(J@gytLjj$n<@S8P=mOD6{4yPK zzE>(n?@`4m%KPcSe+$W+Df*H0Z*Y6`le#49o8fucSa1y^SwXtUE3K}hG7p4%9uxAh zP??{y&&46Saq$~81-cl8G_eE%w@c5Wt)ptMBtSo_BtbapA6Y?N!k&2`5_E(xW!T%i znL2nxT;h?-oh1^BzoNW}bySse;i!LP1u3z&f!$p1x%;io%pvOEe{WI$>MWtMc%~?Z zEOg%SGkVY$fmFS+}i&D=21G&@+x9Yp`FteqSf3%@%1bsqk z@m}QAIqB>;SwcDt+FB~dU+hhg{7GF}XHjnyO$%*<$`0Gy8zX7v`06)VY^+9Mp_O7Id+y~=c zR3$}O-;94w`T!xraW5UUhE_A9{t^C;cO~lP07bVLqW>z_CE}bDH29*=39%J||HS1I zmBBNt#ch^1!sOp3c>-6Lv!ZSi{w&%b@L}^p)CrWNd~r4IQ`R>lcVt@`^FmK`C)%G` zL+*K)Gze>BSe?&FazEE0m-Wq{ViUBnIox;9H`b+Se`XEgDVQ|`Ej45fZB6`TM*Aae ztXt9k2Bs13FUumbRdV&auHo8RjL;44~X16Ysj#-N!SZV`=eE=hCPe+ zSBpKdnd>4(-SCurvQ{gq*3}on6Bv&6N2^q|*we?4x#~KsZk1|e(f+FQvLWw+Z#{+R zn)O0x=Vdq33sEHe!QRlVP+bgr;Vs(VI@`?+AMTTFY2S7;4@9k(`l|jHSJ#3ELK*Gv zp~K_qXn&u$o2p8KS~Ri0_<7$T;{JW<`o%#+6TA3D-$#wPD^7cXy3ivwV zONKTAPX^B6tHn8cGLBMNCVYp~>1blF(+%*P&Q7`>-`^ya>8mB&1JVi|60v-L{z})^ zh)x?#>aoRNst(n68N6A z0GwMSLDwg`v7ka@fg2bq&##{K28NA95M6PP)UPo?v zqw5W}(s0&6Nv(|CWMiX^jgBun%Z<87M#hcCjosizU0fgIM&rhAaHDg7oA=xGweQt7 zz0vhcxAaC`lp7lxZEWnu*ytRNHa6PWh#rt*AakEz-$|QV7Xih_MjIQMJ3GmZ77GO9 zf%zL9uWj(SnACa(MTgLvjh?8!&SeM^_u`qY;Tqx?+%%odBm%Arz;$VwW z@7AvLEIk&z<;OO`IVbqri;h3UB;v$4C{YEl!@DbGECSFnuKeAVAvzy_po`H^n)tdt z{w(TUd+`T;4aOj zdnWrFv*A+{eXr}XZ#e^d%IE+Shx9T2-gDhihrJ){jP4jt-aL~n{}98i=<-j>bCyHC z{42XYs(yy#Ux?1fAn0N`IPrCT`KNvN%qeO}t`+6`^WzG=N_0=~MJZ=Gz8RjEZ3W*uL)K985+sE-)|xeR<>P-5nKk5|Nyy6aHL?($FAdBZs_}X^H8Q<5 zG#BW#Q)-U#zX5KOYPvEhPgV`}`-%Q#2qzxVd9i+nsYsf>HkD*pa-?cJTT zgV`Plc+!e)4VgF4X>QUQT2fj=MZ+JSwayyKz@J6>Fl&hTh?BH>xDL6j@1QlLjP$V) zY0$_woo5MQ^eDO{V4oD89+yk$lVl%I$mi@^LLoZe64Lsnwevzx)BS4vVy_UL#xHhO zDG7$CgNpP{X7H;@60Fk1ETy0}_LMHR$wvIsS8>58s`F1@T#I`1FbM6k=otJoYhzm9 z^fUAvG#I=@bQ%n9L>ns-2G!QkDoxH(3S&?g(WO-x812foh9EPFjz5-r=x;8Y4AjjH z6-@@>`RZgKP0&&b<4+gEX5!Ex_4!M{rgCf)U zx+v&kIyf=@{W;o)=>~?02(lV9I8gpF9rV=_Wl1_kpBg#%D$!}=;6~Uj_6(D{){bN~a4Bgv!qp7G)1C`1Q*NWKT1q~-QL>*(myr3K35 zj2Y7*=X(WZA>Vm4Gx?M*dXHH~c*gbVHaZ0tKto0XH<@MR`a~jQBbL!!Nl&^DMw+Nf zin6{LpIy6F?dUC|<+%fN=Oc79oGW@t7qh5U4F2ib@UG9=Tv5V9azsZ3^OP@5LUg`X z2D%sxr75J96~Q}EBn)D_)mcZC91L2dCSX9yGUjFEJf4@R3_8=wU{QT^1AW6uvqp$% zk!P%)Q$}jqh_CFbyL6quy8Ll}Z2oH3F`<#Z(-J{DXY>r+rp8{mM06TEeIr`gsOzHS z6X7cfs&v_Qv>MDD%XWh&9N`NjF zw5@t2PElJL9rRVA)99cZnJX%i4yv9js$^i$qOK*L2J=Wb05itjS?yESH)D6zTFUfD zD5I{mDiOZE7F{3y-M_m2w>f_5A-e6Nuj0Xf;KU0xdFZ|zU`tJ*8>tEyJEn`STv zzH@Qy#xH(-Bf6vS50FoOFuZ%<&FC#!H1hlSA2%rVM7=NU8M-;SS8nTeDopMf_DA{>o;g4F{CqSv`IRTe=2lkDFP>gq znP2An(&S$xB6Nk6HuyiB7@x4NWF)S42<p9exiw%t>Hn3(gtGPf}SX*X>bsH&uc@ zj}BTF{|4=#z5OVpiSG}1m-qJ%;{JBhcYJ@7RHm<%(w|2csG!m8zD;zq{3FWwo{;k# z0lxlAI(e6JXhJw}-C;U#Z~R}W7`;pGIL*sHr1i<6^2!O3cAhYP3 z4j>^+8TN`5{YZ_yaP+_9liiB`*Jry+fIh=sV|^C8OGe%Blzg&2Agb2Y=j*dlv)&}R z7mogSe6m~7|N3laiPSyI9#b)|`SLGB=j)!Ji|ODL(ml0n7*A0{8k^E)3zWKNIQrl5 zNsIoM*k#gx!+eaKN6-?LC59w_f-Z!i5FP9?8uFL$TO`m)T5fM!?J6NlNE`jHMN7!M z5DC|rHnz>Qv4vpdBeI0Lggtu)h+&U<09qnE=e}ou>smq?*waS+YcUS`k)iMRSse75 z7rspVClhO3W(gI`8=+h`wLDkJz@SC`GfPMe20Rvss-!6EoAJQO_JTXPj!$+e@?T_@ zQ1U=F%M#MAVt<$DsKfl z{7<$XqNcHhaO(S{K^MFJPCi3EX~SQ8=Y_zps`U`rQU3^kU5fg*!{%iHkPxnXODIHV z_)CVF>L1~+OHu!J*xW2E3SJjjuCY;4Vr#?4VTjJhA?RW{IECb( zMg42998`NGvZMYH4lU{*Fkthu4#7MgFrGP=_07m1ZU=dmSHexu=Eb1g$o~39R*`un z-17)&TfQ_1(fQH;+{ zYAoiV-W@hiWLg>KW^rJg7*5NqsnTikzT6_=a06Od4h}8qAI4nM%7B8}>OXf@`;>C2 z8TnIdDN`%!Uev#Gp1&F#QFMPb_SJG?4XH#Gc$z%=JfEupQuYBfXdX`}sZV2#98Fq!veC<pK5Z#)LDu#1T z@bz_^bK4k6tPwZM|HB@E68$ecQT9ZXsVoyeZQmLyOCl;Woo@|+E~bMMU)T3U*lzCj zT0?5zbU4xU@K8_-)I|BC9ZhGb z4QM)u@|W~yILhCYKFXhde7H*2rc@mtu&TYhr+n?NhqFB+6vkqdl7U{2&5$SJAAL*|}{0$NQ#tnbK zLI_uezhdq2RpT!l?QcpS?XNZbJw9;k+Bog)8Y2D+*{3G|%wsu<0V+*Wf9E>nvVJo? zmTLTkBmPb4BmNyy+o$il&Z^Tt|E7QP+LL|X@7Jth+(W-Fx*iJKi4*ICC8_}LupTpwHnRz8@ z(!i{u#vaF_y){*>m4ze!kyX?s{Fzsxs*M@`wi*7GgOSI`D(VjY%qwB?FV7mwGQ_(fNKc(8Z!XzOL^V)6UO6O>JpV@e0vt{9@ZY@?T{x zJMtgluRD?dBHK}tpd^GV!=GCx#zP5@OMK3`tlvz(G{!lVUphPTAK|Y%k^l1655os+ z@-JUbn*3uVZtji}@T(4gnUVhpe_e|FH*JysFm|&ZTCTBCQsQylmxCcXABUie>EIO7 zL$&j>r>G%~9{MWLY4p$)<^1djbr9A|bK-vCbIxV`X39aV!PViACTJ;*(9zq!?v31p zLyP=}XKHh_;F9{eSXbjdTjhJ%R>mCdQ_9GH8+b#_Rd?ySl{*ow9Pf#H5wud4;4bgYDdX+iI<;-ioRu-Di^|dn4#iGfOR%RH4X57A5GkOdzXGQ*l zR;I$B%@x&q*`=HS`-gB8qO-Z8#S8P5drvQ}j6E9-o;-7Y?%5Rz2CI(z*IMMUnYC6~W#V9K*c&kHCHhhbQ@$n^qBHCz z-I#oArZuF-UO4I>tyt|6_NGnlfnh?JGVB#=?~odM%fYCBv|3e*z1DVX3`|?pKb{*3 zc^7>Ah3I_Qr}aW;*C;(hV}!Ka*t+vq?p-3fc6$OxF+in>ugmA0%lgffeVEHo%?*X4 z{?Tex9sbM%VIBzP|7Liee~Ub0UPu}B@1etbpY$j0(p8^yE#lZ;{Jd|l|N5oDFI~Sl zIPhi^UA)itQICk*-b>}}7IEw~5*hGyep(}ry-xQxoZerzBaU66>n0JhD2FD*_rX$@ zs-hJ-xgUizNy))=$Yp&#y5tocnr@bjQERxD8t=9z;u!7`7zj$7G{V@~181U>CuImD z3Nc6tD~b?R4ENPbOog_3sj}*Q+}vn`UpDO5NBpvAgT$be!1v%?P8My@^@(mQsL)v8 z28PP>t7pA|VI$E7PiUhJnx<-+Dq}TYmP%y1Spohn@}Q=ALK}O}xY4+gIjV!)=r%dz zzB9_W(YUb-+~}748#kt1Eq$4&VwqE-GPFy!=X^SRhvfTZLv*&PrNOF}6BeD!aha`r zcW7c%xwG1*tnZ+tRz@c?No`{z^JWLRQ5mbtxY4+=3*4xTTxHy7+}H(fv^Y+Qbz*v> z<29)tGWQ{u^&OPdPtDHaWn6i?wQOv(v5~p6lia9_YGmAK+}I6n)W!HQZZvM}1~=*= z-WWF;H+F*?E$$06bhBa{uSsi#xevLl@2K8r``xLxjT;^BNv?A>>+3tojk*XZCaFzQ zGk1298=d>xJUp(i{Z$UOYND%SqcRqVjg2-oc42H(M#nI2G;ZtyH!9;r7&jU>c7Yp} z5fqFYjT^hbjTTS9R!uOQQNGC@9%VcM8yjtGWTx$)hex@?-MG=XvD4f*`?y`@C`Jn6q`1Vr=gyLS-~1KjeKcct3+1>sPzGb5RKuQ}TRcbaV;LdZ^>1UD zecY{{>jL)r414ql413fEjp7px(bm(gh`ogj?4?`fJ1_V84SR;YaBQ%xiaop!FeLZV zzySH!+rWFD-UE|GQ8m8bVALP|px@pG2wjCE3zX4ABC(F;>z-vngCf)Ux+myjIykZR z}^di#Bv7q(oh%q*gJGc{r1iG-7r&U2|cp*<6D2y|8D=0YhNKheDu~3(S+W@xre?h z`g_-E9^J4EoO1nC{e&Dv@^KiV^JO6DVl5gc!75G6hJ0gBr4zGxd$0_D%-yxTkw?Pt z=f)c82Ut>SW5YB+jn=x?^DWfAz*xqq8OhYHbrEX((d29pf66%Kt$G8a*yd)zGv<+K zYzbj*wn*56j-ir$G&vi@o-%5CtFn)jqmt>KZp04hl%{(Y3x8_aM-#I_{G}7KdAg^0 zBI@n8Lk>#SPu7Qg429@yUbfM^>{H4(^(|{+y{3tQbxjl7W||mH%myWaGAe(|*xO;) zGwg-ugSM^}lz~0vI|wFPT%p=GZ7Wovsj(Nn3?PaW(&Ea321Taxz3`xm>EIOd!WUtM zYLPq<+7+s+G$|XDfA;2ugs)*$BKejJdy`A_9r&LyAWFL@Z?Nm7RIq_R2c` zH&28^FOLO`WzJ=NGxip@gFNhsu)VUTjhQyaSYbKp&RdVzMV8Q9XrB;SLfzV@ZhK{u z2Wno3?d63C@0BG>NQ=D|_saI#UfHNb=z}&xawbVrY0epII=(d&qVugG(8b&sjbv< zUcH6I@Lt)O$8E2y;qS{d-b;_fGjy(*AG$uPm$}H#w9S zHNp1E%CRhpY<0NK1F?}6s#_9!G%-6uth4?tX0U>k*t5N|_25g-8ez~@sIIq!Hu5%? zB4JRwLN&Zs7M73>gBCT&@fELYkX~xQku3;+T|lLKV2Rcd1?fE++7Kl#nT4Xxp za^~qhsyIb;{dB;}gMSO&EHf-&HAN*^8EdJ%NcuRk8fbFY-@YfqqQrvPSy6RgJH>&d(g!wqzNNGlD|T(2=T+WBL2erWslo_**5OgW4;IPbGbxi;EOb` zB-twQ##-Ul+%LPFv0wJM?U$Xi{j$)P{WVFas7_;AVrk8T)0A z+kRQ%A;>42m!(diguZB$WPLL>muxfajnMCxZP^;K$X)3p30XO24HfI%dRlKpc+V_Z zL)v|N_I_D8pxN9k^@c_h+sNE(ku)(_yBbemc+V_ZLt5+|9#_9#_Lq)J>)tOr{>Be) z{V)BK*PiVAe*f_F=cmWNw?3x$UcucXRG!>3@KW!e_00V6?LCE$W{Lm9DdeS?VS+Sg z?Z=miAv)hf2s(HJIq`LU58+XAlfWAds|YkWQ1&gP6{f_?G}2%r^R=UZcAEIQe9pP7Z^n0UGdGmvou97_@1Z69+52W~9})2(DMCxk zmWDs>3G@r=wyv&^Jgc`*5o3VXL$Mm%LreIxJ+!umR$$L|Zs@QFRB9}t@E%&ip6#JE z*++b2vX3$6%R2wO3E3CiLreIxJ+xIl0#88NJUHjo*d;1M-yl9sl26C>h&Ty*Y)Rv#tC4W`5?nytuxz#z2F{NSV2nc*&f>3LlLD$7#tGcGZuUd zmIV!pAuTRM=VK6bF&&)vx;_Sr@RpZR{u7jQzlf@&DC;-V3$I!d_8$ms5zY$an4?Ue1IHT)U=2;8s~ zU1D9x;fcO#ye-HY!9vNp@r9YiMekxy%9x{eL!jcoNOgy5ABrgp|w4<4OfVt zBHohoUaSZDYXV;-I?bBE?Y)P#lCg(&%J$F_4}rgI4=r^9CB~XNt9{D)W^ArnOIh9s z+e2$_dGYrPZRQHqB57o5YiKU?&ONe*l>3ERotwR4@10Es#L%3pzq%(x=g$j)E*3*A z+tU8LP!Z;4i-bM3HI#up^&Z+5-#hy^V*hMjR6V@MbMhd4%+1f8UW|Hvn~FOheDvNY zqFp!lKXFs<;I7Z@80q-QM$Cy?69PW6OW^{L0*E%2&?2e1S_V z^A}d4vC7=aTr_ric{v(8KYw~%-Wt=;v=~}Vl%z*MZ%xf8y|k}EaA`g%qBL5&CNPnN7_}c zW_^7JJrU{TY{%by*}Fcbqrbv1fZ`6S?Jo*q+(;uTm`% z26cO8D~sVhv#^A87_>dJ^*W?nMGaiC1>wuF5FOSlNb4VTl9t=^S7t8|-NSTnVmjn9 zW=|2{J9|RCXV$pUxRDXiDZBiHdIza-qj6*BxiOuti}Soh#*M~}o#)1M0?W8D?P{sJ zp^9~}5|yEwvG38RWBtwaM)VQ)8hQ}t+-rPJ9=|i|-+yt!_S#Vgfs<@L$8idy%AM6d zWqk+rM&(`~lhiggGH-T{8?`&nj2n#`JI{^Uy;#PL#*LllM%$5OdZXMEA@xJ%KIF2# zbCO!SBgw`_8ylHBJIIa7ciI^@8aH-<8|jUQew|M9P{fAGh*UcWSGQ5xOjpAuYvB6EVjDlJ6k z?}!CmjE2%g>$Z|)Q5qYsa+7mV=>2Bnav`c{{*Kt?Gw05QA{8H>PTl@p!r}XdLwaVs z&M|~9!(kNdb3;h-$>Wo#T36qU7T;|gQh2UtgzmhzKZ^Durv+$nfkW+1hld_GOxi2bslgW?Jv!afQyZmv zqWx8!3jO#AJ}BU~+YPWk+D&ik8TihB`uUDOK6U*|2@-Go;@39@-Xxlnh|qF_Qcu+T z!k(dx|gt4nE}cE#koe zIzb(N4?3LRnVvJh9;I`c_-Witm7vd~!?WSvpdGZgAB8mW{XzGY_xEjTn6a~yzT^9w zq%wWAl>R(gp@MtLrHox?~9c)BuYYD$a0-dB~zVvajKy+JmXFOSD$~`6R(FV;s0xn~Yo}#i$%z-{fhv+cc z@^8=%=wcMogpnEvoG&Gby~6^}pxf`TSUyAH!opTrS8-_G5#Yvf=*9(%6VRA2MsS}{ zaqC)T893DLBkGVRi>1`W|f&$mJUtii}>gU zmy!3?Y2!GTh{d^-t~e*j+aT`5@oDXjt%<`EiDyvb8~o7SYSlM581+Z+493^LH2BH& zD^)*z6kR;xOCg+dN_>L_f5TuSe_)CJpwtSF@*hrfe23&)XCXS@Is;vd2GSI=&Q1`M zKpP|15%?oHQ1;&`b(ZQh{)@{*_XHiB_5`t6IDr3 z);EKcjrsYwH{D%iy<;lVuP0o2)ptxa@ZmkB+{4x(d_Fcre^Y9SIOk;e)cN5JpUg2B zV>T|yHXWb*4ys1@RPO5Q5I)ygafZ*DoG|&hP2?v{evi-)(`XJ%`<|+Y4v(w#Tm9Vk zMVtGk=OSkWUL&0jIwtC%w?Ui2`KM*>`}I^O#{GR-=e`fny>XJdFV`WL_4zWF{b`tFb=XPy>9`%w?^EGc}+6QVOuORWR*wLUpgxH*GO_q6c4wi@A6x%0R~mfSi| z%Sf%Ox8*8kv*a8DV2qMT+Q=$qv*hq*FO4Oqlg&0~?sP!2XT2aPx0@?{dL=?_%8KJ-hP^w z=>9P0&xy5eKIdH4=WCZd2Dx8%!>1VYjZzMNxR(yxv%<$%d4BaQnTpQgSUIp*x7ntW z>^4vPkvcQkce6XR?`BH9|GYEf!&Ms}=$Xqo2OA%#Lnr|YzNTv9Lp#O??1I;i588e4 z9U31dO@FZQVHOOVCYI|qK5&n;TYtdreEs;K-ml*g`{L@lHMwSAn0*2MwebPH;8JV$ zMg4k)3O4goO6)X+ePR3h9WUCt2FHsmzuj5wQ`YC(>(VmN?;s&-SGk|5Guo_q!~Ezn zX6@EcA$c0}GG^_z#oC=i4{N2B_U)aW86V6WX5)iC`jm|i?HC_u5yu9`2X!2T&RDzV z4Wnme-g0oPORO~`H~qo&Nt>hFi0C<+?=1XA0M9ChI$A?P}vCbVi$9vbkM) z-X^W8Okdrb(~7kE{aSO?_C!@u+!(qxf9=N@-8Jrc<7+=w{ly;$&!Dz;wecD{Gd_H1 z;{!c&8y^zLCLfGj8y{+Y0&TXP;{#TIXuV-iDdRc^<_~7RD<64&_ zYe(BTK4A5SdVEm6m%BsbgRT9r@j?Br2CcW;>&Dxru4+Fv$Y>i zV6prb;wvf2`VM--lrb$jBdyFEW^=pkpW8KQRVS_1dBgB-3AMCRzPr9NIR<|9$NXYtirY{>R7u`Nq=HV^QzLwcGxm*Z*5|?4N(M^jOb< z-oHb+_eV4Tl^)k)OPNvR@MIXW&@}-;0a)XD}|$om)6Z zp|nPbzV1Er{Qc}~GV7X)+X?+UZiZba)#LW#E4M^zfV zK7Z#ONA5n-^E=BQMLoNIa_qw!8&N+=xq3F^9 z|A7;a(j}?@r?GUHVS+SgF7&xNMCVHf(8Z!nzAm_5YLBp}hN&)3IxG;41|@$^bQL|Do$l{0YLgT93!if?>o?Ql!?RXO2TVg|T6`)zw%_85&Ekt9v-sTjB)v2nvG|IF z*^O9yIhajm1M_6){p0tiVU7Jh2=+zVLuWB?H+b+4U>SSnn?XPcz)%Ulb z`TLKe0kXt)&j0Mun~q((>DfJlWXqjCa&7Ov18ni_@GZWZcahE4^XRqVJIT9K8G_X} z37hc$B&+Z8BOm-Yp8oA=XB*ZmzwbE9@174cEkEhme3|Zjs^0SZm%{QpF<3SIb|0%2 z3vLDCKXYPvTcQd)LYDL2V}dm2C-2Mo5S=gQLHDF+ldtQ``S+D_eu!>JBj?LRr;+n9 zUH3BGU!E0srC@R%&sr(xllKEaF9>*clNrLiF~h9DdK^g}rLL`xnLds}bifC(+!B6^ z1UgB}xZECA;C&AqcqpClOR_v}oWPWIlJX_kdrAM+TY=@ZX#X2;MRA#C{9x@#{~^vf zp;Bc4W5b!Gt45DZ_bRDvl>__k4;|6dZ~YI1#^^1`^pJk~Ir^^X`YHOH6YGg3ssQF#Kb>KMG!Nl1 zMCa?Lpo>MDd|h8ZEyC70OJI=FEL&Ep1_IX|9n}IA~rA!=ZT(lX0;5-2xbMwb~i>sE!bQo%itY z0~_;N9Hwn(Ny_))|C1Zz>*k@ato7~M_4kjg{rJ{D-1X$HBiDZPS+bYnsFY_leSz94 zy47^M>yP9!Bp;s?G$@ATV~EbTnm`w$p)~PzeXHpx3Fu*>fhQj{I8gSz`b$)&(H_4= zbQ-VzOG>Z)DBWL?tS0cQ7MGapU60ELH{``ItEpbklsrn0B8a09omowb7v?MXo?cuT zdo~)Z?m3&8ot@RJ_Cx^yG^!HNc6Sc=Rq&1-gx`s#8pm=B`WKh>1}=kIt7G zXfLLN6JOVt8qX-D#zksKB8~6Q_c^>lbQ-Dgs#0nkDwxy&zpA9h!nt#q`$T5Cw)gX3 zbay28ewJ+|u&o3pHcrMTf@w8vWF>HsG(Gi7;DvM9dp~DpySDf9GydMssbufx6z%<_ zot>Y5Gt}oMV z?xmAkR+mV z2uC40vjhW{U=js4ceUYz`n{j&qgiJOUitVl`}+UG|1Bc^zzW3quYR1y2g+P=fqg|q zw*vPIF6Obv=k#X;4T>R757GG&19UMON)un#ml#hgt-u$k9f>l&Ki>*`o#-@H;3cIM zI8OIhq`hUhSEaJvd`yBa7H#r%@1Z)mN`FR)$+Pr34JI!W zod%N^m6(hRhDkhYB_=V=w$7g~Jg8mS?-_;mdmh;{MEgA-q5YmmGWL7!NcVd_O8Y&h zY`yH`VV}djfjTs?2f6M^glcG(&u0Lkje$Vz=et6c(F(Z4wCs}?P zIc{@+^&S){*TDWE9EIqB4-!*L_$?CXBrUh+>#qw$_b`5tCZWco+Chw}-NL4AVuC;TgWll}#V&s^JC0boMviE2;E-%% zn{K;z1bBCBu-Eb|8>S0POKsdu_js*6zjxosyzl0_nfFy@eZ11S5t;YBmnYxHedl-2 z$35rXDg!2{1&693Hf)~R%<&VE`JTi1RgGY-;jl;KAvmt8*sk_1I8;rsk#QKA?>StI z7s1?SzUQAVey~T&_arnnk3o}sPZdebdhEU$V$}xY*3?fym)2-)`l;l5c2+-i&i5p_ z7@6-mT$adX;@haW4~?B`o`4J;1O^x%x`zSuj1SY!v(dqRqjQPZ!jD|uGh7j`h2)u8 z^H~lNT682a+DxC`(?sVo{&mIAQUz;is&V{l&+v$NEd+;xL+VE$)8XgGM-|p>)n2n` z!Z_Z;$b8RAE}qw-&3w;=#qOTXKj=cfXU~Bi%J!G^$6J4N1YYl zhv})82#xjDqLuD-%=aw2uOawrb?Hz9p`Y#fVDIbKUHX%2^i0o_xBNG!JkK3;&ZLh4 z@6=ui_u3gchTffh1NUh(*u-xrrnIopnbHDuX`CP^d|gvo9Hbi7i#7EmG45%iZ8a18F1kOo0T*r;-sf6BzMKdNJqiP@k2b+a6>dGX*G!88 zzdDTp&$Y<&yw`DU-cI0iobcHs1|OQKE!uY{{U-Qqjbp*5!VbRI5})8#M|?J4gZEy? zoX!~YCCsQ!EF?cKp84+e|8&hAV_v3z^5f%M)ViHLnr$|K3w~`J=hFN7hp5d)w+^1_dA$1zU0+Py-Onp_ z9`M&~!P=dl!m2G>L6`7VTW07PxNxtZp#yj|EUTYof}m#EW6Ek9o!J+F4r5|m_`0U7 zKIbT_-=q`i?~m`#^n7loA6#Vh`;M~unS{w|@U>%K&^&+hUdi7Ck0H_(Mdv;26Z`lj zL*Jld9GP_Z4aLNfjSl#rbItmHqA$?tw0u63?}72#_)kqg9U|A$opLD$CIKtPSMS8qmMox zqlQnn+|5qlbA0pb|B3Xy%2|qQ8b{{lXDNsCnXw_t=8V$%VCivzC7X0@4%$8!)~Yge z06Zo5RNfb~%OHKs+!T0Tl7vt2tD`p8JdcwsJC~fSN}JOdp+ZWP z0Ta}WFH@@6=mdxL23$+8MjRYQ=1Nv7s~i1WTPeD6%u1IZA`in>lHjn8H+_ryEgVY< z4kL3VN3!vve~a#MU2mxd3yn*6f0#2RpFjJrTCCeXNdHf|Zi;8%!a8Dx4uF4HH=SUD zpl04OWulGFl!>5AYv<(an!0I~ZUFb!M<3AOgKaa0YnqPfRvzDc zrSI&*&Hwb8S{)OxAzYWj8g?sW09Y7PZzwHPrd#ApPB`XFj<~N}v`sNp zBWA}8%)aMU8MFKTp1MWJIsxs(&Dv!<;# z)K3w&O49bdt}-IM{kzT%1}htR8AQh`6yqrNT6s^()CNh%tjJo`2N6tbWuwYk@T((c zo3Cj*AvuqbTaxprAj2}e2B2U=KfatXUHyEGE0@%Asz~#5i4CuGLi01NHPQThZAmo0 zMkx|U^Gi}rM;y&>iXgm=K9RYQr1?4Fwi8~Kn#Ja>`wh^2i&MA~M%TI4w!^Lzu zm(6Ci?{bljRoaYE_l9Upts5&%zT7f@awE)LR_|f#v(Zd2D+V=lpvloTx-9*V|ASM2 zE{%<#aNh>b*T>8-CWZS$Tsmm*!M4PxFHbUnUmg8;(fO0PY(WnTUPUan%%K!4h9jVW zF}*PU1dH`nS&nb9Q(9UaEJo%~=CUO{G`J-e+m1+tT>M|pe(M@9J-#$bW7W-bDJ3E? zj7LNo>cxgf(4{p(n{1SbL}KEBi^;Et{Rz7nafu6 z5aCvM6fZ^?N4m!WZ=2t|i6a}GcrijVK;=kXOV>*)ZtS2Jqh(H|SWaP0O)MwXyPMzK z1K@aKET^f)F{wSdTz-wb7%lTE1&e}3NLVg9=J*(D{diKa7@1d@BS}~ni|Lkfu}m(0 zzZ~j6dHbD{sZ_lsQr=LgUEWs>W<=q`i?R8QbJtXtM!UXueK2?K4(}$l)y#rQ)A^Ea zLE#y=*es}nOc2!E!lveDqcbfi(51C=@^wvb{{csD|2&&4TOAQ&=Lr))2g)FP>w zJ6E)Cbjo28ZWL}@6>fCO&Jk`DZd?^^l)MvaW|<{G@tUq5GWVg@k9S^D(=QIPq{p=BT(_#+I1(p*NF=pLYUa+B=o|C7I1x0$jlzv9%8i9MF(kr`!i_7+jYWx? z5WR7|=#BZZSTVwl>xLUEV#NqIt`}}BWW|aRZd^Cqm=`NXxN&`OV{MMyeWQ1~#PC$g z?kk%7S{YxVyo`m#?w-y6=l*{6gkal3O^FDzDnd9LuGuJNV8oBsXc z2N%7YyMD6wA1==lF1x(T# z#o$tQ6+_&$iTWrLOPZp1L9R!PJMkZ%lo-Ye&l4J@>~C&rcnu zdj1hr&+yj#kw@pf-P2R^Q{L{wb93JAM~)oZJ$>ZxiBCW9&?8e1AMtjN-gDRPsrmUw zjvhWSe`Jm>>0CZUlz0t#%+-SSZ^mgRpksafj7Eb^^(q@zC9~0){R8MGv~%)xO?~_a zj{5lfbgrUyKE6LQS9%xy;G&NY&~;DK`7lc>KDfWZV4K^7cD=9APLleE1-fTPxsJ)E zn)MF{UF>BUgH~8!p3!-fn%9aW8y)aL=Yn|k3+QxO8{f|movyz#9co>leUlCxqGP@E zK_6k``*r8Namq5Nw7Kd6Y(wuBZ&A}Q)9q@Q6>8wM)ohd;;m&OT#!q){t^trW@uu@8rX4}BKc9bAhpro|6b%+@pEJf)Z_ zq+xoC-?$!H=J&7p!6mPcG`~$p-oE{+{YzIpxV4{j$HU`G+i%LVhS_6km{)Hm9W!(}}RA`TLrt zd9c5xYHrzI+f2CDiD%}**v-%Zyh83XUSxuxR*KK=o^As6XeB{~^Vh7)Lsff*8M{n6lSK2Yk@EX8k|W7wB|aKA&lA%@Cd5&oLcpzE|4xlBIR- z$rTE5A|ESdTD-+CttHrdXby5AsMa0w`k{$0dPAGvsCt)&x_$!x$LwC;bJ=oc`VZ2H zlCD|a=r@P@;@&z#yWk+^ZoNkbC3Bg{-8Q~lF28kE*Lj7?YM0948vKQgReBe3A6=Ci@A2g($<7?`dAE;JFVh^S;H#wL z6wkng@sgnfXf|R)zZ?o`u2hpY;?zcG;uLgg`f%avnmE1R5vL1uA{U&VAvzbFKJAFp zV#08W_I1T+^y)6foJ31YwDkHIZ=>m7^RYZ1Sg6*~^YJDjg-S?j!1I9>YOCby7@!|* zYkuLkq)P=n0~hX{O{q|2f}plZ1sk0y6+oA!4;Q{JdM$kn?KVfLaESirA{Cw{Iv1%h z?V+u2Q=(rlkscHN6@7~5EPqyl#u{fuAN(> zHqJ=EbTlq2al9K6r5N@;=sFx&pYdUO32k)HA4w&f4PfKzggPys@5&f2uH~5CyE-|h z-q8M~^i935Uw7$GuIch~OlS8Z+vVgf|LsRA%e1+)*g>x?>DJUvW<9F8*Ur#3IFC5f zFZTsCSIm_rm)qz}X#u)4pNwk0u4zpjbhM@(rE|ET<|{9F}x^!?ZRD4|%x5pf1>Qi(M7n%AJ(YeUfjhg=res#oc^E}df zN1gIWbJ=__RM0v`@)^Zcp^*ZL@V{pN(uE+0v}fS|y5#j!4(Y_lC-*P)k5d-u?UpRk zYy2$I6h-&ne%oX?zW*=B-sSjyqH2im-=oF%)9;P=-$!l8<@2;Lwl#gK@A2L*Z2sb= zCwl&@`%7J4PW?gu_x`$`QF>1h=l|E=Lw;!x>5rY{_Z_FWA*f~yn|;S$YBboi^&K`k zv+n@i{n|PCx@O;T(XsE?MmOZrckClNm%an*?4G9kYZdMPGSMYT=7ZNA`;O*0ruU9Y zjw!XJMEg@CP~rYS?bW~aJ0sIUr=+!Tp-??WJUesT{}vPnWnj6q-l;itWccG7V@q! zDW?@vHE5dOy?+1FfBD?&DxY-AAH97C@=3>U8=!pBG0G<$|HDbUw)wj~K}PBAq;pP$ zHBK#~G)m*tGfG=(oL{1LjnFv%Fr;yEX6XjhIG^N>fofYHa!#YcrmYXL(U}@2=v*|; z_Z>CP8|j8zG|mG==b~|D9W~DLM2CKq3%3jJbFCj=j^w?XPvqArKbvZ>c8uSeI?!Ev zi@d+tyN)(-58!pjKBRemDQTQ8eTa+~hGntNqj)>a7p5$>(ZM1kmYcLr zjPD-AUq<=<2bhtl{%!h*tZXe)O-zcctTRz}t%p;`x+G&=UZE!T~2u4R_~;rl&z%;OC+`ApRSku)6z&R&qxQXuyfb?R+vBYxXip2mJ+a<^kS0|Hab&EfG(|_kfoC; zCBzErti~713Y&_`M=fV#c}LpKN3CUrH%46zX#CSp+ex>)^ygtbWaznoHP+Uuw5=EX zhGKdttNzjY7t@(I1YNpLX7y4^UU+A52!3_d)}r%K%lTN|kYRVrD=+~yjC&{9UBP*kGQ_ICT-VqsV4$C^7N5T6n!%SIc zqXRyO5G7lc76`clN z$NX=fy}020InAj5)L7SRSQB-2?;u4ydbjkQUAXz5X#5LDnrnI=rwb)r)4R=YF7?H| zd4_h;jI8O^*fyYLZZ)~zMwboF7yR9aL7I1{=IfeLMDlAotLcGXoix4a7CEaEjybFC z;&#Bt?HJ*9T*K{qUX^jHRzYRlE>g7e`wr2{;CaDqYkUiC>z&kEMjC=&9dX+{pLN19 zpS8_-SG^%ZYj^MKsa)UL7qnGSy_>!~Mr+xS%>DdWUeVW}dSUFMpQ8$jdWI^HPHUa+z7(uL zgXWi;KOzkzgb?{Wr46Huoy}?ms12$@j1GTs7dE#Xa&m%jlwGB48_cyga(4|2T6r1*!1TSlna2vzR z+I+2I(*9glrm)HQGo_M^PHLMm67` zsewLEzq$C`pK$cMW3I>~$x!gCs|=0KAsx=eie#?1uQWHHURr4UP3gMi8R?==_f>Cv z^BU55yS{f#kV~2;oE8QrZ=k5OanIYKwxHwc`J=kd3m!>2UUfca++^sv(0s&>eu1T> z7si7rOKo%}UO|`EPRQ4VC8+0#PCMfD3HqP@9DIK!USA|S7rZ{}h*xArBnhu*BUije z=ZOv%B&u2RMAu86=x}L`Jtbm+QIEpCcZRmn^Rm=9MB94dUfGlyhjb#^W;#=9fG$lR zE__{6YKW%<@1S$DYQ?g^rlRsjhlgW%O3D>Ab*sZnA-`745TWJOJtf}FbC*)7Gya&^ z>0In$_ zR)=@(s?|m3lMYv6c}Pm`*+K6pUWmYFm+v6~8j(plKy)@MYa9KRbUfl2xG*jpBID6v9O*m?#KPES#qirud(&SoX53(d_^U-Q%;rijnX$VXRatWI%Nt8Hwrhd3O72f ztti|m+_-YwxF=W1ON^1k7_FBWqe?MOjFI$>(l@SX-&l?lNh91S+_<9LI2!`*(#KBU%fj|EC}uTs(MJ!_ ziCpy2r-{x*ADws9N4F(RAH}%#p?LU+w|n%SyLL~_ z&p&eX@QL{&a|Ckd@*$#REg648FDf1i)g~kaYDGL0$B)lUMS3Vk#6uw%M4w^K(js2M zTKA#m52)`h+d~mKYf?U!TTKteHy6)uYBf_5_#x?*k;uU-M-Jj$J6lGPaxhnjqLyosUO+rXQN($3B;igt#!v1wf^t(_GeCBj;2XG3V9 zpwzjGkEmKdzLpkJEbWX2j~cC`d@WALMHpBHcY+3wA}|!@q9cavJpP^=?#QB~DX)xNoJH)WxXZn@TxtGDnF z-I=aU^8J~9^rwl=#ZwU{vMxzDjAtE1;;_PN*|^9;v5dqrBFOn=IXWQ!7j@&>27B^_ zY@E@|wl%X~PSQ$f%_V~59ZB91q#_rVM7+L5}PJtAD zS)PYtVewntJc5hyP1{++$hU|aiUJ!~U;D3YX)f?wUnZ)c82=l&Ij<3yQ@ zheA9Q+!-v#4&(o#j`UEBh=)S*ju5vmc}Gf9REXhtD7Dv_nNi3(nu>~UEoQ|-As7@4 zuEy*{GskK8He&p?m|sl~#pf5#cT4V{>RZJ_u`xUp=)asTqi75k<9H~=6tK230;Ja-Pg_+l`y|M;Nr`{gqL{&pRTi5SjZ|DzU!hA`#ln zyM%CXjpZdWU-ZWX^Z-lk|}(N+=s)=7%7 zcGt@0EIEJWSgT{VjlTiGpWv_gxY0(%Uv$1-Io5jMZR4*`@F)1YGVvFk>sOAo0(zWz z%ijc}8S^EN_kFWhW+SSPGgbX2s(*=BLbXNG*7kSP8Gh zaJ*H}+nlFWyb|hNidW*w^GZbL`3=Wg0li)PiC4l0py2Py!(Vic-|(uge(q&H*|&cw z+j2HAiDX^bNY*6G(V8UhU@WU>Dk|4@SXMtL$rQC_G;9B;C5lzG276Diw<1zm7(f$FYv=d481w z$B9cctK|7{ufTl*?{lpmUkMATQi?NUX}i%po>)l!i(M-VNpg(V&_asL@v98SS<|R( z{E2lW_@fqpRbiV2B}utOv8Q42J)h&C$zqVxMk%5i4uZr3BRPxAW&e^)5}qVxMkDzQBBMYf$< zkJVoAIn4{rP0n$w&DQbjqyHs+9X~t+7xeWg8T!DQ;Bi`+c`sTAP1>5ac-L;LRZK_c z_7$?R=0%p=zA%n#bF7;24mLWOi#0SCYattNmGgEjBJoI2{~ zJQr8*;QjOmJ?e-xv1{o#TXs0-Q}nqD8$n?@)I4_|ewwA7(^TVLnqe?$Iel>==pu9a z3i-Uuaw20z6NC?aJy*sN!6j7m<11ki<%@A*swJK??Ca8dOuROJTV@1+jZWe@!||N? zat>~ypyZ0V;Zm`b8>S93m(5Z*f9<q zQMhp>xv>yy-c;d6;l>r^##k#K3pWZkt|&LgS_fFTQMhqMxiQwNxWbLXjVsEHvNkL= zuVhNB5ASy|)_AD&jnX%+WZzhnkwNJjz4bCOSd@`L;l}mDjpaD20f?j)Nxhm%fpC5m_UbF4y_?7&2cM(9<1?cZbv)q=v&s6>dGX*X?I*@o)J5X74)M#XG~hcFTjB znL2(vYTnAyaIBg9%dB6w#^HPFmP0sPSRC)~I=}ZHF3-;HJ(pToq^-GU#)i&rZ;=~y zBb_VhxWqGX;WupJ@&FSAwGEdxx-9*V|ASM2E{%<#@O4dG-bp6FAkiSF2Q>I#`*-O> zKh09*7i{PfldomwMmlT)U5{-YxZ3Y?xV=9}8-hz8 zBYu+rZ+c;V%+f*L#_ym@Vt*5&yW4`)j`TJ zzW8$!ue#hp-#xmu?^M_0sXO|={nA!%bW7s#tIH$CQHGuq&B>mv8QRv1YU;-MX>D{S zenE$0T==@CT%C86tIyDh^ylFFGv(^{iOxl?e#KF)LhdI?uA+@x@jD%<@0MfDgjScr zt?>(;he{2em1(B7d z6+CV;P{KW~=>f6PnGykXY3-agiI9X@D3T-*+*g*KnWBl9ylwQ3x_UitJ8F`WdkW=v zYZ7ETd0~eM@ z89I=n4_iip!RR?^H|~0dGgHwkcMQvVhJ*{TjMj%`G#o2-rrq)3g~iK5LuW73=x}p? zH`d2Vx>SIFkc&+!RGA>CAu&))&8+Glt$#6{X&r$sT_>xJXqx`AB#aLaY0tsWs~z$; z_2X+f4&}a{)65jD;1Qvj4abTas?_EhIz+~_qN9*#ACd&M1#gQ|lM z$wiC z?YG|LZN9qquB*EGH-DgKTk5w`*LQDE-H`fV>O8bfCZ};K3IdAtPM~>~DK63cPryqFek*SA|c)OQ5U`6*9Wtr`y<6Kyd zW#|B!kUbptF+otP=55qvZFHvm1f4GL_`0V2oN<(&Pa5ar`!mOW&k>!A{5K~VU*rbKY{Zro4jaY4pYMCT$A z;;cXbEr1KR3-5ESA74xFMx1e{6LV8}-2XQEgvWm?v1Uw+<7vEr3u+NT@Nj&7ad7js zGWO&*j16CcL(fYR4$Qoc$7e$Xky; zU8HwNCFHRfALu$CWF&U$8HtdGwtU3x^jp$B7=v+J)3ywbRG~Hj4Fo}2VW;xAGMdu@qRwcn)bO=Xd@V#`jS)7&y_3YVt-;q>awRv57mr?k>8B zj^oE1aeSKo=Yr!O5SWckPPf=)A-cnPZmPFlvmK4%do!KU7n2KY_jF z*mt!Cr44_68Dr+UkyxuwwrzFwi`8XHh6()@(Kf$vQ^T{-nUVo?Y3-ag$xwBa4AXQj z7s>Dp(YZ*5I8lE|((qzgT~krxQzNm~-mDbdt*##{eh6uJ)xJh;ZNT80q+3|b`*j|={uBsv%T9dp#o1`?*3p`Bedv*_H! zkyxvZwmT9qKJd+MSWPk#pny_URqfk`LmQomL(rw^!^MU}*I121bRriVK23BkIGlIH z;kJa~FwRIoWPV~XE9bvUPEyhT7H6_B+m33yUe~R+4G; z;gx6T1KtrFDt|h($3gnQx6W-sn_kjzh0mEM`Y|hIXf{k`b1ktz$H{DP{@jrP(t*!FX^l zW~a^5r@&*rH&1r=+(0A1t;T=xeuDAeJA?7x+c(1aug-VuWiaI@GClOdcr?BIHaZix zpwqn(eBE7iTp#~EM#2hmtB*dQ!3W!BY}HeAOg|srpBY>A64AMMH=c9!ZcHRhkHx!o zmY-3%iN#ztPMo9UCWiG;ok!_a)a)J;M>aa(gII1B|3v|vPHW@)8KS!le+UZGq2{q_ z{FJcV#9}VbaY9Z~q-KM)mLhMdmI_G`uV1&TB(i&|~ux(WIZd^nVvDK23BkSd23U zl_V_2@-|Leu~_B^3m4fanwn^80lZftQm>e+#EJi|w3(Ap-FnB?>e4qp;N8-9cHw5q zSllt#GE(8U>G6~9gWJxpkZSI&GqjB!o;qp2+!@qdaqn+R2^*a$B|w+vlTpprHKl~) zWZ)fiZcRn-tD7x99i6jS%x4P_4MADywcDx#gvk6I16~H}D*idG1@+We(EWdszc?M8zgWx{;`qJW&tJT=&-+OK zBxNuf>nV0mzS=vsbZ_d1y~s7jSeC-rB@UN?Ejm%#x=3~uGEnbnZ?WlY2!232F+328q z%J|i-hmX$he$eaRQ_QdGs`gdiCvwMDvB1E)jZuOJ)ZyBjtdxjlflWo^G8XeAYvUOqovtdLkqqGlIAV{b4R5B$(ncq^vs62wQH4_{vqxHfwWt20cDkEJ;iW0lG93QEihDNf=ii(w>8#S3Bfy z>c`hoO9Q{UN{HxOM_Q_$2bHN_>2YO`#+6fJTWDOFqH|?j*~`%T11~Y&Y*vw}x!LGU zT!Jo5A1*drCc&$bBwWU^o}zOf3o&D`+;gtpQOppE&h>7pk4~u(<;Jlo$W1OEppB$k zQrq}psAgQ4c-*JaU=vtHG4W`lGw}$zG)@o{zV0sC*K?^{Bj#u5f4cvk@6XJodY0&1 zqI4f~%%!@KI;^4K8Bp2@?PDbWH7PGNd)@plg#(_zHPTVdvCoZAW zUzxF+W^o#dw>Bfse><@e@*j6<493{W&@u2C%h3BY8f-ETnwYiGnV1EgjxoNjiCI~j zv9sQf9n|j5n2pSTq(G1ux~+^KhjFCyd@~%`=ztHx?RacRmb$TZzE$#kgo z_@|`hKNgFuqk$<~TUsn{TIXB6M=e7otkLHdNa@&g?Uy#f9aZ zE#wIbYD zh?6%i+$h|*qTE;#@1MjzO_1N?YGyO4S^w1z`J4Lj73mve&1EZnqx6l;p)10Tu~xtq zZWL}@Np391S_4|RQMhqMxiQx2$HI-mjVsEHvW71;uViqn4=bh|Yn)X2M(G<@v~QG= zLFpU4_2S_v%gCT`^>8h-T>3`O+Z+Jj zi~!?Udow!Iq~nn@GjiHSClO`gh_c~W^U8^&7D>ILl6r(=+of-mzL7bN`*_~xT0h?T zaq0)=rsf}dWa`2ByFYpN-Mc@#r)ADmg?YDi&eVXq^-#{#Hy6_vPj-(l-P8TX;_okd zH+TJH|HYHu?A~*!bBot~?c~ru{&040D(}5A__fda$7lC8&yvqmGbKGsUYFv?OF+rc z2hGR13CP&f3v-335!mRm^k@DL&I7tMHiE*}H8XCf9doIkp!4X@!Phb~4__oYmt3l6 z9doH}qx<_PKLpi$UG0#+sUKesiuCvBDw{-mkGw9Cl-M@5h zw)cFhu;rB(E_wSaXZQO@v0}nAV?$@R(~3jtNOM{1ua;1t2b?-Gb@-^4LJsSu;oEP$ z%iDZ)?_F1Q^>6+_&$iTWrLOPZp1L9R!PJMkZ%lo-Ye&l4J@>~C&rcnudj1hr&+yj# zkw@pf-P2R^Q{L{wb93JAM~)oZJ$>ZxiBCU3YRSV#yxpVs+_igZe*Tf8hfmBOnWIZO zm#7hKJ?owEW8!w!xPlG0HaZixpi67#Ilb=(tI>caXaCH+mRSK z%l9j$3d!2pGZTyd@AZFsjrY;-_2ws!(mF&%uWNkEcyma{!J+J%)A-?adxBLHj)k_n~{eL&&e5b~r z|Aw|lw+@`@e!S}ose}FB`Swd&z0ocI`lWAwhw6mmUzfFvLlgg}wYI>f4gWSe6aS!# z(icqppK;W+e@N$Z(Y0ZJx#-&OIO^I@CQR1`A3MrzERNDlZXa~PzxWNq`mfHT)Vx+4 z+30`|V!4`_1)WaIxV%=;(YGqFZFM=%bg0?m4$5TBZlha%qb{DBHnqslFOL24T;Yur z`D$)5?7q~(;)lNW!mqsj|L`g-zphuX-Sw)Q^(R_nc>doSdxIsZFt?gg1axT-1cjxS zDMdt!M6c1gb!B5{kuy{DZnn|K;<34RHE{dQ>&FMim%dpDS$|ov{vbJYslfQj&~adn zy*4&Hnx0l0o#2)lGbn56X^nwfEUwZFw-YY7&1G}JG~cZ~txtjBjM?O>i{H5Z*1x^j z{rzixaLMZmme8ly01Gwev7gOdp6gs!LPq{v3qv!-@qPB z-M(~S6Zv}P2VfPB!e0Cjw665&v3FiePkwAtQPwTPuPV!M*TujxRKE|zIL; ze`4$QQ=1>(^o5=;c0bYeXQ|)s|Erh38<>a(`^iT9?#q7#b8&xdGvO8^o|%iS&v=mu zf?B=aMo+Je&g?TlcR)KQU)PlNZ#i0wumoK+=PJ>;Sd3}9?rFNeRg&c#BYQbUW#`6S+s?X8=nu5clSnwqZhs8KEOIAc4a#tLx zqsG+*hl0bM)7}FQeEKsdY9kfLkDkE5`ZnSo-6Kl!upB2>sZw;0VS7t)YG_=&u9r@| zok}&=O`$g>T{p!uaIxv86HE})tZSLNsg2ImO+lB|&dJv`bdQ@m?e-4uh|5m=113YvHIODq^{xS~clXK{T{0M?(X@x=IBMT5m(I z(Ob_lAROjb*JI)1ut#u6FM>+d|E_;=?`~>mHab%~16`UvTx{Bzcn%?DI~O|=2ZtDh zj=*6dp2wm+OR4+AH13?DkN5o98z?IPGD9B=)@2AZ&!o#lJOdZTM1~FkZ>()iFhNk` zHxv_#HaZiFpiAQfLE-B{6U2Bbmnz)=?yr>>f0}4qG)A$M+-2hQR3sKlal95{DTQ&Q z^C)=Sh9est@FAAct%r}!?|#thuld;aIp%GzKr}FCZhz=&f4X?`7L~c(^UCKJ_y5Dm zx&LXb>xZ1d-AszWhE2K@(d}^V%`*XqvlN-7eZAPY-$rLj5zwWz6Y_OUDI(Fpoz>{@ zuAMBanHKrm`#vf8+q>u1EDtm)AIrq-F%4hXv|-jpXJQs~X`Co1Hq1)?c4sl`oWDJD zw0ZvazE4X2w&ZVHS|^o3n?T=&>W{&r{a@0`CqbF_K>_P$R_{xGf| z13tuK6XCJh=aL&zSpkntFmIRSZ~Hh*Oj!@Q1O6G*7hl(u^^(8c zSy_*F?KnDvA^v84hU9Nk`-sJ;@XP&y+N*!-$Cs0#T0awTK)u96;r#89SnF0)V$47J zzPhxLCv(*s-ThtXF>eS(Vs`!M;^kZ3r}@|s57sI&^TTw$q>tmLwb#Ktc7~4OEwiLJ zsL^1PIlz<@Hab&MfG&*_1%gt=-84L2Z)| zHab&6fG(|_ldrprj_Hw6`y3_2G5Vj2gg8xfF5Zg;NAE>CVcrY8YiFxzs?pEArHX=&hQq2(MB7Yf;t+Ic`f#z~P`nqN^2Ig&L) zbb4GE)1lVmq>?ogRxNtzUdR0IN;Z%qt*xd$)kGnyiJ}g-(yB4nVbvIw*G=n440gQ| ztjJyHdS&p^pIqaX(+%w;>DCmUfeUL>89IQbBQEvJbWn4pnzb=%$VO*saiB}{$*AV* zn%2}IM{DX7ox=q|e@S#M*3>hO)>MV=FG-Pxcn?n2)Le_4?t5Kxy4~m5$I2a4Osv*c zcv2Dlgw<@fzY3ebA{)>eV?{QsNuG4P>U_?)$K zU=r)EksLm;#aMgo@BFpbK-0ML+ND?3n%wxcaZT ztzo6LPx)2CS6Q3Yo|WZjhK}L2u>5{bqroQ2N7KTz(V6labh_op*EQw$i;nX90-euA zes7~2cah)kIm+*+6DGgG%Z~E9d0zLulGhCkNR&P`0u}BL)L#8tKfaupv3=Sqqpzy*W-SywjTE%*6qPmXhrU8X7~PoZYy#VWuslFt;kKk zH(G}K{M%JuU!rPkYx-2*UB4Ier<8Wb^x?wSHD&+%j+Wz%bVDwd;{l>`u^h8> z-P3e)t>%O{PjpH0{DRkAEypRMZ6f<6znj`eEJtbtD%>Baz52I)yz`dho>Hz5Cr-ao zb|2$^Pd!A)pXm+tz0tk3p5J|W=$~rY-2+5#i;ljLeoOlJAfAB>_tqIYfH%xi;s6r_ zHNSn+LbTDDQUY{o?VNmFQ%csxp2j2E|5%&&iBq|C38XYz1K^= zcRnA_tKmK#{=QNZ46g>wTBmt6#CmF!6gI2K)Y@!xrq(9b6YHzc%2)?h$GSsVN1fH$ zVp&g9jsEXFrF=1#XQLByF=(C*8p}#Yjc4f|jo+qbOuDyG=3-EmAvqXpWuwl;0Dg70 zq@podj_1*kHNI<1Wo$&P88E2Puy-Lt$IxrDS7Sn>!6tq~G3BF;&XkX!OXCDV;p>{7 z|0>-8?yrwNpuq>*ze^wbX_hL#Ow)HU*ha75A<$&iaal9Im10Kea z&Z9b?nmDr20UtWwgHETl@jYTOZ^H$H!gQ#08I;f*@CmmZ@R1lf;Kx)Gg)FIyXTE>U z^w^QNH*NZ_skc*~qA25o4|>0oAO9EQshj66c|F~4AT#_T<*NKm3fV5VFC92S886!g z&vOJ*?<+KSc;T}b7rOrASl`+Id93#}tO1UHc(?YQUD)-1znY%(_s&A&)5n|jw~Te) zMz;>0>Uq5T3teAK-P`}&@2HHI`zYh(JKseF)1=x+zNUCA;8;{FB{H;)*Td53G;Qle zy}Cx}bXq5(ZKgA&6X^5^GQO@UonCU3PH)lq^!LZtHKh}xoLr>SuN}vwpQZatQuGq| z+DTKKZjom`;g)CK!TzB8?e0%e&iTRdaDRaO1HV7$4*G-JsXr(-^at;GW2!&sdu`v} zd$s=H4CSc*BJPfZ z{lRB1dR4za2*o~MUDFS?y^<>Rojr5O+rR5z^_02 zx!Eu5qBi3)PaBc_!cIle_6Hb}w?{WmIOfO4$V8k~Ol8;$TPDAMP1oe~nD@~?pqz+& z*Ux)v) z4%Tc2WXUU=f%4?Bk$jt><`$x7VQiXx!gKVSUTl4Wjn3>7K(|jjAz#<*6JB<-8Q!6D z>Fao(=FCOpO9R6@R(#gP$N)bys5qVw|;y% zG2HbtK{iq^5uGbf7Ocx!${o~LEgr3!1>4-CB^IpyVr$z`<1NQ(zuKkKX^jS(%yp*5 zYNIoy6X;x|lW44+)mZVa9W~bGYpat5yUP86#iPa6=ih`pT4KS{i*_hc{ef7ps(;hR zp*E_AJB|fAMf|jlK9O^CkOk}3AGpUt%qt;dSg^GbuSkzp*oOU^kXI{g$DSVhg+I?* zq#e6Uw_^wBnQbFqXg|%P^?Nld_TG(W#jaJq;G!pd-_eS_NbjpiA14GbquWLQA(pE-oAG>w6W-D_zBKq?SC@B7-`T}q zEu8%2tAmqnIm0sFcQ|JlT&fr5X4A?9U0Nfw`9P-~rNN6g zp(&+obb{BQA*o6VUZdA^FBIZrsf=XZGsx1aQwv#vO1^&Jjs8jRrtBFSsqE=KPjQUd zEXE{OaIf)r`W;sOwIK?(YeUn7aU_1F^|YbmATRL0~AWJvRX>+bM?PN?}kbU!zo`! z{>s@@+Dli*rru7aXik12(mgHM=dz79lAdLTXW(MP<31(`YUX!SrrPLCnF_kJc22&o ziN^^?JVKVc;1RfW!Q*3&c)T%Tc*MJQ^q^Sg2q+9oW{b=buwLc}C{)&+2SqG0Z#A^J zH1%X$Y|=wKD4iXrkK;kXKs}_5J}$SXRLriv2Zb!MNDoSiJf7ao#j}GHL4G-Fv&eL9 zPduLD@!YW1S2SMpu{q~i1u6rYUW?<6$$ibye-M#Rj6C-}ZKRH{p0xRCk(%1JzhF;CAInxij#j+`bV!Df*Zg%Rp21&T8#|P1Wp; zSzb0e({clyZfWs#P0MY;(Q&H7UsVNSkEKzh4MYmp}=!(N} zqUc0Yi=^hhaz*;akvK78!i~a>E6I(th;zDLWGqItwH~>EBOHm4p>60+6zSj>laBQ& zGjGI3Cs7keA3ZXC>*1sGyC3xW_moNniQy5walPn`rIJ`N!j0>O8_QzF2sf@9ZmftE zBiy)NxUrlSD@M3+eQ@Igb5rvVJu>y+{JoQRyTtH}WZh@y+@=i7P*%}Te{uEa&b<5c z{!8x;{`1wZUw+rC?OpYwi|oAV=W(Lt?ju}Kx(Rp&8`Z1Aa;Q_lEmZgB8Xd}FPr@0{J9y)%UXt&X)tIzYWDmBd)=xI3Kw?1(ER)Ay7#y`6k zYsC3D{>@3jF}<@{`sjsmA~?Qca9m&iEgHv8`3AWhr}-Z0KY9C|lc^MQ68e>)P+xDZ z54*)*mzuK3zdHEtVE?VZ==$;t?^eHb`5%9C`P%>GwZHXl!q%f-3uN?{e2Gmmdf(^1 z{!Z7IfAj7IAK!gn#~xw8dqU0Q8Tf4{o%}r2&;^?51Md+X z?u84VkN3IOkGCE_<7UTc5)%(`}(P`UZwfhxd49~=caclM~KPDDNzW^+w z=^3|Xzw#KLD5x1HX1`*iGy4_L!KUEC_m`yudcX1}-5>ZI$C~vk&(rTN{mPGt&ZS>@ zi#nNeMBA!gd7kdCKy+NVU3i~s{dlMPl?gsMy*acIKB}1gh`Ha`ucYaZxJU3z%YNk8 z=NfvBX);34{^&QhQEjnBBrk~ChGoCbuXMO3*D|z?cR{S>7n6>8$+Qh@bif&%Yc@EY z|DJSOKHs&9j>)_k+PbZ_r|t>6px0$^LT5L)chV^@XoQ7Vy0u0Pt%XWWdi8s~p6=lq zeEp}t*i!RwZ8khy$|hF!F-ff7oE-POg>RWs3;SHEw9#ovwUXLz)Y?&a1}-cGGIRh< z$q1Ndf}mE-+&E8;jV>FUk52=-H1AN&*9B5^>9asLfL;|65;XW=`*-Q1BkF0|FVcq# z-=B%7mx;i|%k@0L>jk34y)@HmF;C7%`JzX{WtmD&P`{^&X z0^h!M+^1Q`%KN3;#C1EFt>cC71{QJ^*0PEFdV71`G(G>7W+l(iGjjn3QA}<20I?qM z3f$oJF0TaY5LrWji4|B(C_H|$sz6jpp)_ajncN> zpS(l+F8xWGZo);I-9;zAK<7kXLI$0GU2Z4(sa6K)hHx)j^k?K_sP*Hm`xE^Nc+U7% zGOX(9+70Me$N5@ow>GO8=d|`e?pE^@Zq2uvsd3Ra(VUh_3#OMJ(N{U;+~u-)noR_y zbzfCcO%m#>e)@~Snx?Uh^bWsY^2gb(`Vnm9Ef!n3ZePP{Uf55c|4fgx-|Ua@TwD&& z#{LavJ>!|U0H-Kse*^0jeNn6a=9K^M`WJJs+27dc%>D*+yXvR&@r+%wzj=r5k8$3t zzj=ZF>(bx6Npvp#%|%D+`31VajbuH8XIl0rQPwl{AUD&0TUpPtE}mG=#3p{>K7{wV z){nQA&5gP~p9i(CyN6bH-%~2*<3zc4(t5u7^{>8r&X-_Ye)Q8{^nEVKIG&lNOFyvQVaWBsucuG3t)|uuw0CjBd}&z zzU*VU=~_QkdQXC7!7}iQqGMJaQQ!LUq++?Yo?aNsr8pTDapFYoSB)03F43BeaUxr5 zp0G#1MzY%Xg7uQD?)}`*yT9|LU%&gZFRS7CVo%uRERE9oR^|miHYCdP1^L6}AZ?hQ zuYVOpg^bpsLOS0UtoHaVz_Yh1`v>hHC0#(`;p+UQ^%@_%p=&`n?? zD69kEUFkZ2Yh1_==zq8d7rvJ1LGPmc?C6 z8+1~w*gRhQYBZ(}u*r`j0k5l~U%fq#7tYzzLTwo*a>5T3Y31=E{bD#yo(;{M8w8WL z_IQ~qR7A&#kS{AYyO*s7<@egu;P>(}6d~d*G>s3bQoG%=!8}}eCN7L$vw!&^u`>Fe zRvxZ-K2cCJ$C~|%jjl-lSOnf{fmBm7Y}+Sxc4g6E&GoX5iTx&#X{wwjPi0( zUoj$CP?80;KC+_9W+<|56%O+G&X|5 z5>mWeXv;>w@p|xb)z&qn7hd;r4Hx2gxz?FwOq!{08Ary1fM>ZJqz$o*xivgbEMwIc z=+ktxie+5q5m*kKK>_@<)NCCr<0(2%Ys+}J7|UCi&C*&jZm}Rcl@JSg>+~4Zf!ZkA z0L6iX^Cb}bp=@Rneab3s8utMU<1S?t@7*X_6LqUejabnmHhA5B;Aj=k;?G)9ug3FC ztJp?Yr2q1Na2n9LSjEWd0B^Ulik~GKT!RZ=%e0Em6M>6W{9{L}_}MkIis4yRrE^v> zc&26F5p5Mu;a+yoC)z3=F30hp$$Xm%FRbh9yp48d{x)p_8y&Dl=c>UIbUH1c&&10N z(dqpN)1lU7aY8dECfw!*i4$!d6~S2f>hHZXc!#%R>mA5P{@A3-KTc16Y|`7&e+TyN z`^^+rSbZmd)J!d$ zR`Z+S9v~qCr} z)o1ir$oQ&!9ob)%ud8_y&|h7s;+*Fq=1b7~t^0^(BlTO*&hSiJ;JHIF`>i_(kZC&J zs^5AFf7S})(CoKtbY{N=I+uRy7~S6>(YEThUL+cqe(NI9x%6AVcI>wh8NOEi);@X` zRo1TG0*|e5zva*8@&URI`mHo->bKx+K);no-Mrs&obP4r`YoD;p$dHq-&(&l8f39G z%=5CHo|y~UU;3?jOzcOfJq~DT$YlZtQKenfhe#>o6m|W30yX`h5v_tw9 z+lJR@wqg1&ICrh`b!8=9oF^{nfz@)?Y#Az%y}y zeS>1^Srd+W))VUQwQu#x8a@NzeK?>gIZu%t=FSBy-YGBT(Uf zLG9JQ_2aGmH`F<31v6;qr7^3nHU%4bD_n9sSI%4U)Yo+XDkP`rtx$dn<+D&)|Li$< zSMh}BE`PSEmsPZW#bJ=Pee@Bn-_6S^-ippj(FiZAKfg{JTEFA`J1ga_Xx(oqKZWvH z1m22s%FF7{N-O;q^+%@mFJ4w^6e^JZx=a@@tKTgC7rflI(ILqDPHO)V{np$Ru0fw= zdRg7(;#mQ2#WR7XwWa2x=(qSN>Rt_!mZS9f2K8H`WZYOsvte~@B=0ILcRUjp@m8po z5N`!M=8d!2?qEit8vRqw*thjptKqFce}#KOfAwM1iI(V7dJ`_ z7@moXO={joKctDMRV>8T0h>}hsb@G`nPQkfeAi2 zwJh2QA61YIT`w*8!RWur6uEzs@K&S&el9&_xsRw4!rz(l`A%B3}S_1A0IZ|$qKUt_<8Oj7W) zD*U$8-b(gkxaNxYV-ywUdn@S0pug3%e(+g8rH*Z*x{H{4J8F_a)Q{!kWw5TRery!I z7}ougevDoy73s&^^e=c>r62QI#@BsXc`;ZYTa|u{qQsWbj}>BNy~bFrp;`V=V~iMb zTscNe*^e0M-rV4S^)h}Ak%|#(8XtCmUeiYNxZ;_(u#RK)T~$XN>=d6Us9CC;I+%?P zvXTFTQ-IDz2RlUfH%PRtY{wUf2G`)i*D`I#H;KT-c8rrhbcioXHD6adC=#a6FIeda?j!t9aH66dNWMfO_ku6ctZ~Y8RkL$A(w{s$K963AU~* z0E!q}h6ON^Y>%w($&h|5U`y%8+^hlV#{z~~kNp@$kj3xEMso2yvh9t4M`gP`8pMw& z|HVv1q&~*Km8Zj_*}MWz#%QyVBzTZEnim7l#D$yzelh#4+vtZh{nBbAX~F+@{fo7J z(~DuFGrbs~bMaz8KZN{m<;D04(YSaqE)boI7b6KH;OoJQ0UldtEu=mKQfRQjFtMtCWK&c^p*eYi*In2togKhrn=6{5R~ zK3td%weD4Tl6FqhG29D2xGqaqZWB7>Vb$cdT3sFYqYAg4+Vi6^`6sHo$uoN$)p*98 z^s!1Itfv0ZBU2B~pZLt&@#Dvj674qnboJ_S1|#J-UdB%1b0GqsI41ZE$3oF76MUi( zsBB<-&RFnSiQ_%1@F0ML{Cr3tS)}z`bK=Jqs`>!5Iu9!F^Xs4 z!dS`B0q{9v^nNA?YQ}(xQ5&6!QP8EebMkdfjNa#n(Z}dqE*O1*=v*-Rlp{v73BxGf zwIfESEf~#-H$-AO*2x-Uly09~3dN;O~ClosL*fyD0iSH7(`mzf>Ht*0oOc|*XjPSRq=;teTh zORMP((ebIgAv!*BMDU5XZo{46Gg;os82F6#hLp3ztLY5^K6P)1j?Pxt#CToOWoH`T z3kvtbrtF0GLNBRc$Hb?OKT_O>zcAtydj;Ho#0nT*=h5JjI5?N1lVM6h!=Q6 zbbP8~&E+RXdXkP&@rEeR4>>?;WutmSz^{%NwRl5vS@DL5H)OqdLvs0e-jHCb4hR4F z`>HPp`OnSBkZ@E;b4elETzExw(dKHxCbYrYFAgpzCk*po)XVZcAARnZ2 zCEdEZvECWiy!fUEIKDfWZV4KI^Y1iACu(4+FtCMv#ciiFu$yH)`K-!Ges_U~V7Nm|$ z?2A4N9<=GHCN^z!CN@Er#)*Ss!=`vA*T_3LciiUr7!l8hcs|yP=Odqs<@u<%XT=OE z@os2v$1i!^*)!xX-}%?qpWc3MG5g}|-mdMVZ>PGi8z;H3)7$y?KW~&6y7mJNdtz(f zsjkOUll|X*X{$H7CGpzbTKUc)Rk+wB$c&?Q_avRjMY}skbS~Q6X-Dm@nlSCo*>^r| z^N8dNu{njyN|@Q0u<9cn$A?@c;zh>rErXES{u zod)TH@h7@&t*jev%*XK)2sa8hG7B#!Vu=5XI%3_va-kT<0v2u*Ze)&H5pFEUvG;@< zg&S9t8;8Y;5i4fh=#3+BteAFZV$*Vu2hU+9wyx{m`?vdRF+~2c0Ro@Ql*m1hs@Y00 zts|RH8~!c+56%F(G&X|5zBX7upV!QkB_h6x2FQ{RL_=mPT*}-4VVQY=m5HEcPl@RP0bN?7wOLm(H$Z2t zEBCnprYs(iQZbeXq*HSPWc|4TG-S%$0OFl&z6M&-)^Uj;GcBHvQb{}?;`vxFo{!RS zEYC;9-MSi3YDGlOV)hJjqP}^}*wSbh&kr!}shI(O*)$hwCut)aEf)&U#Dz7i3>`r8 zvGlOTdzcoNjn35UK!;;o_`2rU)->I~AQAP^2Q>I#+gw5O2|8A!4;S_7JMyTbZ5OK&STNjHg8F}5X)OKQckOKsQ={ccTT2K%sJ56hJ3w^*F&T<4uu_!*H*z_n6c%)Fi3dtJ~<%TT=%(i~pj4PN!ulVR|KIi0(H0At+3T zI>~bblq+$31;UNOjf{Ym$i^Pd#<7Hj8-*KJlpFJLY(C*e;l>r^#)4QeV#TZ%D`vP9 z$BL;G-2GucRv-%d!_v+37vV=udTtb+feUYE=m0DX_Gwj^AgI|2F|8jPo$1p8U0ORQ zU)S_$6&-zA7&CUUrk*4^7oXNKN1xUJ-5=V33%3jJbFCj=j{bTzpUAJ5zZxFe*~zDM z;h-+ssHsi%l!u2IQSdY8in-wur8Evx=tVA@r4ZWMcezN%1b_Yut9^Zl zw!jORy$=OE%e;?$-ph{xE18fxmb$79#%ut6CBKiTrbwe+XZ1#9t-H zQHDD!OXEaAVcBcy zpcO|Q^nN-I1stZGB;@;9*G%?N1_sMjTIwkRyh=8hk5sOI1 zXx+wWr=w#ehO-rkkr4SO9ziu@uj*M@Yf*ch@d!@aJQ5=kBOx9Mcu-6XO4deQ&uNB1 z_pFU+i$@}tlNgC;?|S_W)aUdvZ8`Bs)LW^$mb0RcEyp8~E5wPB5dWC?$C&?CAYx}Y zSBeucAlxY2xT4%REORr8q+Ta8J`Lwa;*2Is-za_KO7@NUSZihoHwrhdC^r^jjjOhq z`*ZG>y)++Q^L3_WHj?mqwlW(D^MANT{S<6+gzK_Wt50UCUw##s;1aeWMn@6Vha?`fiQ znH_JQKzW*IuL?f6F75;SdOYej+Cdv|;p_4~*ZT3bl!f3|w^*Z@smR&!h6`C4XBF@5 zdhy;C@^QvlJ767E#Y3U`G@I39N(397DG@-IR;TvAZ4yD|ON9jL_Ez6InzMK)3dK01 z%WX%056GGs07yl{3N~58F!5)jGw}zyG)@#08~$X?jLzZ@?d+zJ%}qsnCko{_6d5{%Z?u@V=+Xr32}mFSxkj|6)KZKGYLC1s;Cz49_DrWg+2 z>oaC>+UAiMkvIwQNUWDQ30gxP&gr1ET3222io#<(HouqItJ~W9AReV$tNzFVLu2))8mvgH*u6iyder3F08CSKB>wHuLfX@Be;aW5Wjx9%H=v1V) zbEMnxqsNcay>6pVSFh)7M@`1ap5bzVJ;g3|Tf32_=eh-d)bxTsY6IK2&IZNbj0Jzi zI6mdJ@z*Q(6Z|zFSKXlao3r3A-pZRrw&YuntG)?FGsacF)$8pToVsB=Ab7Dht4_Z$B#~1a2PA&LVRT6BV(8^$Nu8~qK+Cr zpvCZF_{iGU%ET+-zYy_CTzOW}6utRIuf%X(yb`kdk-759eZ(uepPseAYyDo_??U{q zC+XW|MxbMkGXf#nJ4xDD46opv1%HKDUWu9yqqSA^mU>O0Xw$L9*RFq~_k8d8(mf;z zn_EU(>HkTeoeQ2XE_hcc8Tx>qIqGx*2erbyZpJ6s=uFE9bZPB;d|lHrs?rVM{#wn> zHBB@wSbT=)T(J14BNn$O42$4br@0`=GMXaV2w5mAeNekd9;_FdABg({YMM~dkFSVj z6f2gc-I)>gU-Z0I5@9nvf6^radRs2sGiT@k-X==~TYiBl5o~m(M36iLZt-=Rhj9Gp z2@KjsNQ77sJc7acd*-buX(AX@{SC(`qphy^xr+&d7`Sc3U}aU~mONTTV}RbrWhyDJ z>#?l^SJR|H^#YlZbQ#EU4^PG0rVJDhq1{6WJ%Ed@1@bY}`tjvxhieeGbOHmn5%?>_ znh&DQ`TM=JS(dMY8GwbvyY85%`2vS?|rVP^<}MKl#D4Jxt5jM~LtkKj-6XO~JF z8GjhG-9|4zoXIhgjWZuarOimz?n#Mcg~r5IQ59g+3VuT|wYjQ)wEo3(rgt86={i}> zBVvx%%4$k@2c26xBSs|a2@Kdq;4mL&?F_Ms#42K#FUKRt|3w`Y$vRSuGZRL;V@1_P zWY{*3;F0m#aBhQci{mZYB*I1-ul*<6~(V21(bZPo< z;dqTCdMA>ELuc>Aj3v*ul9gFwiD{$a|CpCivnG?FZD57HeERq*=xjK$(aD%?Xx7+D zwy>Js39^jDI{~((VzYQmiD08MC4yK+s$KEDUM-_3y0->@btPMh<(+8PGLjjw&YaTm+Oo*gMlS?*-(oR{EMW+)dnTUO5k9s&iw&D!L>P?Bv909d#V)n!nUEY?r5uQ7!tR-X z9>9ft|Gdw&etbFFVW;AjVvN~F=h#+qWuEQWX>EWuJrkbf*w)6GL=TO|;6|2#kvX=N zTqTZoUOW@xnP54z9NEMFMIGgt$gk?W$dY5L-iK&p(b8bU=J>%PqQRoZvD$n-)>u)y z7LnxG`T!LCU3vJ6%(1QHYc`IXMa1?~YtQ_fs;duq<|W5Atj$$b8`Zwq(l)*GHaatA z33O@ta7l6$Ymz(@F``(bb8IX5l8o0%6ze*fd8m>fjy3a1O@_3V3Kvw@6p{*(V=H4t zE@MSWis0EyeC`y%GiS-Mt>i~mbG%k^Yz2c?Fb1P@Y%7Hv+dEFyQJdZg$+1<+fp{nE z-iaj1KD5Q!NO6Sv=F9{WN4DHq)5~Y0lN{S{j%}g5n%)V?v8_u4iQboEIOWf+Br>iD-YpDwu~$|%*XLiNHlBM!(g*`#4>`; zts@Zo?3V!|u}^-Rhr*Uou{ILxEzh`QDNH~6Mvwa|PovX*Ultf^{vI#R*D83k*j+sLzkB}ooCdncxCdA4Pl z8<}`N%FCxigyW(!bP!l!&$2|5*IUVD#m+i4+ORR2d^o$B-U-RGt#h(?C!#g84eXt; zGK$9EMz)Nm=*@4VPgk$!ZAVRN#-7S>A(m&N$TL&?|LuJZ zd{ot$_qj8ZWJp4iYOK+M&JbDy0i1k5LhG*i;zAV*e$>US-6SLfNeN`kM~k+*M8%J` zw8f9MD7H&Kwu?$@K-jl*1w)B0w2ElhXX=BN*mU;jGd+(W?xy*HD z1PY<|{C;Pi^PKbC^Z7jIoacN^a?R+l!D%8+GkPwo_Q-N?YIkk(@cm@JYs<3%((tSR zjeSH6 zSDksv{JjVMa%M`xEwIgaM%JRLgv!UgU-1a9AW*7S|l>Fgo6eWTkqp4Pr`p*%(Fj?_Z%HEbI7j45%cg9PE$ zV5QD)r(+n6{k*Ib9nZlcuGslj(y6pEKKuFBHqfa%Vv>$f<`quyTX-}9;+VBjHm7xq zv!ria7;@iHMN1`G4S;vd$QBO5hb``MBUj{3`QFaLP=&mE?e>js-zde85|_xR{-=c- z=et^r+c%yyBXyOl#kkyf)^KCBtHrq7c(!n3Sz3Fd?h22q#mM>O>6kZ`xjTcXURS3U zVya{_Kvi2&yyN^&3pctugDy9Uvu31Tkj_5^xFfYYQp>*bwDgVD?h21PQlBk-V|iLH z(z$)3+c%!hzOlUAU2k;z#&f##OX;Z?x#nj-o#sRr!ng7pMnk#)9hQ;l&H=8z=C~9Y;O)3%uQ_&r zCY94}+d!AfYmR+57)9D-?*;{szgeJ@MlGZCBUJt0jlQq0w=y=?39V^l?U|VICb$d& z^y0kU`GCv=+xi_}bL?*JS=H6t($l-H`xf)BmrlGPw6Hv_lb+QJayf?l!NkdB zpCOlv{}7EpF1>xb;OgE|S29qfzq4#kLqwBZHdzK~WGe^Z!M2pLxm*%hQ1Y5xHl64~ zR(vuV(gh>}DATpe=JFI}GlDo$kG1DB+r2KL$RE?BhyIhhkpb$FAr8{P_Z}i6PQU2-1OuqJ& z;8yLzirBw^rg8$fI(7;v`Iwn&GECf}UsE4T`8rranO%_1 zKk2yp7V)yA@+s?A@~VAa>O@Bw0o!r@4|q|cB82x ztv%gSpmk+?1}&{ibG5D@IEEY~M~dZSA;m~8vvao-oqePrT|kM?X{2zqu2Va^OH=D= zW)l^{#{J*S!pcxOr+=zXR_n@*Xx!34YDubbl1nE#yIhhkphV~-m#)@zYUMJ$ zl}f%SmQXIs<=SH^TGzsm-2F$AzEpi{kU^Gh$j-=&8u!qgnMw zZqO*Jhq5MguTewy`p@B91q@ktT{{K;rz%P~A=pg7) z(Zu>w)WkUcPo^CQwsjhsSTo2IjjxsNn`G|3^x3j6UAZ8=mnu^qRenqMx9xw4P|<)E zsHsb~M#ulLp6qLMxkmBLAK63OM}``OhEAuE!HLd3GLS9+D~(LoJ~Gs#I5IRLqEtqP z2SJz0$dJxUm9u3b0A;->UWQZkKa+dWN&j~}ZZEp`7B12y(7a+R<*Cf@s?+$VPgfQv zI7iAv5MJaTIZLaVATeB$x9qDRPIRs;PE_C|l0{?l`9xWqUnWmrxw2S$-8J)?dwROs zSN8UVyC+&Xxhv8AQg>W5`yF-t-W?ZtM$7nnsRZNV{EBpLfK|s{1WLa0aoA+xxRnn% zM{Pc;Y02iP?muA1pZ{pEbqR6|wU3RY3n;X5Ot#Nc8&aI7wj!=n=BZmim&!afoqxcd zO!L&F|9~AoPc=4^6O4`X(^-jh_mbo1nJS-B1f-1E=b27)lo5zUgx}JTPNkLc{kiNV z&#y{r1>+<~hrV6j?A!t2;W;FCbTAlDIQ9B=j&`DRM+dVW`Fkccr!+?g{`FL%*;;xh z>Q8bN!kmAOZQ=?9G>4m4whN8>g&9?g=3XN*r)FI<#gm_cV)nE4#bJysmJ^yw>o_ z-qnq`Ftj!-=AGIV50*K+#`0Pv&${%)LEfScMkm3J>rfO zHLOjx_+{#kX!z3Re~{eL1j8C9d*sf_g(b-1{(ghfiWn{W@fUBc~dm_-3 zl&P|!4EXNvE|XtV9VOZv?=CN>PUj@i$)2L;{m8^Om)}`7FGg7>yKJhb7^RHZWpjBP zZ#c`Q6P;Z)Nf%J!l+ChYGsrBn!0Q{-CeFq>$U5XK1J`|U5?%Dx67r|Sm=(K zlk4;?=SQi_rPJNzs`9kn;fbBdO1>hJ=iWRcQqtlXH?~lBH$!TPIQzJ z=${cOKBQA=WqkIPK+4<|@*_Y=N2s2CnrwHMs}`j5%H>IGU5+=GU9F4EMJ-7+lFRHP zg%h29q##{DiO^}JaJ8;eJ5r>nbv3hz3Sr~-yQ&tZcWPHsC!gKDV)8`Xe%F5QiThc( zCY|w1-kIzxACmuBAn6XmO*xaRlGO}U48v&bGU!BSmqF467=dMEy7t*xH8M~D8b2&) zXz8}!Z(IStR7R{#pi5=%sw2g{t6b!7GTm=v{iUH{HG@2X3|5z=^U_Rp?4NIv%itj< zXuDB%$F9MwYyIymhvbRLE{80GG*TXd@Sv~cuD03)!BOxG@l zd{HSCIlLM1q#}o#L6?dgMpBf+f=MQaZ0pqJ(AYvwB!_98ns>FPcv({UleYR}}AFNAd1;DyMbbJ>>Yi97_$po%oR) zYab;@7nmT6%@XaS#AMh*o=hi=(%VCJx^rAzmDV0|Y$Y!FZ0)xuPsC|V@@`eKlk>b! zJ=te$xd~(<2tUe^oUzp?G;~TCv(MO^=p{?^GGlY^ zIj-w&YwvZqb6mYJt-UE%7A2d1O; z=dsa=&OSDhE}+EeG&Z_-j@bsM?j}n*x5_X!I@~#4SeeeMqPva1;Tjd8QK` zbvbu6W8y^o!nFP&`($5gQg0knt8ni)l7}aZ6F1jPkQgpWXCE0z7ceNyAE%MQ)tXN2 z$Ut6BW2WYC-*{nqr{H7%U6OnS;}w$~;#V+y@4VMU-kIzx7n1*3eCZCtP5F^47fyS* z_LU1KI=c*>OMAYPX%&&}n}!S~zGqw(3Wb!Vi?YhHs`-`k%c}5941<*41>EjE>G4n( zGgA4dA9ocoenr0qZLJ!2JTz-V)&sFK`Thp^H4Rxze0LZESFRjTOeTx2rW8M}IcY%l zam|U&)s*7y4uc!#D~fwEZmga!-*QSmJA1pRJKDpu{QDCHJfMhL@zc&(wzRREd)Lv!9N51aztFGkqq-lR?vv zzsYn$k8Pdm2+{3yZx}LJr93Z@R3=aMK0p59N8TGw_5Y5GP|nFNmn?%cQa*z4Aa6@8 zYN;f!pyYeITsqO&<&ty(B~F>HT`niXS&Ydfmu&0Q<R;E07n^Z1O@)b1?-cS1&|L@pye%${ZKg0h!u6?L(*@*f2 zsDEH{-4z2KJx4d!LUPduIqeKoBW$vdr!0dsa$K{IryY{Of==V96PHry ze(F58BgJ{{CVZF5Ja<3nQkmzb^NQMJ8c*5QsgI`)_l6<270ThpWOD1Sgv8HHRX#;? z81q&_`xxj%M;U=wMEDI2=~P-Nn|2+Kx*%_!NF(V8C-J>uaARz71J~G-apOt92!oXn z`H#o0))mj$OC@VrP;!`^vz_SdqXg*!N}NukgsXL(+Wq77W_QN+@rn1OAeU9?>|LFL z)ey|%Y9fpGyZ?6#nW5~tt0CrWlKn;jEN7OoPT&*)Ad_kKmY!T1TgnOLQhi81>3DgP zr{U}UPiMJ%$`gE7L&j5#(->K!(9kLA>|-S90R_WPr;5c8L`hdo#>~u}0!o}RU2;EXMAA%#J>|)C0+4N;`dXXAJz|Uy3;u+A%HG_}A^hvlAEMn` z>PiNRba})7o#c|U(#bBDEQ2&sKJ0S2R1#RwNiLn}>~cxEfD)%ncMkkixtt8E8*wFga>6#&RH8Ifd!r9(TUD3kE9DIamsY< zW21Ygm~C)o?i6=B-6@7VmRIvdY11T=M|V{tUY49zEA0B86CGs)av720LpqgK%I2TV z{&2;7`5Y}6G8s3X?EbJf4;qxm)u70IL0EE|93`mns77+4owJ?j?4tzf0!oBVqlBwL zo!U_%T@9)kZBz&w_og&PiL_43pQHxm{-1HYEY>J;L#LB0I?>r>k#qrAX`E!S2Ax3x zh`9Ge8d|!~rhTZ%q(SAP?$TIgbh>9;vG7m0n&EZt8OM!_HE2WCxUy*0Mj`r&$s~(u zu4XvhGp;O?mo-zEue#b({J5rSI^-fJS#qMAgKu2zDfS{$S*Wri4PCxEHl<6xC;YZ4 z+1DI)fG(9&M4M8)cRUCA zn@p#O*w(4e-ddgS9aqjz<7JBKYPlSeTtxKPg)$=C%ddtKBSQ{6NCq=P0DJMB(R{A1^cRp6P;aFNf&^XMy6|*)ut3> zwGR=cBCESWmx`=Dn4+v!PBK{~zoss$j(3qOW8#;>?Czvx)o;qGc{2XFEXb-CvYPc! z9erF`b!AnEZQyH;@wDtqxH?0(?7!d?=eDdm-cOz%O6QH8ll)KPt8q6ubPDe#vrnJw z^l+k0kPr#`+q-c6ogp2m4e zcl9KGuByr#MZigxoaiVc7&jvPmWFgHt&GpE2U6zF$-Bw(E7N&-CN?#EmztTidSYp2 z#_9=Xdz!16krz)~MQJj8Cw?S%x|-SKT181yGizpx7sA^1qvtP3XAkUTWz||mu{1Mf z6~)!e*gip6%A?dmn&4KAE30O0oa36AqpYfr({h`ndJ;k@zfqEXz_TsqrL0Rz76;n zWn)h}mH$!x09t*rj~XRpUCYRIwIFbEvz+POED0>=#OY3S_Vql{1(Y~ty7u+Fn~?#o zefwcaLrb^)Wa4Mwr%IX3pM6cEA9Shgmu*gQzbu6OQPYt|rYms?RsSS5*nfp6mcNueIlLr=-q3r;+TQiS%FhGp0D{2M)YX;(jcAaBx-u^iW=k@6FS2W2jq zJlbcIO)?@2zLVT0O4mNdcBCk`n~+{Aa=RaNsmN_Q@A;m?a%*gK7oyH=E1wI}dLREJ z-~CyBMDrF7XaNzZsY~U5na@LhC;PmYbuNvQOfHcG7L>APmq{l&`&df4fD)%n*DjOp zyFcs~Pu)H?`8ADsZ{q)DE(=waxo>QXMDGzOEFF8dItWk7iyYt7v4iwZvgAZZ89`hT zeoI3-l~%@Q*ZJB&cLhJNjHDx+)NgE8Riv|8a*}&v=4uJFFk`g@TA0Vx!pKmv2M@wc zj*{Ho1h;A=*V#voCY1gK!8zA9|iM1al?*X_gCa$cea>Dpr*1Ve0w-v(LG_R`av{p<~--ReNJNLL< zh|um_UA+H>BN^T-?q!$5R`6|Zu9VEyy>Jy6?p)+keT6juT$&O%YR%P>rP;=ENzS4J z&rbeT6P8OFIo<`~!D^J_tkaHzeVlcovyZc+Q^!S_u6>-1q&UuQw#8?%fDras>H*ND zGR}TG#hnSh!Zn#>mu;PnhSm)F1hQKlO5<#&yPq8|ODf-^dSi1@yDT};xf+^nKfAiz zT`zFg3(#Xvr8rqejsOyuQ1yQ|d&DvxLNE2wRd#Nylv9-yZaKPrquV!1jygTuxFC(y zE0-HxZalr*7(0&a_KhObs%rZ@Pp*~+5zf&{>R@&{Ig+{aM%Iz6HM3H=tEHNRBlW^i z8t1FrzR~4I$x)|eq+VDdAE$BqMz?RYSWWivlJg`~{Z9`!&QD`?*6kbJzEN`K>EXuM z<9cr2==P0gyl+hB%%Iyhx_#s6>>KfC<7wR8ce&B!#?#A<74GV{yBBko?8TIY=BM$3 zv)ebiedFov8)JuqT`k7dV$QG@Q-=R>1shr>**h|B-{|&@r?qb^D|fXRciwom%p1$x zGd#lO#tB-oU2VNJ&`woxX zE(T2c%?AB+gI>Iq@#eO-{Kfvaw2$t(xYR~(zkM`KPPqZ+!Pey!ZOptY<8I$Q-g`Y? z)PxM@?V3d4r~2)Pu5ib^p78n}F|W0`r&-Kf+1)MX(X%zYvUhdks;=g>VKJ}vx@+b& z_w;nNuk7s!cPm9m>bw*btakNeT$A#Zyd}iD@w`8ZG5}@%YT-tj5dg#d7QgB#Kbe;O z7E=)duC=})kaUC)%$S*p$OnOC!!kcix4?4CvH}%jKoZ@GVwh@VI`m7v&#$Jya{A)x zgt;caGe4$b%}f}tu;W=GAHmE6d7ZbIW=@bB@yrEYri9nq!iCvkw1}BKVrHvoY+Svr zx3QzO{gZ1uTN~TL9g%PsJb|~iS6HFFCj|Fe;fOmAHXD`umxL%xA)tE8k!?x5nh*_h zd0AO`SsJS@_zOa7=9j#`3Yd)(>#wo}5^jqu_BTZq<6mdnZi2g@=~`eXz6r&4kcK=W zak^EUGD0iE*>;rGQ{B&;&ORp5yBg}7SS&A15SCRcxp*l(6=PPn5cbozPIMuBE5Bhh zq+3phWn{W@fUAASL1dr?eyn%d9(3E^W_$#Gsq`I#pi3m{%$wSG^aCL+^YTu8M<4R{ zSD=wbEu-`!RQ;3p9coV423~Q#8X01HFYtnxpR7I8!#M353*+~h;v(S811Z^elmN=U zm^fvW$K4T`*W1qqNvCpvgAq`ge5-Ys9wY7Uy#l$2i`AV*wz9;WfzKt|s zVttAqHFnx%{asEU63Mlhee+jxR1hfnK+3f$Go)k~ja{yt=qRs6!M}w^6ChZ^;6?H;`JTKg%K)cnz(*YCrIGPTTte0V-N>PghtQBS zive2%#zmJCQ7bMdo*_=O7_dczZ|PoDKG7uxlJ<$!@*;@aCsMA}{)@QmGbUr7$bM29 zSq_OysQRChKG9^r7LmO=>~bP&+3gd}5jzpbNk76<&WR=if)hJjPBbdo<-{|@i6#Sr z6W8{3xbsBtqRWYAXr5>>V2fB6UL7|)C!Ht8w!YkXB0JM_X`XmSbZ3hJTSRy7O1DpR z`@}Q1ieoWg3zj)MyRf1dQ=gOfiE=~3?Gw+nJ~5XCvW%*kNIyc=|CH#?F$Qem(^}oD zx+iw{lk=jywC?gE+vZ#vpL19s%cwjj{Rmb6Q^Jdq0im_5>ga6l>2B{{WvweF=SBHM zrpt?Ln{$a5&&)f6F$R>}*t;&qkIA`FK9T8iA&^o-<2ivhup z*aU2KccI-ioin)$O$Ib}p^o^D<2_Wq6(fx-hr}gR{ZGj$9fbi~ zjMrx>;}KViqCxQUqV0N%qnVd!f_*n#3u5ohs4pAzx#VM!JLWU`t9} zoG**0Mz*q@i=F5~_*j0!ct{tZ!!j~m`^z!>Z+gBI!52+PLrb^)<(L)lQzcENWq+|^ z6X;TTIi>>*yA8D5-=Sr?iC(P8MgHa^Od6T4#3fYy-;Goh$%qW78GCQck7;D>nOLHi zV=h4u^FV$zUV;g)YhKwAo*P~tZovy@bGv(*Th=Jg!I;5~R&b*c%-9PV2cGd@e)zJ> zsz})a<&lD<=R?XC$hV`Cj}E(;S>@#xzFrsE?akf)`+vF7J0|L*^S-ug|L@=H{ma1{ z|5=n?F<3t)yqzO|=jj~T&~W|{pU555DqH>A>ih%VBMrXdh9^h+Hq0FOnEyMYf9I)v zGJkgUE9Z?CgBxh`#tyX@*KUse9;k)cgwEGQ<25r8QtJvC}Z~j`+1`m zM0=hazGZKTPU?c$zkIdx$cq)7N1mxLzbD<^;YCNTuc#k; zyM{E2#>VSq*i`Ma7yqP2%s4PC2KN7c;|zf^T{^p9_x|5c5zCHv8}bKd@9p2&|37`d zyWoSHYp$!S@kYwU(WkGkN7+6;?zw&~x+bRJQl3V3^*c=-kvf-5$eyaP}Gw}*wHOeB5 zlvwu1>K^hdc+N@oGbAS+`@8qU5|{n4^|B*;Oe3SVzXIq)$G%d2!x%`npAO5&{Dpw4 z`FjKTYqI>{jODKuZsaWjV3;|O-BkMHCeU3gKLV6_A~eO{4D3LLM&RV$5-sy5>q*uL zyu{7O)Zfuz85y6%B~<;B_s41qET_+C6B!qC%{4W~Nm=s1#r~H0GYxBM!X$bXFo@un zV3)(Pe`ejyLWC?Q@p{0y3Vt2%G6m;LO!F1o?3j(`z04N^SCzLlwy*06ci{!FiFX6r z%2!SJDum&1*m^tApqM}zO>>74O;7tLRU*|FuNxvStI$vjENF}yU}QON+>HEsfHx7M zp*LFiy%zqUg>SL&Z(I0w3*T+w-?#AIb)RZq*E+YkYpppNCDT%><}bAV<0<(#G-6JB zWAnm1w6?eHuf@`V`VmoI3|rK|c_Lm)U3O>xLr-3P$%T4`u060t7azzx>i7AMzR=TJ zuY=E%^>+PRb=jkSQPPk%7(MoH(Y=erXf)(|X?I=jpl>u<{hQ(M z*Li=wYTB#Adl!uzT%mjW@gD1!mW>F+V7foAOP3hXO0ot$u)eEBN$x%g#m^OJ_xgFnDQcXSlo6~ z)|3}7&dPi7<;?S6EZ8Ug-h9C~Iw(x+;;fMud~a@#nAppiM}ZxV>^odg1D^qJTh30l zQjs26JOy>b_KF~#sk;AAX-7-57AS5H>a+DNi~S}3p@2TCBYLbonyHJD|3d2=k7kv; zH54*@|4+1JI(>}xUYt8UQ@>EpfBw5~cKxmQyZO)NKX2Lx59bTd4zyO@FUNEHemP#W z`7Zc`^kBz_bs;d4`S}xGej!zuoz*HH$|Iv@aYk@MwXS)^fc<-@kbMKbPoJ z5i45#p5l(~=Agc8Y^3Y9?M%C(y-dIDv1;V@-mQ1&{BEJ%(y9f_FE{TE=(jyeYSR8- z)SsV;ya!Pt5uI{bhW?}BAB<+@`v#{3Wc(#YXm8YO#9q@8Sv<1mCu?$A^QPzPK0W_u z|J|>#Y(F#YS5T5=Bhdvck@!mHA=ca{jGD{PS$72wMUVaDxG4D@Qn-=cu z++zq^2zNc|F0}jAH9u^+qxm9zdaIZbdTIscK#@H^YO8P0X=ST?V5c@Cdh8=nmcWbn zJpr~&7C78r;${0Fo=c5TvsEs%TIK1si+BF(nry^*`7mZb18nCz+s@yq=~|$Ot-i-M zE9>B|4{IadDVbBIh@8Fovol`u1TbrQOEZ4O(K|dv`t@zv!{;~AR}6?fclBrM-pBEr z<^wrM7dhIJ(J#Z2#iu>Q7^k#d+f>B48R9G0v$5azc&=VQ?wiXvXXs|EzW#!JBYS?a z=KR(Rrf2DSdj3zp`)2;%UbrLwK>kln`(?A{=Whgj@0SY>y%+6uFj}U+cl-Ajx9jhH zZ2ex}R)1j2;*1iXo;^4Pwe^9ASo^-?pU`uIqU5!~DKq)a(&GW}R{r0P>|>ubRe!GI z^ZmKgr?h3=w^{c;C{Q<-=%TcBXo|;MoORz9#^2xch4Go8(zSa>J^B8D9c#`X(Y*CT zV#F_=-sQbtd*HG*ars{idgd)2yzJiHU{u6}O>Jt@GT!cU0tmdZ>D* z_hB(xjNIAhG2nOlMColWd$xK5o&%ByfqsPtz*VTdRa*V!G1fCy$ zVcfUPU-`d=J*9vDN>1*tcTMqmW}rMF-_d(~EZNM!1H(+mGbl=GM!wtUtK4GX9~kQ2 z`QYJP@o)JLPy6Ly#^?%#Y#}De7p80r*!43R!PoKZ?)5A4-meHe% zlBb5Wt)ld%A-|QE8hvW;@=rvMy>$GZy4Qyu|HLD8uYrrB$6kIrKj_hG;2Jw#gZ@VZ zqsRX1cvj$Rh|Bz9KfYKrSd4ym5&#p9V< zOIGe!xn^Z%plLWi$oy1*6u13z-K8&UXp4}M_vo>f<0UIIx2{3FnSuGkEN$!CzRFB}M~ketE5~L%QKOe5 z_UN%5#64r!uWM+VKJ@7yiPg+%q`we#6Fs&PGzG(1$TM?Taolrx$;zJ&mFk%f*N@M+ ze9g+|%(0~Sf!DO+`(E=Df9bW6JsJA5{k~bbhRomS%?afRt#sLu^BTUgD?FG{Dn>T; zc>;^jONr9|87i1Pez3Idl}s^uv~R}uLb`T8rG5Jv?P2iPOyB=_N8eND9n{+N@!|qs zNUQLbjty;Z2_Y{S4+1X_drJ=v73O|**M}}DDE$Rux&&j`Yeq~Pj8Q7{=mF2CFWIr? zuXg%A7}T#F_vO@$`|`C9t(Z1GM2-xhZp^s$42#lTLp#=dbyvxB?E{%ed0`zm-s>3* zwrNei%7RjXk@le(qif0m ze={g9YuLW*NL{WtdO+lkM$0!1OF8|qJ!JHX-!=u#$ z1v9jxPkX-k=7BCvUoU(g)X=6V?;4c1^Y*&`9@;xxaCzNJv)cx<{&BP*>pgnGi@_1i zlTkXmNqe9~|JYz~#H-beFL|GtdvWS|ScuSiyFf%aQR(m*mnDsT?NWVm{8}WFMZmITw zxXeuZxnW;udy83HYw*3__}-jnyk}S|y>e_RYHZ7ZxNP@JtA^$GGT)CG`TmC&OY|8d zKEynTn9Z<(YsHblQkpBMdef@y+f69XUEqDO1zyGm5 zALi2EyJc73D}bas1o-%s)qOQkVTj)VNV+W+zTJX5Ecks3zF|SX&;0HR3$6fsJa1Ru zj{*Ci$nJXtYe9^6n+3mZ!R>&LU+L?!uRBP+AD@WxU@Pf>DTKWZwk~hx#wmCC@6Ng> z^WKcl`ab9VJpLn~HZQa`J8x!PPJ{7VpEonMe!zMvft>?O!}{6=YprK|QN!O2tjf;I zt<71a{F-_Q$OP+k1z>%ie6SR_9L0{|tb0_iq0;~ewgF#Jugxpi z=)22%H{uf^2Eedg4g%KY1vdKc%DOxAo{W2apY?tYG(8(usN??_4bXYx9aeoac*uLw-`fnFcx< z@)zAkp4s9>SLZ=J6aiQo@?8WluIx+l27T-D3MCJbCtpB@6Y@}f-g3`sgMBhwIC+}*OjsK7_I9KbmzTP{?VfARcKDO5Rq=&s?9?@{H2=K9MB7`}pThsL zNc2w@%ay~utP>jh8rE(+Q{D!KAg_=wNXNE(zlDQ646{**iyow;kmV;+>WH~+pxBM1PaWfWw#$+ZeI{IG) ztH$>>;*)&}>qEx(F}P7DWN*VPhY(7hriV<+zL&8PbZg8{j9*DdsANY3@ZmNj#tXyW5=+ys0D zAnEz{Fgt;hPl$g7a365iGx2`F9|C8a5Pur*S>PNihz|m0AdoysocVn^)(&R+KUVPn zK=}Uy&OTPspU1=uW6~EX`0wHW7r@!Sl3qjF&jDv&DZk%>KFu`d_v{lT&iwq7g0uae zQgDWopG@O7^8YVNei?qDk{{y#tbA{MXaKKmWz~z--Xi4pYoKQoTnoJ%_%|$k25=qt zKPdReflCvBqgTP1&)aSImu&cBHvAbIK5WCeekl#(pKim8ZTNf}eg*JXVP*NQhWj_L z9P3%$)o|CMJ}Do>ZwLNS;0+f3W#A71XS*Y8g-IK<1KdeOYH6M2%YIMIS@!)se2x5g?G)mpFD+R|ul?+!0o-x7}W zv>VmQe_E0?VYG^g*uDyP_u?PK?74+sV`o?6b>W`2uFg-z(yi}Y8|eu5fZmF@Axu1u9a@-6F|4Zdt#+uYOAX3_PUZEkJrTU0B{$#k(tnS4AwiYtz!4U~!Nx&zP zTIB^}JojLL???aPnI*(-!r4On7%&?XNRHngz~zKS0i z4-=LN@djaq5XT8I3A+t_RyGcJe8++Z3E|&{K8SR8Tkt_b`2P9Gjf6{txS#ODpd&wZ^8W*{ILZGEm#QX`G8p-j^i^eyo34KWO2vSonyAk6CywzG3`WV>7;=Y2hUn&if?{Ut-~H z7S8ijOmCZof7`R`VJW^~SYEckI*yurpO<-u ziS6@Fq1HEAsoi(DT0EkEM_)Sb`}pR=(ft3=#lFpN1ar8z)MvrXZv-sdgo75o--07= zcr@7ezy@K8nt1@?B>`(VETyA$?@utTuFfgNR9hY$zsdtigGWw5od*TOc# z-U53&?0vA`fZYlEL)anM-@qDi^uMj$4tpQ$H(+-%-fi%My$|*qu!i3oy4W-Kb+LTz z>(NWGmh7GTdaf{ci(ehDIdon>zdNlok8_nYNm`G^)6@phddA#FXcw{}s}{|@Mr2OS zx@L+eJM$v#eVUlped}6d&7`}h%Y<#xmGDH+yZj$7Arh^fPzI&J@L(7$3B;`tEcKgu zD~1DTYNk#AuM^fz4k>XV*q|lEkZ1JO=)Mi(L>EFRXxNPzhIBI|0w|-$(gEpWhB8_c z!zSoRZ;Fo@$hAWD5zITJ$Z^f#sSF{$qy72k4Cg=VsfOos;^T?OxTe7R zr*9D~brM1qpADS ze;xQ|mGD2>@O-6B3y{ZB8-Aq?{~H^=-iGtvP8*?nnabG2H2y@NxEZKa6C5X-@l#NR z+^(%m%tGJc69;8w;#&s-nQj7Y#`rdYzxqjie3oLL&|m5m*V&XAORcbbPtaRxjHHuV zO)NgcBaupjoY|F~Sgd-S+GNEY?-`?2lo^Xq@ln-}6Uv~dCT3>h>nBkLl}~KhQ9>rt z7kS|K>}i;%6HXW6M#4*=FA$>h|2km+9c8~&Gwt2cP_IR3#@*<1t+O!W9?5^)Rzs(ygoUXyYp~=G&E>|;@ zXI#t^F1a)8XIw^xjk8YmnfhJ*Q+3P+{M^6)*JwXZnFySG2#jpd-ZK)_0)t{?#M@VT z+u-KX1%um4KRno9dh_6Z>^Xn7PmGLv2TOBsW+cm_mDi2o%#W@GGm1Hai;`dB%ti*! zY}`3@GHVyAASvt6@Ic!^7XlNfj}2N1q6+Hd6CPJvgCuiO_t3^n>MjdVYSbVodh$6HXYRn#Bxlt2Ai!JcP2HunE@n>X-<@m%rBtzQ_QT63Pq zUxBkHk81aOjQx3@#q#fo9=rW`Ux$C67@+&p$Dipqc&isD8T=vX$8&%TGvH3lt^19m ztirFjDWvEQj5{x4qp$A<3ts`)|6O0-OiW+;w|o1RTGN;nfVl|k0OWUEFD0a(dWN5K z7HO*CSkANeSMjv{#9l1@?R&9|hlcs!Fk3egy010s}ER9U}DtM^zjUm3x@MC<8 zN7jpdZ?zC(W+lR0cyR4T z8pSES45<2_%Dq+g1KjIVO{#mV)MMmcBis9Y^DUco1J46Kh< zbv1Ld!XiOZ*I_fDbKUjUPEO*Tq6zAy&Ffb8Hm?p}k8OhXRqZVe%{|R(Y{ah%chq5D z%i4)ilDYvUm4Q0yHX9Y(Pk6pC_QZ+*jyMJtW4;Z18tR{T9UyM5yI4!?AE#=(|M?~AyZP{Hp^`e?}ogZ@2YB;pO= zK1=pXHKm1v%S$gD43%aL`SpE={l@K(Pwy-!ood|k;Juj%{|T1}`1eKjEHByEpP^ql zmQ^Fvx)}F^}>ePnM(#{woPmD z^+)zG+<*0d4j1U5|Mpyc1kn2^PMhMS@qJP6BVWUr^FxZ?r!2o;l78HC_0NYn*YuXp z81V|GW5&t56S+8%9?;*bPsjXsW3(JtDe!%VBQ@WI{>Jb-`Y+Hk^~jTqp`i>tZAPXw!cT4-LQ5{e}rWGaoa0qb#wz6cMx&*7iy^_2=mq;Qj(`b{G@| zd;Ni2q&vmZ29?IOB)9^^0M}O)U-iPS&{vvzp zopmoC+&%2Wx&EDlS&vM+=zD|ZdWmsj|L&+36f>Ce?MALPL37hQGwMrpo^1bAG%N6R zv;joQ7=Z&8qzt3mGWL)Nx!1$9xhn`C)A|k&LN7SPz>U7Xw+;WCzFeSAdO!eS#+>{v z?IY^BPx`YjvBGX-82cU?=7aqT&cJf6{*mmTJ(DNuau(%@XMR>^`qf*062{I#K7#Ka zhE>j!;)rWwc3wekPJ13I6=5_i8BSAh7ljX2BW1hj5;+P`g08&|9Qk zq+P7N&pS=K#53dF?JAssvzt6mEDh(WH1_?6T+E}%59BdaS8N{rehbHNXqW=&uyE4S zl*0O9Wv~++d6D19EIHBH^$XH1vAzXx)Gv4@Q6CSW1lPtg#5to=Kx*{yVSz#0KW#yK8E4^ zemAUXG^0J9mMFp-;a-SBvacb17a-4Sc3AjEK%Tv1JPf}d@HfEOXUOMQlOaIQ;BW0Wg4p)<6V zu5fc}V{b=zWm$POH5CKzw(ymhwc`vOj(G8qTWjMdn>%{LCP|!EcNn4$NTWk*V{ysZ+baq(hu$BY&D=q z_HDb!iy86pXk_RAo#t(5t(#U;t~ZSPa$j!?=wjAULysUGX?T}CdTcOSy?0xi*jccT zw;+EK-PUB@VaHwI-M+R>b)KJ#nOf6#7Ipn%=k5)Al*MTl0*uKf|*Y%rL6P z=>G{bXUp}>shu7=L7b666HWOq@^i^CB2*{InglN+UH4I5Rl3|sS*j*fR^(lZh$b|0$BSzsR!+LEBvLA=}KHe)&JehlepeEVKgIO zjFb7|JVP~!)?ouG0a~UQII?c-*=T~{ET3su!xJXayo7ut4Zo|B2q5vlwBd_v_|?F< z4$J<5^Nc1y)+74`;hw^zMKirK2_tF!`@7ufa{){~2&h%lk(daV?F(GAHi7zEY;cg%VV{t4c pq~X}dS|eon3E4*y76N*}z{EKgF<#;&7G7iF4Hmw_!f&?l{|`S{0Mq~g literal 0 HcmV?d00001 diff --git a/lib/libm.a b/lib/libm.a new file mode 100644 index 0000000000000000000000000000000000000000..5678f568c393e145958a068c71ba89db39a3628e GIT binary patch literal 494922 zcmeFa3w%|@wLd;NIp-t<44_sK5o1IRPeVXOrEn79@D##BMWrS{hyeqn0Trn~jf#rk zwX|CQlv<&dU!~Mvi&lHRRx537OTE^Mt@USB3hl?rLvk8?mFw-TzwdWu*50%CIUz^> zN90=PbM{$#t(iSDdmd}8S@YPZ4WHdSw_!xl*(E_YcA22{DAga=*|;kHq11VgDm8q9Qk6eaD%q^mq@GGu zzp2#4>y)~@LaEvJDRtGEN?na`O{Gd*_kmLX>p`V%8Kl(h4=A+?;ntk1)YmRi>Khj* zwPBG`8yEQ3qbDdO*Hf=5^|Kq5`qk}9{rhC4{^MAsUc&t!?pA6?y;6TdJb$TDYVQc8 zT9NjpSN9-f|Ur!-MW@n@C)Yh1s<^&-Om9@igm?f9+A{}aOh1^0X3RQav1s{8}{RQ`Lo{uB6r zzp0|JV^y^4&s6k;8&$Mdk&2%BM-@F|gtT zqN0m?tLPHMv85t(f|9TioS-t{b`Yk{^hGG`qxqweXl}A z{}XxoaGi?9E-+W82UVqdO z#`9lBn0pZB|0`9ob^BE8fk##B+qbCLCdBoB5cY@5RqS6MP_ZBXM8&o~r((|{-d|U! z*z+H#*o$!$`~3(N`$JO2cD}7*f0?FYdl7f)RTX;&aUHx;#s0fq#Unjcyx;^C?_8wf zUE?Z#><21-!uu-T^KBLH{iceS;yM%8z$;aJ$fGKLK|d8AQK8~vN>zN~Dixn{yNX|e z`^&3Ty!JsAzY6%m2h4TtIu+-2(|zVzxlhH>&f@nysp8+C4F+o< z+I*G%<1HdH{}y2|rb85wntzMX4>bDCX))ilqm zyQXPAP&~TCQtO3`8%^g!%bN5bZs#wYjU4hHNaJGM;}5rs7cJ0#yluLE$^5JM(z=B3 zkK3lj*Xcj_H#ILtSpEZPo;Mr5{0E}n7=Pv#nYORHL8}Zsx9c5tg=}G_b*Lj4WW^w|U;enx^@S-4_FC_WVV4^O~JtOXkjQoa5qXUM|XV z_akM&qE+}M$+8I$blo`tShj%x;kpXPfZ}z-vwU4#7qClMQ0`*a2e1W$1AYN)0h*7W z&+7x2ZqUA`E@(G2O4>!Gs6#YU)-F*Oc7UKev!9Y_;68rU?1c+w*SPi7m`>7^`V65+ zo7Y@Fw~_z&Th;`ogn#|FaB!ol2T#I(-Ta04Z(O{%8DJrLBmS20pS+9}fd6LwoG$%F zH6JB12TY{q>UqtJ<~7!!4t+#Q!>5?;X2UK)1E`zb%uZt|Aoz%FVAf0GVwuVFWDXvN zXX{mCoz9#onnu;w*gSs`I3VESYZf8%y8aBny92|Y4PryEku|DC?T7*Geav1s0`*}dk$n$>#Dki3xfplgJ+fWC|Wg@bi1 z=t@xa^B2uuI?q%ED?wL;t_Qqvebd~=*-MtpufM*|REMbs_@G4i;Ps7~6IsNe*DDF3 z=1c!1tOJU7W=O(1Q;iC*t{^~m7J!Ab_1`l7n|A5f5@_r+D0~)^UkA8j;cGTvZglAz97Sf^Gk|WS8nSG0 z1BQ?ISoHcIkxCF)DR+C+(QGw&d$g(bwCu2SoG5zlq)!f4wa_K)@3lEQ#*wWSoiL96c z#lO~cOaa!LQUEjen7_yJZ36H+J3Pz}4*Juu!RMXpjq=&sXAhh^uc=|)lA0yg%xNC9 z`0S!IV!cBZ4bLadgDz<_ju6d=L5Enc^|OW`g(aUx35L%3_-%_oZ3@+n?dZggoPn|zx0 zo=&(W5Y9#$_roozF?=jQ@uZ7OMW2UWzhr5Mrln1Q#_m%Wq)?)`6f05!B+b4;6f&a# zNwX)HVug%L@`@-(v}NQHQAiLwF2(Y_G}58~#fYLXX};4bY&>q^qp6ecI8W7Qs*m~_ zEph_EKv_6AKuN2#`Wh{Vf`KyCBLY$s1p;cR6r@a=tMvn*vqu2{lD7QkCP_wD8$YzRHCiJHM3~l0&{fltNN+jyHJTPI3?oMa z(QA?DQ?5&6A=hQ%TGv4%qA+tGG%~`Wq_NlQKnb!}OL5vIC?W0#N{Hct5@vKH1$i(i z9vcc|N|#HJ5`LHZnzWZmW6IYxr)Q!$J@X*>d9|WUi+c9X64wGgxV#*4(EC4k=+Kgq z^UuYfcC|$}jhU3p%ga;Z@>Cg&$-difZev3=EK^-nC-vdq{_#u~;2*-}smKk*U5)|W zcTwC{4#D5-d9&xtS9yJL8#`~zz>8G;n1YKsMT+9bMvu??T;7TKJ@QV<>zQ|Qey_aV zkj&GYA6vvl4PKYJbCos1AHgSZW8-rau;(*oL^hJS|3H>e7SlX5%@ z{)JhDD@T}cx-3g^az6lsPC^8H7#U#vn8HvD!;5$&F3AIK)i7Koys=K=`#f+rzQ+(> zH_#X#%Ru78bOhhE2|&A<_;=q~(&`SnlnDdgh3iV*SSR5Kr7Y?7Jdmw`opH&#FdxiY zAU+_cfF@4j6I`H6kE#P73Y{=NP%^~boDg?YBp%gy^5clAV}LM!#z|{2SiaYK1TWNK znJ1R#vG_mHcFEEBx$OSxe_H?Fgr=IQ|0mEs+&<7={~wNUZvWqc_}Cu9{r@7+;MD}6-AC#F zUyz3YB~OHIulp$dzh{Q{9Fo43bcp1l|GQ0`!s(1Gs=Gb-k-^Sf2=Iy^h&fD zxBa)L_kT9-KU&89rVD$r-?VIP)f9eq2-%O&|CGAFe(%rv|7ZPQ`iMZ6_vK>T|MBbo zrVG3M-!81o#_orQ|0#8UzIQIW|7Ui;&+L8~?fxIX?ytMB+x=np1I;qD_GLd;U310{ zGkngj7jL%D%>3y&zrlk!^GDaQ&A-7g(7>Eu;o}2aP8j7CYA7B0Sp27rY5LMb7BJI%P zrs1ZtxbW7<-Fa2TC9&$l*wlj9w0LZKEH)z=yEuPNd`A4@__X-+cy)YgabeX9KQBIl zbB=noyPkr~#f;<8WOJM$6#&Tb1YLN(u^Jwndy+Xi8F!2X&6T|?fmh=aC-Gefg4?GW z;6eL$c)np0XzqN&E5NgvZ|s6h%tBakk|#oUzF{09-vwGn^NnT5-x(4apv32p^sP(J zh2BBCj_;y6pC4tup%@P{PwY#aZ#>SAOqcgbA^g-3jx85pFT$404iB@PL2r^U%NFqr zwy&uo6e6~xsUl2@aGtm~CPy>RQ!*Ydoymr04L&zpo;A)Cej3k;l4pTe)vh8xA`c>; z0?*R?sV$WNJ`Q{-dI-McwmEFS^Z8PbSam!$H5Qu|jZM#=5#mNiat(wo(@(7~MEiv} z;UQt3G!!10cv1ony8W^d_&A9SP~r>Eflh))CY}_Y1APo}xa~vI3a^3KgK*i*ftF>- zlM0c)e$IPHx(-R-y7XM|B$sdh|Cs}2KO#>G&w=)GUV!C)dI;A%sXoAzu)^JLuQI!~ zG+(O6bL4;IOT7ufm&l(E#h1*|vn=@1kP7TArt4UjddyTnfG;5%stx*7boH%Utd>L$ zwGLVpG^p8{Q-Lc%b86^0eSf$9$Pl z`_GXmrog%`S0`Hwzslm{SHy0M-kyJl*3A0EsyoG|7RII(#HPn9i_32;?o;LQLGu42 zw+_r~JIt9%oFQ#sTdwDJdt(G@)jpN zEX)&U!h>xu%oE8sOmi_YtN<8oZuP&!7oH<)f(M#?+E|ri9`L3niDDaWvf+t;N4RX( z#tuj1Z3x>DPaJ^!u?)ny?I+hUQ)>1<7xoz7^K5*Fe5AzVL% zxd2+{1!A`odmiH}NmBppo4j;?_p6ClB%{e=k{2eY?(d<~qdjj7a!7sh={;?g2m`ww zT56geISFMd?kU_<757*Xzb$rq^p5R_0Es6;xZ$x4>5Ap-I&Rf>v`nq<@wgLn-Uf8dy17Hl@hXT@kIy04 z2H~E3cLE{!vDPVp-$)!f=iP(|_ke|u0`^A64#lUbWOl4$@~kkrj>q#&rZEKgw3!?E z*ObBtKC!Ai)d{0@V{f#)c-=5Pf^P`TiEy4|zNQUJsiI}64Ig2CwibA> z4>CULD-6f6#1vev-uXK4Y7d(^s@?BKh{Fp!ESW>>rv?q&pTIPxUi99eoCsG2sIL6DdxHz4TVQnEr6HVWq z=2TMyX1ByLI}DCbz{BKW{VZfXlh;iHJd|y+`Kr(6c|VDHUL04JGbVO4@vs?aZ{mdK zgn8I!^Sn|*L6~bEMn3MlPh_4K>_yCj=7>IR_cJy?Zyl=eF3zKnXH5n?G|&2Mo;SC9 z-B~xe)T)l2IS%S9!~9O5^&6sLp7hx~uTx0QZLWEet9yPz^So&40j3l-+iAW8mFgqU z^TGs}-TISZL$aQG*l(2Pz_^gr0~_9yfvrWd3dNh_z1hzE8k^jun3I)RUfS7c^)psJ z7$fzZZw0Jw^jY6}(T}IJsUlpRC+(qtuUc>SGO;+Eu{@RM0%&LAg}<8|0++Uj?OXZ52Wt&5DuwLn(x@1?DRLgQO( zNln5iw^5IBr|v(wGwq3dZknEzzQT(qIAa|=@L!P8l6dNRC zUf){KAM-gE=3#!j2&;P9rhp2YBwd@H!@*4pG2m%y5F3q${@;L3RaM+)MW@>eZ!fqb zzA|=abXERpJ?}j!R()J->anqD-DA_c#b$JkU0fWy@JZSK91kK++vrultNvt>6&CWldVYbr<5vH79YN=R$2 zb?53UW4jHo^nNEAiqs^m<{> zdZ`z8fY-PdU(@t`J;^NH#B(2&-(V+ocJ|)$hi1JF=p~~-2lx$N$=G|nU5D-1dyQq( z?CK$J(mQux>7^Z*_!E!N4y#IMOeEIw$okgFUs~Tf1vcWb7>jaEda`F*s=g;}oZPwC z_GQ|2#U@KjZdGz3cKnPU&*v+Ww$`z`Iu^kq0z_S}nZJQMeK|DIT2 zRcXb|bIquUf8C4by?X2SqRrP0E4FDrex~?29hUjz zJ|>3ebFu{yQ{QeN1d>m)Nw^S?pCCl|ZG?F7mk6;@cNZa^+e3)OAb%&s z^HG#1={$FV;d>C``7(=Zn=<@|Sv)}qW7Rl99D>e$fqcH!!bU>GbAyF=1r5{4RXDELFG;;nrQB`gPIz*4~@{FPBUEY)`TD}1nbK$4XJsMjf z3tMod?`fMvqIJ6f4`qkGvM6YW9^ZL6Ph`>i-EcxnF?se8mW4T8AagX?q*)i@gqsck z!R5}BEF$ce3Dk!CcOzB+1O_GK;U&l z*p9|a2T>5N9FTOKtms>po(oyX^7Wmu#gI=LclfrMU5Fr)Z6+)W&#);GfK>*@zQi-w zq&2$~;iN?sR@4M+(so6S6({z)Zq}{?e$G5leq2iketioe`2WL%NL2G_G{y{k`ZL>e zPQGNDH3lu!`n zn%5i!wr9f@0?HAlT^!pp0@Sk62 zFV9@c?rh#6+0S!7VG1xX?_|!Blhfm9qk^q!-EDe@K|?a~UD||XO}@L!fb<=EBd5!} zPB@Ir+n8|53wP+#=G?XWG4G5y){8sOLYup|2XS+#bLB9<62Ux-Kfi*3<`J|h@l33o zO|KkHI?zU`0KoS6n1Vg28vbE>5+=|B_M}&UGn_by??MpVK3a|V*smBLdndzjtTzc4 zOg>Ej+R=7QUMo)cM%bRjGrwj@AV3L6XiT}rb1fn-0g<|fybJTeyur(JPas1aqllCE z1Q+Pib74ALI@iZ+W>7$v=7k6#B_^L zfvj`VYYEXP8ZG?>3s(}NvcW1;1cl3Zow)<#LQfrZe1=m+_UF%Wz5*`5o0UE16D!HN zs(clBX+ttk^W-+HEZ<^RmXrR?);z3EA750WSFD>A=cMCgy5-+&Rm-nRZR6>5MY~c3 zmv#mQQ7Il&7g5AFGbVrbc7a@?+B@mBl4j7a#AlR`$mu z%Ug3f!aRERB(dyS=HghcbOUg?{E%l@mV+idiQ&i#61ZF*vjO-xT;e1?%278yo?XQL z8RoASf#&kpJ;2@eA!&vAYcF_YGj}};k!NGCZ$$oF+q9&M>;#-k&jo*V%SiOZ1~0|K z*Be>Kne@h9UfiZW`h@WQA)IYM9P3XrN@q0`8I~MdXBekvyysRMrTy`kuKO;A-;s|p zUGmW~Lhwtr7vc#*1lIf!g_F)7waLC?{x~%IHB);`r3UyTb=SamCBOk^uaa|-&F)yy zXyt@D@O3&q9Tdq?g502v$ zWfXZpza0%++&0{V^xFZk>dvvLMX_m}V$%y_GYVoC$EoFBTs)vEFrRw-k>$lXUDke7 zjoDcT;=qEm3-jV}?dZA*gm(GS-+|B6F_=GzFU*VAwxjEYc`?^NWW$SBB3w4ScpG>z z*Iaa@>vHatc@gKnqtFOl`p3nKHP6$DW;bS+{PDRkukCB|%sMA;K3f64K;mv+CO$souX(jURgqcwjZ4o3-(~sw z&dlL9dW6HD(`6l#&tfT`=lI?oty$^sg*N3>9>TegUmW8z{4=N&^Q67N8Wyu_Ky+ey zQ*%z+SJ@BIk+(7p^42OsB*HdAp4yIHJa2yEKjnN5-#d3kP?Yh}#G{0dAX~c65{7xy zXY)BMm2{VD9z|a1yTc!svraRO%hg=ng~d>*F-^0HW}44A8{biMT}S5$4;ebtKGE@+ z7SCgh0OyT~yQyQahv?v_fvpi}G-iw|<5gA45$maXKa7lX%YRJW=(7FYR^z;=e%$kO zqTcgk#;!cU={Oyp=SOj05JOiae}Pf)h2Hs2Pw$VceioFc_Z+;H{wrFQH;yJw|Jy*L zzu7yZ)WOHOSLy6;{|?_G;z?EJTSMHXBe{Lzhh|sP89IH&!|P=IgoJTVeL7M5$ajnw z*7favNMDY`4?b!j2BrN93N-!z5tV;ltV+y>m?qp7zRt|+)IetYbW z=*s*%^{HiLvFf7O)K1qH>5rzCjP5+i+#q}}?`fr;$9-jSk6YvZm%akF=Pi+J_r=Z3 z?~@na8FwV-7wi<1p1oZH!Ct zKZIp`3?uog!#(2@HxnLD2?EG)bhWtL_!6+KaIC@jWX#EUzlaOtv?c)Uj)!c{#x6&@ z;mz_8pyY|rc|A1=i6lV4a09xD$sdLsY2(AYkf~=u7bo!vF3_dtVtmMa`7WySc)v%G z(li9Fr3r?Q>+qYr@X~4|d|@bjp$@;yD5WX;kH;3?>L-^exd>wG6&oVd`<^5pD z{}JoYK6EU4#uFj`pM-GexlIl8megP#zBzrW9@`Qd=lR8qW8__gV9@M;3{M+HQ7<#zW4LnSr&!x7JgbN! zzR84$uh!x^Uf?%ce3kWQe_=QzrHV@Jyqm;}e2*jjbo0FdrgtTA(3=R6ADvI+hi!rW zUnN9-?juBgHWDH~TL_WP&n*6e#dlf!U5o$S;(Bi;o*Rk=#dvv!7~|pG1MxbGa~~J! zD=b`N{nrvAe;Y0Sn1#<0BK%7hf5YPMTFCvB^go^u`RzrBcm@z6-QgA=O^9-sMp&X$ zGa{!LY!Gr|H&s>+fWBGNdUoB@2{yViB@h4Ut z1UxadM(+cSCVOCHX3t*GUx@8JQS@GSY-M!T_C{XC-uNTav&=bjtB}$``z=}KSv@vo z74QJfF(Z2dyt**X>bW~V;64R4?M z-BIqF`R@OUy|jGy1*y%O+kgL&8Q*{KA>VMoA$|G&1t{;cQV%`3C3Q8|?_k_Go^P^w zSgL5%{M2fkI=ONc@B60utt(5d#3_?StFBM=#d@AX?Js`6LVYsq`S>c(mr@TcZ%LIE zU6*QkvL)4D*C)r>Os|v95${yl^DiP*d^f0YHA+8J?)~R)?A!n3T2ub?Lmgx~^J1ue z(EQZ`R2Fx;HM%1IHa%vrb0k-oF+;a8ohRrq1G;2j55+d%V}fIbi;7EP)rGOC1(Ae) zq{k$L5l8+K8e>!y4~tb7$EF?=o7N>Zy>o0vQS9PQu}cbLmli}GPCG>zyyD2sjmwG) zXV_pQmYugTV+$>s!_rQ!e$8%(#6HbKcQfq$_L!*F2HT85&!y>Y}^+_Sxi zV;H&-xLiGb4Ulo5F+O)3aWQZ=zFHuh8y6?>O$EV??-d{|pfNs%k^J${1m|(J2eM}y zXyW93=YrtIHxnvoIcSWJ+Ni`wndFWmwg7San55O+gu}maZy?+XK>#HjA+qGTJt&Me z5UGDN4yMcg$h;v6&%J_|{F;aP@i`=YE9nr)#W;d_@tu^Op>W&~^p7j316rRkA;Nlo zVJLi|4$nF_&ftEWMLInBi}=eOVZN>@pTcni)DT_PwSd&~p=NoG@%HgBQ_g)u_}L-+ zoDg0a!Y7CDD?+%mN47!g{Y@c%9@@ay<2zFCza!*-cL;a&et-5%cpBCAdg|?Zstglm zW(G}E@p`J~qQ<8!=kKb#3bV^Lh%1Z7GG|0t=q$&{DuDa6Jl(j(}51ndghqnOhQ!hAd72V9-hmH1Fj@Q zJogeJp6^)vQHwuo@$D9Wi4f@wM}08<(S(R+G9j2aUP(pJSrL_9gG@O{obMAUFgic+ z7UEzejq~T!%pN!wRg&%gkzrY%*}4sRg7b9PF5nvc&TOVtc+@b&#trRE+rv9rgJ-^E zVbmY8Y*)ZV*RhsKIXd?X1+q5o=L~#3OiYEhqKOZ?t&L^ZJ!Cgk#$=DL*JII z%J^;B;Q84-j+`#Rdd=Nb>d~Ylu{C^;lP_Ayrm^X#FapoufxApOj2o;^hVB2K~)x-yva!6hJK$mzWc z^AVQ8+mN9#5*eVx=aBTROV5Q2W|{i#1HB5uJ@=TMB`aX2xY3p;%h9_G6a>Zc{mDHc(~7_ zv)xBhk@eYUf@NBx(#wBbm&55HoOLda>4tf)=AFKxPfi-v zzBNe}$<-qcts~>bIQHS%<9>u7o=XVbw2BakX+DSo3GqQLX3px2-Sf*W8_eQc+kZ!z za2_A*3{7Fh7VLAz4v*PI(Jf75RoeHvm_KoRC)l#aXh?yiCnHo|U);vd8#C}C6+fon zqE3;Ve4|mDfXp04&Nd4ppPv*@BClaTlGe=r?zeH%M?up2iQN7+8Z@_kvM0QfDi%jmAExXQCw-H;xZ92s zz%%t>>hNwKUe-<@o`7&}A8r7iO&`7=;V#D|PVz+P_F>LfA<1FA6OB+E&q0RJzQ*BVQhLqY(_kGaV#=Au>Z2#5wr{O^yZwY4xbdy zDMuNzsknLr%UzuC9O@S?FKL4Zbp*C~hT%nhAZ!=f23j>PaT4E!Ah_|Bp<7XIGCt-- z;+uqfmpAo5X0zc;`e5bHdXUC153v3@wd5J%kYuf(gw6Og##chWp{<`8xv_NKX9k)&_ZK4%Z}ydLN1 zbvjTkm@kfVCKDo|IfSqWT}y~YbR%K=b|55@dpi(qk#GT?D|Vn-a6@yNh_UyC_fygW zAJ|`6gzsI7Z3rtx#$(Mu6yK)IU(WA|Je0a4i@lSz$V_G%P~9hG17f-7j%nikjwZgz z@)jq2F3dNxwE?j|j+V#(B|i2ymv3fk19}C|Wy3eQ?kpP{&?NB9Y-~WYka2f@)#Z=Q z>jn5}F8HQfMl3z*(Y`!5{C!Hbh$oW`i0x1u`Cf@2fW*%V;e$fB=97-fs5=Vzp*_`G z4+K4{kUjVtad4c)^K>zdsrh3mp~D|X5Jv`%2h8xD$;FEnWT$(cUty;#vlu_JUBG#K z(Aa^nGv#Dxh2USc;AiH$NcrE$$Cu;t@A)SDI<^m;iAbRjPUSm)?0TND521W=$F4pp zUPT_nDsgqZGT`Ebw@@c@`zQNLrf}zh?)I;{$O|luqa(&gy=5FOS9e&uS3*9{bYT26y;uuggY;n_one5Cd9=gZNwS@h>NqygvkXWED` zI!T+Oq3$G(?dxNgz0LC)2U+>sbp4X~S1tPIKFfgLd#5ZB87J~}G-z%gXJ0PCB~Exj z0tB~@Z?%1#@wv8^sleSnJ`;F0ef%zjn~h7HX&=!?QXyQ>`W7uPP)rAA8^Z@wL$s!QTPDN zk^w&8>MJ@PZn$i8cmNx=-h^r1?T~%nbo~zZ$(=99AZMWm>@mq6)q22^9CrOrN_Rip ze!rm|`5&HZX;1!hT<^AN@)5Sfu>79{+TqH7-?rxKB2{O5RmD`*|bf6mE#67#^+ zv3wUEuM4*}Au`E-+NE6i@7f%s-v_$A?)4_VL-hHk#n)wLqZ>Rd`|qZ5&lFss&y#?? z1!D)c7V#{jCt<03605f`>pL5>zEzl^n1eC?sGe=9xtQ@Cg&B>xt3Y1|y8g(g|`*l9={{DGJ0qJDm{-rE>?YPY-;z|v~IEKU1Kwf zV;3J2yQE9(($2A&MX}2|MaCAzXT~o}+rn8gq4SX(`=QqVUKoUpF9 z1?*-60)@wXVV=JSaWzR~fTBBwd44taEoH^?!56X`^C6tu*5s844Qnx(;(m%25Xtj- zF@MYlfE>pjeuAr493N;*VxG3Jx3WBMgJ>9{&PaOnoIE` zHfL}C9ymIR9P4BT_Rs*zCkcc2oU zB#ue0-x5Nw{+SSp`P+o7B$OZbB69wcbbbecdlJhm&izEB>%D#$=+Clv9U+WzO%`Wc z&!cNeV7T-MAXI!*l9YWEIT!FQ-wRAbpxS-vh_WQ!8%`+x^n>q7&vz&2( z=hxY9rsGtEqE$U`l7ZR1Qk&|#O73^I9)mLx9zvWAI5(p&q&L47Ao2ILd6}PTLB7n{ z85>faR{dc&iZ@M`O(M~{Hvql04ECIY*tB?TdMq|08oN0Es(ht0=y zK7w{jwu{^eFTDHFBEKjbSQp~R&*=u>a>p1eV7n%-3d^qqXy{s=<9e=I5A)?0`Jfvg z&)p=y3XfUH|J*UlGQ`I`ij%a!N&@ocVR&S-&S5_yuSQt17+&qkui^H6!|4hxQ1U}O z7xK$3BgP08r*<)N?GE2|!8)cq3fnGv*_a7fAE$@#z9IbV5bo9upAYXd)D{ptr>!lUF5f$aZAVTnWy-orHxJASvhi)W9 zf@=xUcs3G3{yawr`SUU%gaUpU(rAL z@esUEc${L+a%7(QOeVfg{X!her6WELK1>!T0|Sj&g}?KR)*I$ossFzMqOWlp@=;z*#^4Ixys~4rw`mR8Xt9Qu7J`>HK$jk;zx5YcO&&U>?ZZ(LQr*LF(7=n7?kzHcd`LU_^8eoshii*2b>GQgxRcPEtQpaT- z&a>t~3c8PQ2KI|?vEZ>_G&4nZ_~!DO~yo4jzwZ*O*oGynzg(guhpdl!dl%Uxeru-mo{e`vXK8ziXXAP zu@8w9XJ02@5r=N59d#?WuMuaP5hvj&TU|c0l)8|mK^^n>)_B~ze5MXK(-tRbg>|sC z2$0PhzlXtewjeC~v+zvG2U(CfewWD|cS^eAFVLmug3q{R#8N?*H2qsA$ddBiq4sjK z-l$_4eaP35bOVK-?!Tze4E;ANo#uQoC1x?VpQ-<5vya>K-y^z@+k6%(haLE6@4u9# zZX0f||AzN*x7U9sAil%xzwW$%Td+njvz z2##ksDU~zs^GWfZa+I00VU|1PH_Kg|=mgX;TzPj89@U_UTxK}x9O3!q?VvH7IEn8< z5Zw6qjg4-gF+TPuiEk3_T^?0}%rcMSOmj~^=Whl)W=SAG2}kJiD6So5oE*!@yD%Tj z8@xQX1sNLWVSaoLN#9C3L~@~HuuOe-cx#O0dA=9hnKVEB_S%Cydr|a4e3-!D$DuV3Ry7O@tEia(>c+ezN~&DK0v$;TI!;5>PkzO%J(IjrcIKQ&*<-IXfPbF=(rc~skyGTVsU z{=@RgWJj+oF1b2jMrSxShL7`%Eq@;e>mhf{71=(T_$$j?9QhpG09-CV+z5|y(1a&3 z9C<+km&;=|03U}-oWwUA1UJ5y;KBYH=C2ol=JMA)z}@yCX@$pdz2K3J9i3w{v7?j6 zGJniRn7=l{;~db%NxFgybm_U^uWlL17_LDQLvFj^p7}M7lF4_6vYWGxGuh31`H$;( z`-JfRA)IYMoX!XNsiR`*j$(~Oa^km4Z}P*q+8+_{Sy+ zMB$|K$A+wIMuUeA&01&Wnl!iof27XJl^}Zk%4X4BZ`EIG^mWzj&a9^Xif3SFZzz&) z5Au72Tv18>Dmt&|vmJ%cM!zKwj;~JFZ%6A_HGkUxLi+81Sas*v)S}q5PO<5Qu^9!i zi>c*CE-oHW6*#x(_#?}U8$PwXm~|iyEJ(XBFQ#r<4WEv9@!t_&%neVO?9kiXV_8?sb>8-mLp?I+gAzu^NV7*2RM z+XQ*_I70C5S%kcL!1SokzvIc=`A zoJ8xI0KN5s_M1qtY0=p9{H9Op>?2lvPL<%JNe5=DSb8gLM?6J_wgGW0w{rynByRX@P$@>w5j9w5P?wl*-^d4Wz*Ot~ z^N@NY8rm275rVfe4f571LL|aALY~^5Ui`)8rCI6473a!<3mx-J+MM75da?PAc|bFU z{b2UGo2_O%9v0g9ShZ)?)w$Fx=)xYRe<;yT~ z_NVNK`uT3r-A$Z~@&1YW9?$-7Jo|N|(nGH)RHfA6ng4rr2z=SRkh`R&w6%~fug`|Wax=?Z)gT$MIYlyc;E#2K6TSLyv) z6E&?W$sF^`;|7C^M!Vn@szgfFJn1R+RgN&CRsLeU&KUR_Q~nmM&1db zSu95{TF#uVc#}4?T`+5ROW^C+fYqZgj1H{1s%9^>j_2W2757=u>9)e#3+{-ojNKVs zmA_i=q8lEo?i!m~9GiAbY6UY2OkD(foHd)fq<~eUx1pyoJJwExG zAJD5DH1J(-e*Rl07Z`TxPkd{Bp!eS)OFeOM|AN+sp!|#@jt0iEB5WW8LuA=de|o^u zHxXh{jvi~m|0&`pm~Wj^ulgf#(BCA)bAPwt3sJ!I?@0*%eil|)IDru1FCoODfdzyJ z&p8%`5AVa&!u^*1E+Nv1qOH-t3nBGSLgvHL z%Pp+3kZUs;zLpUAK7_uS-5CG8Az6>{`yfrYfWB(>A+{Z2jK98hKE9_t&f9Bv!i)I2 zw%$3Y4*a-9b`d7pHnwcQ{1;-v9M?FUZVcui_5G z1v~f@zse0;K!zB^lJJQ0W$zI?-a|}%Q)l7p&JV%Xpf>Mp9f{|;^QEC^Q|cj|!sDr} zI;Ti=-H081Q+?NMz$NiP2U}H^`fgE6s!)gKF38$c(em}J1D3y=`jyVxxMvPvMpp#Hyvc`=)+<$kZE}~IoX6~@iurXT2|aLeZ+>45+9@YTSB@_Lj9hP<`vL?ma^8Z<9FgcJ4%Lqm)K>A z-IcycWmM-YL;EgAb&iY=kt#di5TcBtj60Gxa4_aitu2OiCQfvk0U)^YdJ=RC&FevD z7+!_ADsefFt3vRtm7s}}_`L}X?q8e?S~ih$9#lsF~=i++-omR(iL2wOV5Rl#PaZ+vBhlj5($561etVP zruj&|8y{yKQ)hA4+0ieoGj(K(8SJFT=ZzBK+Fo=|3EE!FCy1$6z$&B9sP@jGX8M#< zjf9Y=+I9`Osr3iouab_04ibW{^#jm{<9!(ZT0+ooxAyE)# znW4>DIV0>ie)fxE;h^6#oS8H9>h-PXd?{?zq0O9M;gviXnP*=0^0FeSt^X&YE$_d}tj+{7}+7t{f_kIb}>l;bsV z)Em>jCtMb*E{aX?KF2o^P|Q7&v94_%3U1g2whm_+z<|%YES0$!28|;e{m9@-~wHGE@Y0BzlqLS>Nndlw@a#7dUhW7p$sn+4 z&rxQu9f~8~PY^)j;XVGzkpFbxOrCk5Oq&_jLb3lJJ)WCUDBY;5S_Eam>*O%49Lmh z9=JHydnO?o*&srU+gWxzcVLF4v%PZs$TDEKrGyw~wh%%NuOUQ*{gM#Ry+nv`uM%cm0R$Z2-lpdY6Va#JjLS~1q(1+={=5cmJsg^&M+O5Z`=f1SF_0)BbrRM8# zT+xf`TTfZFv-K2=rZ|#{+R>?rH5eml7!zWg7^HKY2*2guP4xxjXi&yw(bZ-|$R~}I zO<)|S-%f3XoNKuWRS+1HC5)&3e+B>Em@F{2-Rz6D!cm>;yg?QY+Xu5cg5xXJf9?bw z-uGycbwiOCmcKZWO#?u1Wz#H-OR7Pm{?9PH$Y&F{Of$v}To)iS%&q>H_^8vk@jc9O z4rq)oj!WXZ2=}h6t3`awqc}+`JifXY9@*HSUqa*wgr%(G#dMjEwDA@4Hx_hplCIza zU3xBLom)oC9sAAml9N&>K%fn1LoEE~%LOA)hI6m*z z4e{{$d+I{sbiOGNoZ*=6STY*pjJFmg09asDuZ4-shwGK1MxNCB^WqQds(h0Jx4w)-SND6n`txwzK?nH zO0x?}){L65m^)@MXN~%!EskqAW|C7tIoDWeXPSBDCudS+9^3etc|>uc$_#b!c zain?vr*~Z`%UzuC=m8+O{HGB-Q0rl!GmP-)1nynFM|;&I(8Ni6VV?g|mOP)jn9Elr ztuW7D1CMNY{&t7wi~J%l3iJGK$lvAi5`dDfL(;b{{o~^Knpf)7vg7fRM?M$k>3zi$ zkpAc5;ybVnP$saR#L>S>5J2MNLO5l#IQmZ&1d#Z}AzY6ZGORNV3_vmtF)}PV3}6@zF$rVzMmjOC9^$}|If0xZpUaqOD(>F5d41)AryfPgpdOdTl^`)E@mw* zHt4o>d8EVT*u{#w)XQ=Jgj_c!AN z6V}!4agT99Opgn`iFFzwKibj6Nqm9}bm_U^*_0!`GxHwgEyf-GJP7MJ7xN%&1L9bJ z=LiBw-0j7o~P|rsR;pgR`FFe-|3HN~CnsL*RdCngga{M^`h?>^6%&6wcem%ljS zo~mPCU*B4<%bV+dSx#n-h|jrUS^f+m{-gD~$cSZ>_huZs@VP`9Wked~!ZgbHX_Rv{ zr6qZ%9!W9gp=n_Tr%}#Mqo~rMUP-rCW@misMeO)v8g5DR{uIwg%5HsYFI{TxnWUZm z_TR_+>GP41D<93fX4hZGkG$~94Ud=IvT@|aqgNJR{L^2L{9lXT%0KqymquQ!-7iMo z^3_3){Njlpj=U`IUrug}zd3T-s>|;GOFxyEIB-?3vo6R_^cXmL#($mmpCb!q9Y5sE z?|fyr!8;{B{P3?MKm2efhV^Z@xbC!eIP0b_)+S%6-%^!+K|@n7GIp%=N=5p^$TZ6E zG|B~Ol=IRkoK0jMvFz9nO^wKy*sl#qcVJo!{n99^w0~NSN$Wbz3vJrB`R0YRS;C%a zHKv})b^V0vMd|}8YhbM1hs@79?k}k-F1xiTef94V)X{2c=Fgiq@4Rz{YX1Le)YXQe zyjj-bsDIIgb+rb_#4S*Is7o+7FNPhD%hgv(Ak!G9IEi`;2#CUSJy7|S?TnA3Mv0Gd z*wxi$BED>NwYv}w;@)$TCqh?OdkOQF5(ZG20Mz z!Rev!%BoIjGkR$&XajS09%9DbfnMl$O1-+)&dcG&spnItqg{mK#YBS7Ju0KKW6ctSpQ#I{1prTOo({)S^Ql>r1N)+$5Al!*YkSFm!8*yzn<5F z4yxDVf#aTGBb@Cfr1b__q)u+%`hQ^Rk7z2oY|N#os1G z_zx@|MZ2PZ7eeNb5dOU_US|EvEna2eBtnFnVeu;o5l_9vo2>sbi?>++y9kj_uI*uZ z-yuXik6O6Z!g{oC#KlR%OMiy( zwyR&?y1w;P>XWxJhTdAck=0U?Pdtwi5dBqYPn|PAMUx{L_ed^XJy(?+qeo7ilM&2F zl`2<9e74H5ZZ2mNj+Xgj>Lui@;@Z=7xL$Pw0)=&* z37|QTE86s{B{D#CZ|#!!cXgfi*5_V|a9}x2<|&L&5MMUB&hhBeSII+wk|#pb-Hj*t zPXa{hI#9QC{=m-Cbe;R5J1sMh=zodNA*IoCq3bYTzKiO0ti!y-4bJ=;7uWB>K4hGf zw!t#ZCvy%)9OI!4NF4G0f&da{`w&Nb3@#?eG^yK!=L+g1Fd)M(2;o-u$uOJHzVZ{8 zXD}zbxynximNp5lwI6&?WpI;2)aa#+H1b>h>+0lPB(oA4nu2KQ4&B*K)#;QAWa@ zwOu5kjGHM>;#>F~%pXsDpsM`!A04>9#)NHo`0?^{9DIahegCPidLhgm zWhFyol9VPLZxwP0&sloF+V;MwW4~3$CX)ANFK)^8O=*-H(kRQ*DA%P?uF({p`6PL5 zP7BkNMp>9fS&Y5Md{e&DZ}vvC9jOuJNU6N=bxLoRtR?c+mq;Clm%T&5`vch|73FF(tgktPru9efbhe?>Sw0O=)qo~qjbl-7nf%j6Q z(s%qm+bx-ougK=TNj)#uWt>TG9Ie@w`MV3EF2lEE#}*HpSyWt7)ft~5!T+WDKk_F7 zUf19g(jURcKdrX1HK+@5?dgw8q5O^GSQY^poEO86#|07Sxoz;6>0!S9NWH_=AD@Dv zME!#CK{fT_3){+Qd&@?DoPlulh)0~{iO|&_?}x3d7DVc45bru&=7V{I-s-u(_O0Y-OXpj2i!8Uj3!p$`~K}nmjLegqie9mW4RpACB$J zeV(>6mJ#zneRGa@0y2JA=htb&wnmjH&9;_yBCuypYhUq{4ep{{GG?mPY8dlZvsEl`VX@H2@CZ;cZ8c}@mV&U*w+>jhrizchInqY{;LSF2z8^yA0x#3 zZY4yx-&*)bLOh=$MEvUKiwAzkwdz)LJnn+?-hNr-gT5F#G2 zn>}d5ZLx3y+Bn1M{px^oh$H+0OXs-|Oh?<%;IHjy@Yi-U;M$G`{|z?0wxhvc+tJ{! z?Pq`i`x)?EHl028xwmaPA6PtscFcSf6XJb(65=^+M*|&AK}9e==s^gc)Hr`m&Fq0_ z)L6+{k&PY9`xr;Z>sS-W6I{k|z@_`UU%jMi$f&d0)TCR-P1^UnCAU^}hi+q5q)vTh zZq@0dFiMy(LHj`K+4tRK@|6NRCqHD=tnE|wJ+!Q_EmC;-zG(iqeZOB;xqa5YNdEZk zO%v}QbH(;W6W5Iywf*_Gin>hMH(=IN2ZndO=ylb1>)W@rP-hXHL#$NPOKH=3;y_;4 zh1;Jv5b1h3{#DoM+moIiigRI*7G!maAT3;GuXW-_#Ne1bTb<QG9*t2{xU~ zkouFEWBisk_bYm_oeSQ|%6D9g^?ye6+uxoxom1ZX4D`K>-_I;}BI|>G zm_a{_v=qJYoH6Vbt0Q|3kRG2CULpC*evKoV3ldQSlE`g5%CRW1lCDfV1vrABICiiJy)(vI6~+36m`26 z5UGnn#On88KEk@#2E6Yy(8Wo7f(vx%xzNR!FW(v49p$)jX5ZsJL6Lii0X4wOgz+El z;Pl_%;EbPg*f{e%=et~-Jr_Ggc4j}cjCJUp0y%C?5(|D;&ayqN|s&j^AeSUeu)LBM3O?w@r?*((J zj-xzIj-HT&M82nLbF#-P_f=JIuY?t;^!3kcsY4r*v8ef{_D$GMSt}BU($Wt_2}Q{( zzGow@bCMN1h9n0=u9j#&nJ-c$XKD)^p9#-unR5b8)7AxAfnI*qm2xIM$&sXWj+We_ z2QXh^NhwXz*1`3BoxBvqY9#iKpX%>Di#>?;i4Q+KdxTl{v}+{PtH2tY65!%k?-}IQ zC$qi=P5RS1=j6|67&`#Ve*i95u5gdxGSD~%J(Qec-*n}QaJI0V>H|4IKE(KNtK+1M zOp{Zg_<(AcCa2($m7GF`N)VR(niuoOe1zpx0`I#3ba9fd-~wIx$0etjU*po}oWzGP zS8_w*WVwtL1d#X)T+9yJ4CP84?#0pH%8|pLQ<8DM{`O2wU1*9)_d+wLWY4L?JkAIt z%W<3DpMpwdo;a`5LJ0pggrMJV=^F{rfVL1~oVVT5-y}r%w=G?d=kc6gAA|Vx`WX0Y zd4mQMmN%T1&SrjS@VVK`o0fLu4M$*DhdpZg#M9c;==-t$ciP1Jt4`c875{bmKk?3r zmTF)lcH|AYziQa_v3h(Hlp|)H0_6&4H^}|RW9_Lq4fe4E%{AonvtFb9-{Q*21) zjROWag7=w-;La}t$x`&ci%g`rAr>~#*MC4VDmq;8nd+djyZ?c@lwKuNX1^&GWfx_}?JZR42 zdTm-Jc{K*%T=}=M9eEYDale7c-S{M}u)OMleqApw;pB%vO;8>sodo#K9;ghO6w zww*TYY2QX|#y~Rc(H%`6)G}{b)55{dQU~DnTT7539Dh;POd>?at|SCASxN~16&7DZ z2pO~1;@>C4b59Z?+|LNnm|n8@>lW@IM7aId{~wmFWf$V>iSl83g9s5$pV@+V^qDP) z_jrU)-?Klj1}{O8*5SUQiu2CTdSB6FXwz`s7^Qq z*B$eRr^c_U>i36VymMSW_ZP)(R%a*L2HcFVF5xu#A5C0WrQUwI<#7$)YBBqO{Be^i z-J+!hPrUDaGbNQO{hp?f|G&Q5g!~uJ638>ypKD>bRRP+&E$b)Wp(*jVeiavq_cC@V zQLgZc>oHi14kLRgT0M$WrbL;(WWD@=nQ0`6sb|F%Xx(c0uOj{k021x!TLK zP#V%GZl0J=rpC}}(CqDe4|7UA@DiM)UrCDl1n+s8I_b!}etWJ(ykxv8A#L%yH!XRf zYWAz~_m*Fq_f~wWDxK2y#1i_jyiJ{5gt{8}{-r;dG;zwlUlooT&AncJjg6c5s{?uQ zwWC>5uk2Odd;jFd-RjKd-KA;z%YVOVo^o}Dciv=L=Br&SXS~BGQkZYi4kSEjs-#S7 z4}R{}xAwOAWd416JXs!E+hEpM-kz9RKJfS5#^15^AGh?MH}-RX<6a)U_VU`{*Prv( z^Y?vz`^KL%&p)qz#DS}S`-{q_e>`HqAJ6!~f=jxOyyxkkoY45w`jI2-J|f*K@JGGF z*F(;RddvMmNFv2o*bXkI?5 z^dO!GEv`L1XeE>w%43KCNJoF1&AJEK(={3p7v-fmiI4Kq4Y#bFaMV5Aa4Xvh_eC2{ z(&60ROhEvdN4kZ$T>a}6C>qQk--C39V;*nBg(#W;v}*&BjsDdK5zsCvj(MkZ-+_1+ z*wc4`h~cF^?}zC!AIt-i^4xx8=Ib72;&D*#R?;CM7y6f5MvRete3Pd@N@<$pX&<1! z@8SxofOdSRJZ*`w1b}>15DH(Q^#q16;ZZn_%SVj_<1f@_$}@-wZ~S?0Tqj+Q`~A0%r7#MhZ=#r)-7jPom;BL{;zsn$I08Dm%}3Zwk?(6}U40`xp>`xla(G2^g$(lv?y zUDfmTNmX4&?L0X2&sFank4XMfwqmZvapP?y|!@Rgg7*-?jTEeY-{V?SdyZ{;89GqWHjvBR+UNf7g_K zrB{Cc?GH!POxiH!^4Fl@M@PTga{Lt+eSggC*S5ZMTwdk7E!|&ut56l}nzk>Nf9&@C zU88SRMXy$Q!*-lJr{|hSeq1%|naF_;D^$PKtFLyAyfr#{g=*V9!Ms=eKKowltGXvw zGTdO*_u*$=JNdNa)P4Dpx3*V}ySb|Hbv{>_cXJih$K_I}gs-^-_dkO$pA~{jK*}x)+ZsMj0me z6;JhZb!xu?Ki>yBkE%$1dw0Ra7m(9R6h z5A0UtS72Y1R{EmeMEe%lrKkUGKwQ3D_UD0U-(om%T+=m75I{+H8t&b6p*raJm@c&h zhGV*Oae=ip0cf`e@nxg0ktZ*ahX5r{?mN(1e{UB=wpZ$GOqcJ)ycw2?8@Np<7YwXC zC-Hd%d*jk`p|54MmwELlrD+nUzD9l5cX6+d_)gT<=Uz zpZ!_=EvDizgEdv_kNI-3%0>J^6R$> z^By_SbkmgNSCcRX~dnsFK|KTjT$Xwcg+;wuQY|(brXH>G% zo8hlWaz_ehUkb1`jd6_9bMd8K9Al8@7Hvh6SSiWH;^bOEc#j<)dZ!Al9E>gR8&^DX zaxDMAO;eTL$&>e9qPu7TowU7eJl=lMj&1K8S9n}JTdpEol_qfO#-P!ix_&eX- z)yb5{q8B*_vuk%ZyoH2fY9_WqoEfA_#wWk7--~vn@yI=6Dg`B)M_U-aC8*!j?6isJ zi516vuW5QW%oScKi1ka>ATX?0)y#Xx^?RFpvs*{X;D+6s4xBLay9Z9VY|6VQEHU+- zcTeH&yl)hO-U;+?zeoDdlX>@?x|=$Wc^7^=u)GF)ZA&ntcoSu7SZ2C>le%X{d&`94 zagn>VS!JI7kJJ_SL0|bKY%IDjeoAF0%U_&u-LUL@1u|kg0+DAk3@^&C3AkLjuoiJm z0!^I6mjuC;iJPoUWPFI)i|LZ<2^GC+yXA?aI}o(q}CJo(P7aiE+q?vq*bz;|RDp$ugGh|{umUX2k`A{0G& z7#QRSgkxYBFGGBpLoyxBH*VTTr%}*tzFqJ;$^{SCl_~E>)+Z6qK4jfum@w znHY6Xm3rsCmIvSaLh0gnpIllxn)ofi&nbQI?cNo{zS`3D?Zioc*sJcWe(3-1Rafmi z*z_%2k5Fn*MiHu#OZ5D~YkP}Mmp!hp?Jd;vA~MhL+TM5wkB0C_0B5`+%klY~Vg?=fS0*F5R*W)X|#S-G;6My>1KUZ1lQ{%Pw2JX5O%K6AL3}?LFal z*Zt&=zgXMl=Gw`L=l>sj?*U#_k^TXn+#5o;!4P^VLI?;Uw1g%^ASaa+N+>GELT`~0 z$|?qgPy_@O6bm8>s|biK6cMQr6(G~e$xXXe~s*_xzRF`>`>e}p8h3V6)T^J`y_VGe(`iU#c zQLf83a<-uI-6-3^|0iXu%Ht^NjM{-?nX#;`W%uutwK~7+DeJaoS*vilCpT*VLsIi2 zV_$AnVKDM#geXlTUlyV)7v@YZzzK)xeEXTUfK^UhnFg0>IV0gx9e$E5evI-TB+I`r zEBBXY@9m))oBdnl?gT8~6R5(4k5C zoKL^aaDLVv`k@ssf9mvnNj<2P6$uM+s_}jp`Noz}il3P~e3iuMDXBlsOkes-$?1%t5&{@y=rT1dQ6^ce*&pxJ4rvzSZbk* zMQB>+JoDzi*hH>OxC1;(q>E`(tBLl)?Kblqx(d%q!VJ>EN}AUYAXb-tfg3E zF?Qn+8>X$*aYaM=bdhFzT_)d~3s`5BixxV_E3dTB{sJeZKk8;mKqas8SXG!boo(xwmg zCX~`LEZhp<)!Lb3%Aavl5UG?d0AsoCw2Bp7NY9uc2BMc>uDw^F^wvI){(4HmR~>fO z>zY>e;KtoOe%x1o>#L{3qLs*P#`y7WcjWk-ZJ=Ec-$p;6sD;i#xK}HrdA1{iB;jNiz?b#!Uj_m+G0` zE@fl1Q!CAeQZ(yJ*}Q7n7+>snRbT(I>83(mUCPFD2d$#fLjNl2nzbBxXM{=%dnMxz z3FBr6)>+m!#@y3_>08BvWnL*~*LlZcYPM)0i;`6>^mei5p|uTaAv4Ur$is_aP84ZU z8kj@P6q0vd0V&uz8DoC4);jA3f zN8hx0v4HNX7h6@>x16@fHo!b7-4+uMDmU_EFV$bPiMvG@jNLZ0&A0MZ7}n9%S~hH( zywAM|_rI$)sALGLG#GQmC)CWX0q2872{JvM3amW?W3#7V|K{ki-A{eA>+tJ+Zo5;v zy~msP9GbH3k1u-M|H7t_-XC?2e(vhHjc0m27JcpeA7Au&abI-fyicG1`qZZApT7C} zw&1isy8rIDFssdoCwsiVZ`$P@=W9mS|M+iDX4Y5~J$L`##zzc3WoxgL$y0{Uc3ZTE z?NUvXT0<$RWY4DPuRCtOyZ@st^jm@>Y7ZYjTOWTZxX1Io-`7XgUK)6~#&_npySdN6 z`E%RM*N0#0eJZu+4LvO5~6){+CzQ z8hS0)r5}H*&9lqQa5}_xlF?Sa+4K<_mi2!BbCum8pmB*&LcMYLQ-R?>#GLJhxaM zSyKxf@Jxmt*>dxhj2^Xf)x0vc(S6CoN;d9^TiBj>b8Gc^uUE=1opKZEyJACKy>qJ_d20O| zlcRIheC6}pCP!D_wpt(G=&tF9Mjz5AH$C~>_wSt3R}ai;9Q@=z^eX#~?Y{HumRvQj z-S^vy(Fv&?au4<+HK#3o`YRt6QU--G=K`g1g3VPHUs9a&7-R$`yPcTGw|=Udxc&;b-bicT~^J zz4l4(&n9HNlG}a6fzAPsY{^yg>=9uz?{SP@st>t&_mV5=@9JHyK5%v0fxY^OGXWpp zeBfnW&A*0My1&n$m-pz=k9|3?|0tiBxK^*uJvuimrhCA*VfU|X8S_!ZGp)z}Uh91| zU+*&ZuC#|QzNrt+**amzq3`uwudP~AZT2-iKe=_^2V)A%`Ci8!3wwODdsFnv2U`?8 zccmoyhl#&#*zk zwri`N)Mqcf_1d$WM(S9umb(v?hxKP%Id}55RvAc$b!nNhw}ik5$BRPh<|Tij&P$o} zJp*;A8@1W+<*my?-Ig-_#Rs;olon8_pDQ6ycf9NhY#r;D=GTu(R>@Z6b}NEt|L0_Y znOWwp+0>EKrna4A!#$#kj0i(OD9Ak457FAt&YIM}i|2bl2hVqZ>vt!Q{ebr7cV>U< zw}pOyhd#5v<=e}zC)`X6{iFd_d(ZbIYgi(lBgeHJF>=^nMh_k}dFc3&THBcZz1t3* zI(72cVSkxA(z+RCty^V$|F`TJQvS>~q6}r3G;AAIIprl8;SktUmdPJ!b^Pd^vP&9& zv?HsaQSs{rYcGD#u?U985ZKeN;+KYRFMe=fTT@2y>jeudzp9Niq4N;}d(tR=l!aRP zWkcS|HmHo^HyjpLeg_(R_$gU0X|wPnKPHnV7_zMh<5T=Ae)EA@>5|H!d&)*PtsJ_S zY;^0(q1#}iJ5mlE^?I!F^G7FIRyy|D=(?0c_qmO3OgVJa7qW)Cyc{~pE3I_o@u2kDu*BComRRK$RNw&M|r4~E(vsH`utcEqpgO(4NcE%AE}^2bI631Fqa@huE;(^81`-NwnRjI z5~{XAhKHeJ6@k5mCiqUokMRq_k8!g!L(LccOA+jpQT!CHpw<3H>@%o(Wbil6^fL_h zi4MdT$05Yoa^-G7fS&S1k#hX6JyxZNN53*3RK2^8TR~PS9lE|R<=H|ps zj<-z>t-a)E(ATi>uW6&NDc*YX@P{Ix#W+zLy!qEM-|sZ|bN9nzoY2JZrmt=4qlAIX z$4gU#>8)dz3@P~q>#W+zLz4_NS?*TFRL*dk7oY1uQrf(qLKq863-*68y{jjI=7^m0E zeayc`UhfgopLOq)_*9Q~(QnPR;ZNA`7j5_(z}fschpBsWguZsO&cQdF@$i;l=w7>XG?sc#Ft8Zxx`mXoaILUJ0mCE5rzBAh({XlB{+1v zSxo#EnQrhO!tlU%93gPlTZT77;`1c_n8cr!_)3Ydk@y=D-zM?>63>(P5s9Ca_!)^8 zNnE5G;fr)5e35S8BHh46x`7LQaNrS02jk88iYpmwV~L++`Y;FQ*;z+-<2?vR81&4E zH^f|l@K(HoK!|Sl3L(0?YlP@#*mE!+niGOQvQ%^RmT#sZ-1~^9%6tNy%BO|2M?6*# z!hXGkn+V}=yTnC(0NnwJe=Xg=mAJ?c_`fRc9f%kCRV4%;ksrVtNxZpq=RA<^@e)sy z_z*&bH%{8mAVj+6Nqi|G{JlijN7FVC_BHAe?LQ};21z|3!aYL>|5qgx`}5%Mav1J4 z2;nbW!YD%U6Ypoh|2@Q044pvonMu4d?&T)Ln&VkQgeTt10R2|tfO`p++0 z{m&AQm-*OV!h2*sj*$2SLhyM&;@O0V??Q<`MF@9Qj`sS!Rl4t&^oI!H|ER=IN&LLT zf0j7c5ln|4^9}SuZvycb<=9J}rA4GgeFmMq95ZBoFC>J!Dz}x=Ug%fA|4!+?j}Ym| zBSg986QUg4(w>uT=Cdd-@T)KLueF3d2ocXdgzz_p5OkS@D8Fp!F79hYI$kD@a(s&r z<+z;?{68mzzi%ZxO9;M~Bz}z${sS>C5!OOJIZ%kfgqZ(#lekV;#ptK#o=F_jN|q1t z^@Krim-i}WL{?A_q*I3q>w(0BKa8pS`Ty&IcwSNbPwIi>pZ{vnu8E!WOYyh=eE7#1 zJ-QEnd;Qs0dg~8=@{gmV{od^U#<-DBBs_kPzS6JbUz111=*M4rb6t~bE&nAwfXOyJ zkaadakf*%#KwgC&$RO%FSoA=ih91b%W$1z2EB4fGw2qJ3dHT=jfwV5QTd9Q_cdn=% zO{E1=7r8RTqS0Y!flR@EdM%q4h@k^C3NAtLW9R`Hnj?l5$Xx{`Bi@>}XkmB#Q1gB9 z&5IZ8-c&ukWK+L^`tsF(tsi%F>#iR@yZhUS%*|<+c$3fuX$4(|?dHBH(up^jxyQ;~#I4w&R(pZj7oN=K zYY8=u8m}a%{XZ>qgUG!I@lt{ox?W&My!JB$y=twxv_J*f_7?$TnpW=k-NC$%aW%ikE$88BRBd{xnj+&#%AfN9b&pZTVUMF|G{a-Lg@?{nj7Bt z4t*2wN#fNF89l~4TW9;ekBWK>ZQXPEs+;bNJ~H#YFTMzWy?g7DhyS+ljZQt5&x`JG zWzXgwBYytuy*mbnMGu%cyhgx_%glXY&weoP1;~l!p0IcOa4bGbeT|f-66WTF<>N+R zM{pkB=GA6XCo22Gq3kcAlhaYWbkQpD9j{w)SqGGM!lz!^2_Bb!uAQ*ks}&l&>^=;w zDbUr5$**tCLzOpf1_GPIVUo3sKv+sH1S5bTPF_ewxjbCNs(Wp{3N_UDS zZLiH%ZG(TN2@-1Fpg2wBjFs0oGgY)zv1e=OSxR3cB9Xc!l~MQ6|BCuP5~avgd+Tf5 zRc6~G&zno>Yt-`U-&8BK>Q1OQd0JtQJhmunO{cchE>k0erK);W=88UVzhdp(H}8q+vG%b(kEZ8t?J?rP zTgE;5Sa@{NYrUgy8u@f7Jq@EhF2$6%Xb*m7dsHLZMegTEZ{PFFL!)1QG9e=Ofp<;~ z$lJLfxAxR4dO@>~b2C=vjm%qHkgLYepq!*9pXjlD&(S_R#?JHg%bm4!%=_QH)**L8 zO3=5jv`onDKjDk6odq!pJv_lDdUs+rt_224MTEs-di_r{N+)(eWyf@-8c1_+!xpVzVQ1o zYjV}NzP;g`V`ElL)PGr>{CTA}7U(T=4=3HyV1a)4NRMv!%^a@Zf2Kjf{I6@~s(Ihs zn;zI5Te2%U_pK$rzI(x;k9cj;tXpS<>EAsutM2-Zk@_F+Pkl8xwU#;mn|`p#-IqbX z=*|1i?0le_-tyqu7n7F6=(h&9?)}IIcj!O#SpUS5o=LizS9HBHy&$sjD!t|BBW`M3 z?V$eL!R;Hy-+4w)?L6ZP-_&Ee@9L6kZ6|KZRrAg`?fvgc!2kQ&!zcK5ZlD)BnkT$h z^KL!)>;8Fl+GOkRR-L(H+auY!n!kS4`qx^^`VZE>Irj2bNBqa@ugwcSnsxuZ`cwV- zT-vxjL|5hdxj0k1EBf$ z%{!7e?8)8w^84P+S#hTpQ*Y(`$pe1ACFY(t>pghr&So*e8(s|@`)l?0)x6nfv|oeH zzdfP_#e0EwRgO_EoaScz2AKkoe|m3ne*tu>xwIPsQMSZ=~uU=&A5B1{$pg@ zS04U)u|A-%?Tqmk?$Xt~yKjr$&*ne!hCXY@N6*a<_)gzZcgd#Khkw!A1Z0h^Ui({f zUN*4st$ycFKT5uFbl96&Bll>Xd-qN{-z#_USHV5MTre*8=LYu-es9$MxmA%7sM%$n z7v}o5B6=FvKv$;z1obpl8X6aaRE7icjA)tk@qryHrQKAiU)4(e11b%m)X$ z{(b|L;)UZmVFNV`+ENw6khdxJkCo5c)aB@chi)pO%JCo61gN#bvhXEIZhHxl; z*7)7i*pR7*z@EFKir+MRlOM!Z!fbMpvF*$SE5g^+Lj6r;N(yB3M}Sc`4}1DvxV6 zIu0sj(Q)6w%8z;>Wra&Qyp=8(vdFUNLTq$;IdrXUbYnnQR{Xk2I+YL0LD!HGk%sk@ zrVH$>^|@9PP19i?f*+cmS)Y?Zhvto=X`^D9Q423 z^sjnJ<-fEZ2kEz&8K`QxqA#t-LHZywBiU1V4D~qZ?lDz`T%C9Xer4%#c+=lx?tB~c zsB9KPJq~aBKrKYN8}z6o7DGJ_Z~AKH-7f}xH48QCN05y^$ZTTAYo4&634vaxxT93nzQZS z4f@i09NzTxwKU1jphu@*G1TMmrf(qj?@1DYpO19+&@>d|G25bH481GP?G0nJKhDPu zV{bp~DLsaIAJ#Pj!{Piw8RC-_0!Vz84S&przW|)kW1OhxvEJtXrVZa{!{4#t9|9*o zripqU2W{@u^N5ss9-P5b&4X|f=H!zwx8@vt66VjGb91iEIrb#Xk2$C2Tso6~Eb)AapOW}_iC>X83y1L$`VH_e_VW=>j^X5&16WG0 z1NsU(Y2QlfbwID-L*h!WBg&@N0scc69{7%v;ZK#}&ye^$i9aUsrzO5p;%g-ShQzl? ze80r=Bz{EVCnbJH;zbe{=|+4+x{*GSZr~!_z(u-&H<|43Lh#>B2!BTi!H4-sdgc?|uMr|2#61h} z-w1OM(nko3y5|zYeZRyH5h9$U61TUrpQXF1XF|^c{_D$hs(QxxHsjx!5bixBo+R-! zi4T(a2tvePI_;}SeGK54#BVaniS!4E2U+wn#B2B0zx%yo z$BN&}al{{iSoARh#f>z^-S0eqD&M(`-;)wA-p*Q_gWaL@9f>y|(Zc2=W*(cFw;k_J z@=mFl;idXrWV5r}k!y`r_5k&#s{BYxaS-DU5p{ zgUs}*ofzZJckY{{3b%k_pMWpLEdghaABS)29&Mk3zGqYXA_N`6dQ|Q8lz(r$IMET8h=oa&{G$L}Aih^k_D6Oe3AvjB!Nl zAFbLOx$ zB>x=l^nbvX@~F>A*5bZrQ$^ZT?y1~VyQD^4YM$5*x4Q)-{&4I#c(gw4$r0uT^P+oi z#=OQ!l`?hL9bziV8ZE&%+-)eaoB4n=lF$MO*jh0`td{z{ro1Q}QJ3efW`|GGi(m>o0|qj)rSIE5G>a znic{(@*^L`?|yt^y2~l7Fkx`SQqnXkEO;lKY3>2tbQAN$iS(A_Y5tgpr@;c#W5{HT zaFMi9GVnnlxCnb?RJaOP&}#pGB?G@=CcszZ74NM#jB(bnNM*9fMdil)DSfsP$rts) zpfcVoX8H|d$l%z|7{&;X{eodi%gmJvAQWa|mUnb(f+6GMv8^d%CzOA53unA6-L75W z=W%+-$^&;sSX?6IIUZDuF~|$P4?U9*a-t^)vB=#^2szRrLhL1fO9;9%gmoY%A#8*{ zWHjG_7)S{F354L2CGkZPzDx+ZP10S+Ux17CKj2B)gMX2vr<{uKTKJ(1`Hn_&Lb$gl zL^x4|+)I=0(+Cl6HX-;elf$ z5d7i^5nj54Qwbq|%O(Wf6B2)kFa+`?Lh#u~2>+iGg6?ZV@VO-21JOq4-blhOgrL(U zoJ7rbN*v))?}Fh45h9$Q5x+)=53071 z!=R|ed77ybXL=njk9-Egb8%qidUvI_?_BY>`NE7jgLz(tccs%%zn-(*jhJUYk`s`4 z*HO-japz)uXdLf6*IMRYcxbj3`c3N5UYz#^B)$?mv8aOcde5n zSJIzlV{@>m-)!T(bK{mbwMJPdRxVtTsx=;G`f82Hm51x(=3cK*0^rzkoNnGL617&O zi_-8W?+~olwb7(iD^e?eCABd0g;iV@nyVAyz^y6CS1JKSlUhPvi3^L|g>(K`lXSIrE z`js}bH7`7CH%i&Gkl{i;;;|)P6^5bV&#;vZIcXuc8!{Dqs}zz(YpoakHJg+wF67#w zfMxw=HY6L5wiT&Xu_BdK4`0QcycV8pDrl9oNYN_4inf8Eq7OyM7^+xV^FZYn?X0!Q zT;IyOMwJdU8%CtG)j&oj^=uP2(@WS_4|wQ(NGW%kc;HB0(CASLERu3r=^wU1%7C zp80AR`+CZb`8Z&8G%*D$Vui}#aPCutMS=hS%>*{%rHVM9A^@u;w&Y^eCj3Xo+IH-LL~aIgr_CE zK*-91gwS6QA^0|wFkHfpgz(=@;)xRPBXP062=^fppDdx6AHsf~#GfDpF6M~{N31V^ zi+x4lVx9>2t)x3G{aqkLI{%Qc7UzeEw>X~v> zLF>G=p*c5EvlcaGliofLVO)$ESq*bWMmrT>>%2tJ3i+`%WK~+t_%EY7w<@lF@sGQ@ z2ma8!_ViDWVSb_J6=@%EUxNLTb=(hO?n=XU5*rvY*MDB+NBrhjTHw3T`KSYx{y%rV z!E0QPlvh#SkddA8DAp_0(^|(aCf}%L#$9KmLsb{XPN(W7fZ#*yPDO(K3)ej!LWx`I;U`kk;t8ZrTdq3(p0 zp9;%9t{;KJXypk|(GjY=q;m)&6ah<)>#Td_jqB7;o=6YUD1Hi8&}x4p#&yQaW8~X3 zW+0{Csv$kwiD6W38yMxTR>M2um~YB3{~^XO4e?ecW|R->hca|ePzWILe)utX#)0GZ zP<$&xcgPiuZumxwAqgV?Go-I1pOfi zPZOeoP-eoh=nsk40;G(@KGtMTe6T{Yl1`nwbgAfABRWURSQ8{>qK2&G_Vd+w3qj92 z&-(g2nG?=eTBB~wodr#_$*wBNdYkZ7vk5%X1tJp`~4!eLnzhXVn?{apX zJI+>h`W;+Vm>M7`mb@GL+3`L}9%_a`|Jc#b)t=(Gf_?d1Z3SgKeBU($d#T?%RHeA2 z>!7n$oWt{U#6rI~FWXt{JB45E=5@#Ue*NN-xmq~?+lzDJ9Gl3CW8~g~<{KkYTNdek zUP?G}Pz%q!kT;j{&b=^wF5Nd3(C)!`jKv!TTC425)dek)3*q^HEgm>&N$jj&roY{_ zwtk_eJ{#dYJn#L>^M^Vkn_l%Pf&i`f`Pf;P?thyiwcKKd|L6jwJI;yM|_xmo^bWpYxTQuvA+u|oD1TIUwq}S0e{x


k%A z)6ahN_eo2Pgfz-W>hJg5vC2}=ZTZAct1(SmpN$-3-+TK8-}gY zs)gR0%G@TMDg9Yq4f<25;9DD^+{D+kdq=Ldu+(n$U(y&LuV)| zhK}VOL`qbSwHFw*Up$;yp58AZs`Q3=<${Xaanz@lsn7$<9UlLs)EJtR7`S|~NJ-OF z=y>I>j9-bmz)+3Y`1%-i!%x%=#7^d0hm$|`Nk|Es`APK1V}DzgGXJw^pO~9p8#47^ zbnoU%`rQs0RmtlUk8K@)EZW(D=6klClT|);M_=~2yVl8eJ$C=@jLIjD*?QbVTh)ll zcIL0M1=2i$OAn2Fb}VO3GnbfiDjuw3_MAi=_u*UA?6LHsMYC5GegVBe-|5UP42;WI z)*+ShRRw$z=Xyi7^=SUPIvZM+J>oWGlTTS60xc|_XVz>9JC0-86Rzb{JEFNV$b zDUL=@bkgaJ(~D}%$r0tDWQ^^_Z4VypEo(?xm|k>s_Il`3h4p{=!XNGXUdpanGiCtR z6Rv^VQr283iFCy@J?rq%LL7-$V+2GXmWD>ohnMG!aCS_+l-(fps_$=$&z=>f7;x_B zbcV~^>w7jJoiWv#8FycVAhyKIijRuxe6uDQvTK!UmFucD(wI+e{elrEqul?!et|ivLQpYNI9sUZLpi^SyU`Afo-9`AN2Z#-l~kTIie9a$ zXonY4Mc=z9emlkj+T>nHnmqvR*z=yKeo6~3`FYYCs|sTRqE4x?dC*xuXY{3=Z)}53 z)~rhpz2QjofzD?fbb!K6u^p>=$x*WLsoVInRnqbV{i17j*VKS`XIxcNW^csb(1p~( zqA&g9Eu;ObINV~EA$gVj^6QROg`uKNOg*iIZ$65*RpT^wP>SYW8ddVk*&Rl@ZWieZ zJ7u)QqCJ1iX*IHE?dQ4?k8686+R#xv9o==@`l>_k3E7>uX7}W=w~p#jeE*@3Vs`E5 z(fZq4-p;tAdi1hgyX%a5e^hi2A-w)bj-fb%c=5{K#uHwZvtr(fu|((l;~Z;CK3%G7 z9VbQ)!w5d>mmzQS7NO{0K6_mY9h}PA(O;xU)tY_+W2veVvhUGop=zv26aJaP1oKWC z)>~CiwU8upELFW}cQgO2Ij!oI>ap1;X(6hIBBhEAd!%=M&|2(Fta?goQS!@AJ6N__ zNNW+2Q6}wn7^S4j%=6Za;of+M)@s(J7O%g5c@E}3J>~r8z1Vtr%MtgY?G5lQPxLRR z-efGEN?ev$^)z~p7SM{TTJp=G9jsM`zAtsma!#umQ^_x1a%w%KXYF62<4@dsCE%@r zMlqrPHp=@Ka~|}Ec=w6@a~^(bF2vfP>CSEH?I^63^S+2X_j|7%!bQxR_;p2;yIqcu zW)O-0lbElUxqr|zaLfd56?iG9^%k24@ulql9Gx<(E6h6*Mq~~iV@1Z9$goWFbIR1o zk!?Ey{olNofMuynd9sQytn;|A$1+f?@3|@_Z9IPL6qG!G=jz286?Qa=pIXx@y0CKS z?t>pIzb@s_jg@rm83;@g=olwu_)R`DBvkgjKsQ1mfXdG_d|PEHVRejjFulwk(lITM z;%AkmQo6NWL|PpV7?J^d#^4rF!TuPTXjk2eD`{I56br^!fo zr!0oydyJpCr@}n*DJ83^Y@@F%^fu_;uZuse8^w|AGx)ZNnj( zqS!`BrbPFOzi}G6Q&R)ZYs1M)v(0Pw$-3cGN>Ps2lY3O&#!+uh?LV=9_h90N@(Dww z8r+oOL&pu9Am3qbE@e>A|DjBj`bTdNq7V)PI-pM^^nc*q3vH6_;v86G$iRq$ZYCkz z#Xb#SuA~!sU!c#I_!&ueN#fTeUKNd+{(~h9mr&@5AsnG62KPkT1Mef<2T6R0#4{v5 zS>iJ!zEI*=nhF1_CB9zbJ0-qf;&~E&C+#mt=s?qB`dt#%kx=NDA%5Y+5x*!2QwU*y zkAy;&uEC`{sn;+n%rq_N68MtaM*X2!30o{ay(VNc(Rk zJWGghu1e^Ku7-STNEk{8J`oZ|N&8rd_acPhd%qh^}M{;JU} zQeUsWN9NqFv%H?#5F}ssUGokdJ6Cvrvmx>l#@yeuo}c6l|ApkH(8+r&c1g~P#7dAy zEX-b>{8(%&oDS5g)#Kf)E<;mIzqo!jS3XbT>>$@OTG8U{d0wlXkFcIl>llw78c*AN zgjLO;#A@Qy&m3^qFD}lW4R~*U-?Po`e*Hq7RED$WTtL62kg6~g{?w|8aso)#ghrhf zI#sO79))b6Y&w^u%Mf(j%Y=;6kheh}aN=wuj#?;vYhkta_%wAib%YK{)}HctGCk3M zy&>sg>T@sjo;^3Q@<|P^l0JeHa7+cH-~lQnjI$xHq%B>M13o_$#F)8aoKsY5PpMGll_A$H<)rYc3{#@t}~W*@Cmj7#ew1NgKUDZZj* zj~lXn$hjeZfesjY#eu&y`87In_^|pzx8!w4Zz$lDOlR9g^Bj-QiZD!y9i&TRz8)BDv20T z+O1@JYMN)1s47isO)>WO>C(5T=ZdYyPrLNlI!Sl4R zUw3I&8sDaUTk@P%ZFwcFdb^)ASNdXYeB<%j7c)C+RX%N@CH8$+dudd(*5>SBZF`Hq zXg{3$SnEE$So@`GW$mf{i?rYFKdUv~I9T()_i-)4d51Rr8oJfj@7F?hexY@~v_kv- zwVSp3hCZqJH#n_5^883`b*;hLphb5N7`ikV69<#FU&$XWXo>? z($S>jXQlJUypwlnD5K~mOFCsAg!yBVLI4#VmNZ`Rn}+>$t``|U#*1`>=;$>}=`#U@ z83caT`l+ITDK_a$^BCxsn3xfFqSiDJ?}bdtgC&9&Yiowfcrfp*{2C(vUWT1ADqMvt zXtlo)@(U~(EXH_0FijN}a*6IMEjaTbL}jv>+Xf5DAL#Be#`}WAv+*lS{@_htS;JIS z7?!<{R$1_4ei_DJ#D{%`VayMKQa)idlqa;bSdh=ZDlfR#=6|dWr<{ys!Z=Z0u-NAQ zq78>UKy@jmP{8a`tX+w@nlD!bFv3ex(0*)|DFLtx2ZUy-k_M>YL4E(o$rDD7Gb3ai zj5F##&!(jy?u2Zcgd-$eK?qsEON7Bvb^!P7#33i#E8X`=_oIYx|4zEQ2`M;2#u3&h zM2D9|2)ZE>PLOb>gyPH++=VVG);1exkMP9VC7f;AN*wXpNr-rTBHh0xgugQquZsFi zJVe4U36}!$E*a{aQvYVPwBJjJa1KdaoLz%|p=$~#WEXJvrECCrEeVCp0`}re8|(*4 z`+FpuKnV8-BtDN2=@7CBKp~TWzfIEqq=aq>{~(0BKk6R+;Zt)!E{&v%Ggs}p{A+8t z$Sx5P71bMJ-oTh^IG(ZM`Kr6lS6|!`tG9t?{hf1jxNd;fPc%hGYiG%l6#GJ1lz&YaaE55np^WnLGfRD~qt#mhT z%LzHi*|b$F6mK`+{sv#nJPi#Rf9Gj&zlNH1b2UP4+>bJ7)!i86ohQiT zDCgo4|!J3 z8a$es|-C?jsYxFlf(=qcSQi`@E+k=Aa%*H4XiR znwXL9b~e154NtYz)G- zxs0>yGkDER=w>;r4|KHk#Z=5XWZU-aM2s3gafF(4BqF}lf$dL-^TbmLQF)e2xS9|h z+$KT{bh{-yObCA`2{Bm}a|;yiRcY^s{Go1c7$Nvk51r?3#9RY(gQWWyLf~L6?w3Y;{xL~hSI|Soi>HOi*wvDi;CPs7g=A5N_&rQFj-%V;VWSN zyVT219O1OE^LbW$HT+-~8d68Y_4vVH_tN^o7^=G_ZWxQH-W+Qoc zv^p|(5I4?%kn0f<2ETIL$#_p|tjli&q`)>PKc_-|wW94};@2Hpos<7;1CD#|$ zep}HITF1&Uh!Fd6j+N-*(3_V%R-VCF`3l^WQT!CHpw<3HjFpU+#~3n!5Hpbf`|~1g zJb{byiL&9zHvA47KGKFy2F~cK^CWX@?n`a>b2faX4aeAO3=e9TzwB{U4T*A>-fNhJ zn^>evw^AdkWz;nm`f4?A^Z|nhkIEcAZs?RLV@ExNA$9D8u~SEClgCb&stNZAxGw~8 z=D6965S5I1NStkjYe&vEIF4o#qCaDvaBcboA;v|q)`$CB#8J_=5n|FL*7j&L-w}tu z1AvXN2LD6CI>>0^Vq8VTDmAW-oiK)nTCRJ3vdgU%elPd1(YQ*Dt8IR~(wD2fktr>p zjk+|Ueg244t=*PA!+VeDy*vRsX1=xZhd~ojyZA_Uy4Z=}o|oF~x>xLW1#jkx4rdUT zq=Qnw_*C{?fW43VbXcCyQ>@T>nR^%y|Y_-lf6 zGM*dw8Yyx`3k^2oqE^bvuRR`$N2s`|vz56LXYOcwI!t||TjS|(%re%popj9R_HaF0 zQqrym^=V_;&euQdFkgT8%6m(Ac7=VUb)CyPt;~MZx7fh2xvqIt9`T=Fd4b=;N{{+3 zaxVU}&UE66De6<+Fh$A#rhNhCwKC<6(Ol2wfrw)&$2I;)%RbxUT?~jE_mv?XO#*(_ zFzL$_CIJ$ngb^mN!O zqxdOYL96|Z7^9iL9^)(a8HDfa(Q~ATWgDd;$3Yx=T^$l zeE@!p4(klptHYEdAlXgH1`O8{kfHenEHquc;hfUE& zPRkr`z3L4(=AwuT*N!?NI-hZb7z^h}`=$T5-%1F&eG)%Jh%xe8LX4@W zrTaBP`1eQNkUoeIYv53ci#r`)-U2ilZudx_%;+WCNyvZOiv8BE-ww2K7(TbL5Yi&Xk zA3WZ!wpKJJd)ORMoCu&X47u1aN&5Lc=I}hrS&fs|6e^SuJ%09)j`uSYesweHyi_mqPt31Gw z$de3^Q_p@WaeKkRYD`Uk?WqFZ;m{m?TEvt z*vIGUSML}5Xzv$?_=aBfz0@?Wa{MBFytvi36{N%*U%kiNqS*|Gv0ihu2yt9d;L|xQ zaZ^D^Gau*<<7`l2n-*1bo^mftuZ;7GYuyX8irh&VKe!hzDsUHMK-Qbl0%1nD zTeudw!xqhVXS>$B{Y0#9#dic!;J<5#Tgy687*~H)VH{!*mx3Q+Bfb#}fg@INh)o>n zXcxZD{nsd_`W1JJlmhphs5R~u8Q;6trL1+gNI&IXm;S1|Mb^7+E#p=9x{T5I{@6V~ z>!f>hMudBmt37hVe-~U4FMrq12z>}BP82pps7(=rW>F^!LlKLnDZmkGQ-t0$1CYP0 z0{6>N>)dmZ7weE0W@t$Bx(tNAXsvr4^I%a6e6t)lmhE?kfqz~2uM7X#8Aa|=Z?SAHf0+$X>84fs=J!)$`1Zs5T9-?HxHn8R{WMvY_kaq%7uUTPd8 z4SyWRQt(6fWtwT=HNwO^<6zYT!iO`Zf zagHMocGnvh!w{)R&?%$%DO^FT{f!tG88449WWk;Ul$H&9Xqj)!Nsm!?2QiK;V~%T0 zJkBEjwUKgo@eFio&@!sLXM2(3;V62~z>njX&;tUrk6Y~`BRa@q4gy?P7TKX=g~zQk zMuwLjx1!XTg+6~#vtyf!U+7yI|0R8IJH}q#7^g@RmA4u9=G4ze|Lf`kTJ(WgVd#f3 z&WOH}eKM)l9vMcuMGK{!|E@jowH_FIRZ?Pf%UWRcq*=?s!RnJVs|uZ>m)~8ms?g!u zQ4l;iQuML^te@P1{FVJ=qUtAmo4w;5@=I=}dAiO1-VT4x9vUmnm>bwp{x|iLEEi?U z>nD9NpAG{N=lj-vG8MSBuQ&s|tbVd5?5+J|>vGl)gFt8PCwqZ;Mf%BX(2ap#WmKF9 zt^Fj=>lMN7di~@!Br;hs162GhR^roYe6rBjh*@uX z3UJJ~)A^0rYdU7J=~xjsQ_i@Xij@Fo{;y&s@G55hrvVEv+dqwOt}=4mV^)mDN`PVY zhHhkse6AbRnt|(ujhK;h&dm7jcRz}Lp0S8WDDjv>YZ>b?H|FS3TDdy3) zx<|Th#SESr8Cshodp2Sv)WxzM@?G3z7kRBJ>8IR7&%&)UR@-{(hAPRB}ucV-%G=0)rAb zO{QW7sQ4w~+d7Wv7JkeF(lP$_ z`99A^So21O1+lxCR(y(gPbxCs561X;67<&_$F6|RDic!SGAygH+TVzAtgQL|HZzca zf4SBzU6F3OnyizdKr9P1z@R{`DNm1ER;!ZP+i+C{dH{Fl}M9XnKb zEShID7O$}==$$z^pF!K*=LMW~j@^WLf00|ys>dGR6@vYMjj*W!S=P+K$$2a5`W88S zmGTl3U!yWb+C|HIdXz_y;$gjp1OsL-!(RqSI0d1ZS;T@O3T0e}L;T@&71fKgqdm zckMv`o~*Nv#}9iJS~h-^2kl}1f9lgZx%icm@mSmIIMh3=UFMPg)3;a zzY+a9=SUu7tVeV+kbi%D!ZI#vebUksm`AR|x?WbtZnOcTXCDe=6!x~^pZ)nvLiFeR z0J+wv1?WHpQhVF&B0F^bm-_X{TPxhJuQc+<)~};?OKB$eByP%Y3F%EDRu?Ak3o@jjrk=CStv?g$u#DQ19*pS{21zN+G9oyQJ>AI!x)Q(@HQiu8BXnXO2F z$NQG@5XSZTJD!^jx1_^pQWgvOX|?~q>hD&X!T$UG-5T&HtG^TTR&-ru%3EkZN|W*x zoSOm<_HBJ9r;=NO8c6B5cpN3uY3%2qg9}QM$(+tLSGjXPheWX@rndKP~a)5??FvO%ksKXq{u4{V@WlkpASY74MHv z85PCskE>z!CZxhrYB1;m&Uc;D6SU0Z9W=7Hh%r zd4*b5{dmkPQ=moYJXEM<++DvTG&|7mVr|}wKge!-r30n|LMq)Nh4P3s?gi;TxGO_q zy#R9Ao|O7h&YY#Siq8vytN`+1p*50=-nnM+!__eR%y_{4VOD4K(dkDK&+ri)9Oph5 zu&S_27FYZ9li8CJ>dc;$HES&mDMn_`O_(LuJanQkqLl32|2U-*nLWdiqNU%gDr}B# zt?6GO2e?IyGMPOeM6AGBNRJnY5kz-&hNL00XQNceA}Ei5OukWu^W1Fbm&l2eVl2^9 ze#cyS8-8^$hhFDSOd0KNo-sw}R5H$tZ)Q)98NnDoo~-?d*atnuI$iFt)r?{6#FkZ`-gfI(t%N^ub^1QdCF(d-#ptyR^q|k9`~> zuFMuRmX!QIs$;^uS4NE&tzlsuFLq*( z2!IqxkiQg_W+T9J(PkI?77R;x}2+0T>1m2vOgFD%=V9 zwx;7S(!p_$>7czz$1HqX*9alt*AaHgFzz&VnaDuUEis(LzoH{lc|wP77;kw;0J>bU zZfCfR2jhTnO~Z4Z5hmstM=e(3Q-wq1MvQx$2Y8I3k+YdRmz!GDMRxv{q%>z=pyvQ{nT zXnltkKC$RwAK&9>lQ3pGna18A^ihUsN!sL2~En1jt z`?wRPTmT!Q9Ag5jaz}JNq~gJjUar8ZG5bD(6g-A=!9Qb6V%4D-+!%+_M^2u2;|8Ap zCYd<%UK!QH*vFlF(5BetSr(+>k9Z<}^sf3?_N}y6M)Bi%#uALU1H-!hRdm#|xAqz% z5H9-{hRfbbg*yV@)^Xx#Ft5lsu^)6(;a3?ICqk75y2T@)B0$zzjui}-@vx5*9TC6g zuvbR$Q@Daw`x`M%Fh4xTSP#`Q17U1EhT{a&;4z*%^H^3KC+P0!$L-^Q9j_wJb~8BE z9o3JEu2yyAqPciFZ=)@tp9a0zUn6r>f88#!)2;uK%)CQHh0lWp+xlzX8^-=Q$h|Zi zJE3vV=8s(#8}yFjXuZUmiLS)w>u)U1oXB3x4-_%j5#89geZJOgQ*r&luA{>?Z$d9U z4AS+^S)-s&!hUvUH|VTWb0>qEJFUL5>d!#0J_DbUV# zCEwzi10hjQAsb+knRy@_El#`R~i?S;pnb>qXr*XTzTU zQ`UKph14;bg9uWtZu<>`=mOs>RHu+?JBsl z;V=5=W1aP<$5o4M^TEcL2LA0fzPo()W>0-EzWjZs#4h?M=}l$7y!wx^>YLCzKhlpz zAV1RbBaj~v2rUBn5rO=O$cpF{nG~7Q9{ItX7*#4ixYxQ5yA=^T4;5B&J%zk@O5{bQ z`d^A~N6MGLpF)0oiM;s|aJ73~_&?k&!v9&`Q2&v-kC)t9{g2(vvmSK+L+k)&_C&sz zc|*N?Pu{$1=1rX{ak1OZUx;Zi=Gn+&k2bM(4I&FxKmKa$L+Ah6M&-wbeNE%kH(?NU zW25-)0{3>>6#6ap7rQb@tBA#}^M2UL;n=kWrx73b0vm*xA!q}UtWOlAga(BDR zaca|^I(8YpN4w8tt#hw;9WNN;UXOI>DfmIss7K+)Z{)iUsiU3+h*5c7I<<38yI)Cp z74o=K?zQP_ksCj_*NS?`nzIh}qk;2`THj;bA)@Vi=&G)VoRTpGjxm0%Yb_*)Myz48 z0{XRL^xabY2UD=3D^k(bt!)T8+6D1r+FH6>uHX*)JMP>SoIUi~lkN83knMKiWSZgE z%7;9ZeVBXfBGlTf*FYNvt=xrZGe(}hgZNQSidehuE}(qyOv37jwMVOT>h|_a8y7xt zxzlr>&+fKkLQr(+@<3>d?!YPa)I6^3cr*S#y4^~4Y`~~NIT?y8ge@gadAWyh%<_n(MA_QGr4j)WW6|(S2-Q6ebEp2 zM&3a)c>zk_&`7qXoF&x~DO`<|Qghiz>8irpTqTIf0_YwXHYdT$s6p$c4Re`o>_lN( zb5HM#*t@gxx0KL^hptmXxo#IqD13t|2`e9bn$mg20 zduzL6efw^gXKme^eWBgh@U30PHCfy-arCgACr7U8a?_cPJsw$>*6p3<&+VG~Yp9S1 zv#gAE^lbNKDcxe~-5(JD$v9Wy>Su#`vQ0J|7a2cz&gg{E-~TP)&V-v2?uxGc0o!P1 z$ur%*uY8C8(Twoe6Q762o!Zenj_tDq_Vagb*OxY|9QWDi?D*6@SK`^Om%K4Qu4VfH z@jvXiCw}>cfpLQ_zLv{Au*Ppob{*LG-kw!=UdruUx5N84UFws|{&8E$l3mZVsh`__ z``ho==r?BX$Y*|gpM5~(<30&b_gI#A^V|3Ke1Bopp1b?6`-pue-ml!Xu)!m_)9+fa z_k|Z<{otWn-~51mZBa-6xc1!^#MM7pFK)#n88Jp$m+qS1$LIZ83$s6XU_gV9(!N8Qq=CQ3JXUE=4Ey{~-ro{8rNcAvr%N7- z-}ZEyIQx9Kp%E$ZAB6F|C+EYD_zZJVVlh6z>kTo^8NA%51ZYDn{+GgC?)}eFE*to*)2Siql^eEp~wCqVQ!mB-n-Er`CGpOZ`K7N3?`liS--hD9R{) zi(p};+foi4?+~)m9VmzHWgFe8a_HW&(eZwdvf{VhMpp|NUKZUx8(r&i=nmQF;>)4? z)<(y3+hv7&)T>u6+UT~F!;fzmSi?O~4!`C$ zx|8MbYj30DJ>F%dH&)WAeBd3X!HkGBDqniQ&RU=X zn!&Q8LI4$O`<~w*&<$3O7CKs~wm~-jxc7>088*RpB7O|FEIGrGn#NfTI16K8t*lDf z-v~K_HIEoO&NUb|`$PwDL`&N*Lgt^!UBiO1U2p$>Ub0yS-0AN`R&)dJh zpdVuI-X-X#n)K|cJcjS7GJKDzYQDF^Hs>Q!>v45r$I+YqCQ)vrFzCH^ zB%P34d(#JMw@7vdJtf;7gEY0EHRxHBJjRKgX>a=K z<{b$JJ!`SYI3Wr0rmvxOlFkM_HZ?8A32JZpn&v%t2EDhd6D`==rk1JCWzbt&INM=u z8+~mtzA_4=^f7mgjYv6B+r0VL5xNL;HTc&t2<5+1t81gLYo3iZ_}8`32ixd_wce7# z;Lm@LapHAg@A%Zy`blSlKOced7^ha>MqgjMT{;{5>wAdt<-`uSH~$9OU6R7!Z@7DE zg>|Js|8~5Qb}#(1`EZU=1MTsC$&Y}1CfV=@Z1{8=z8E<9agI>~?X~p1{G$d#94K~b zIW6XNcoL?;lQ4yygsCg1yP3o>UFEbkQ`mI@q&p$}kOuxdlWk7I4XrqF zNDgXpR>e3&e(9m+)ZBxKW8No`21i>>J4G0Zw{!?~O*>DBMt+5`Bi_OxY=wRv>2*Y5 z&yFxs(ls{r@f?`^T_PQ-qwt4n;7htN=?}#s_NJgU#j(tRLT(Ov7lh^cgh@vDu4K5u zov;}p#=Zzb2(Y^mrpWt?G0?1_zh0VlL_)XZbCnSO86KgyV-b8fu98n5$%pmH5pT33 z>NFs!0`Edt1#kOEd=MeJ#cdMbNr;ML>Of>fR!H{Sv1`Te7&&YV3#RP15!!{ftn>f- zvftj}0kP*Fem&-0AhvenDn-gta$bcZo&IM7;WoQky)NI5p-wvc0Q3GW@= zt5r&?q}Hh_pD6ndO{AW?AC)t=69txS~I&u2_GVTMQ zMEpU>HYr1cp5va9lE%6<9sIs^WRtjo@#kas-Tu+&E!KMt4B0K^UVh>%5#*Ob^47&m zcAFsNhSiRqD2&aTh8%&+&%Eov_c$b~E^5wySActFAXkinOfd?Q+9=2oqoVNRH{^%{ zCxkrFiCe{Z!$D=Fasl*3DM3LwDZZp>x~$?{2*s+x7Qx+oJ9|v$C6}W$!9qHXD3&>PD^A^kbCE-h=$D zF*q3a&-vk=xq%|RLAzEJ_P5DL*F)}18bd~!4Ouno>8iqH% zL~bWTiknQD6}&~E0CMs&ZdGH6E<(Lp!Q17a&71M4yZH*rUadLC8|F?xGxvFSHf7eX z*KqU0CMAnC<)$0mNh?%opd?mQGfRSJgj>2>taub9{46A?4TL21Ni(m?Ty_jLCUqgr&`H@9>5kJ*O)a_Qi%rp+R9>-2r`{l>jp?%nk3hWFXVdj2*euI-TS z@!{WeiNA26LENodUdm*e_3bW^m@rp-3#8Ct|w$w zjSX+OHFid~SkW)x-tz8EbH33(dGSc>yJLLf_qFkjXMgtm(^q5vANIZkAj)d(|D72& zM@33aGW8;Egs8YHE&~IM0v5QmkvDNeB^OdlBd-qbsdY`gUDHZ$xm~T)@|sH~*`n>x zo=SLA!Ho%&l9rqQ-|xKV%)B#T+V`hh-&Y6DJnwUs=j`V^XM4^;$JqE!?>uW?`mw)g z(-!=u>-HPL|w7*&1k-1&J9CH(wT{#{ql?_^6GBzUo)2#jj zYxxff@*f=NKP15a7Jr|0RfyNXsWYz?P8fk;h9U~MOVAZ}x2s*Nz1f>UP-5+>%cu!e z+#s$TUH&U~d9o)>9Bo`3y~hXlFkx98jqW_=_X~5miaOb_QaRbPDtgZp&v&-LJbSWd zwKRLOVTIJoy@BQw&v*6|qk97#;ijfmMYZ45og}sirPRzn3I<^R+$suF#8_Z#OLRj` z_AC~f-qnns>!NH!N-281VPK>;9`wRsMtbzC=%wM?NH5HcMH?DOrRag>^`f@~^vJW4 z9^<9xjm5W--cl?Av3)6}=#7GbF@CRsUVoU89#MfKGVY%7akuF*?#Ra*xD`I`C@-fvcZ{4deq6V$&K=tV-6_R)ldD^IF%qpJ9@jXC*)I+r0%}zx}&%I5DiNlLh0^VlRS#+j^6ICam)13-Ln>Z6xSWS-CyfI zW5>2<^0DQ*qqqC|Zdp(|eKazI;<}@^`vzJsX|KCCws5wGhCc2aipy*CqQ{4|%cHpN z=uQ7R2=~#I?!M}}qqqA;T0bxMjRZYUt}>P$W%23>8Q;cQ3anZEI0kavPOSsd7wHV+ zhg8HzDFl%CI3N6e;H1Yfkn45}eC&Bw21_~mx}D(KxNIjr?g1Ni57;cSU1Yb&W|6(h z7C7v{B9VQ{o&s}xdzd*gc|T*74z4|Zr7*^0h$q+MP7tD#<@jJ+f2$;pb-W)4!{vHg z7r9Osfw!}1j`g@aLR9kC2vK~82vMzC16ome@(6qD?|oUZo_B^g`r>a0!KjOMIoyhj zK>pEw7tPV}lAbkIzJUV&!XNCp{%3`Iv5p6P0CCW}oe=a!Nqg2Oa}T|py4T@=<6o@9 zWk`FLuX`O1mLgp!XwNzvB~D)X3}&Y;U9b8sQV7O!DEB&CFiz5Dt8;aZo#I@b-(t+b za}tkg5q^$-M+W4ZqA1Vc=6t_1AKuIPIoClZzCgE;`8GIn(+#PmgeTvlxQ)k2lCmm0U zGx}eB)FRRnXY z9kP&}){)u{R|!wp$1tCm12G@tTv`^^RkF%lTDl1_7@L)e6)010QiM!Qtg^j6miM9~b^l|mr;eDSB9K#K ztp3Ni(xcA#DH$KEKk8eDN#}7HdUCC9Hu*#k;dC z0oHibEFrg}pafy(sJm;vYZWt?Nm5Z(IMx^D`pvVN9Nka{LHCD7QHyyvfX252SoTUOdI>Nv&UtPJ5(YEUBj>H?W#HT3U8BsT zV=z-n(HjZ_BfaScdW@H%Hv!)uk*)j>g$0Iow^CvG&Y_mV-Cx|UJaM9XLw0Gg7>_ex zNbZ{)HNz$E#JCyfP-_vX=`d4Dg{yD{jpo199E$JN>x!}UsOrvYuzWlP5+KTp>C+W+ z+M_sUGAhoAIBQ^9p{{JNn=@AN*$Eq{ljTEou(yfl{QGr4T?7Px7SI zNk(Nu*ZE3AXU3?XQ!mnTwqS5J?j%MZ{TkyP`Iqqppjh^(b4}@= zG1?ZD{u#SHcUl*K&oOU{#{Kc4(mQe}&2KJHui=d1^Gi2cJhh%IkX*4_*0 zE!ZE-6f(%4#K_;7yMVYAdC=MhH(uJ{TWebeUN;1LUgAzt7Wp^GV-a!?|BhP|bKt8@ zR#9o2bkb_!3J^CyqNR)Fu2$B`CFB^_ls2_O=a4^R_#3h7IJ#uYcDy14^F~>`g%Re8 zhk0v3dpTZKx}}7sCAcw4-sa|#uf?{u_y{P3M5K*!Vo_LP(A|`0;t@@ z;oCU&9zy@azLsX3?$I4bfIw6Co12u_Z_$!p<9Vx<&F?mZgmO)*1=C0St&=|f%v|U$DH#hi^xeM9w_pd-dT3) zPCL7Ib*0@i9*LT(j}a&oHAZyk*uCq|y2IY->c@lzdcnBI1m0oS{>Ay(99>4D7#Bvk z$Ax4yE`%M1B#&!C->P?@e3nKTBGv@-Taoc+@`U6L&U`ovf~+d^xXrR4w~8}-+-hqL z9cZ-(d5V9o^!py~Dqu{wUW^Gw(}u=zK{JjE!R~Rv<6eyo9usZ<=XZY5_eh%|U7ca8 zuo@$tb7#Q}@a@~uXe!k)z_?()hfVh2I{s-E|AA%*4VeU)A-c3gKYMLR(e@zd@jOVP z`x`VmgV29v-_@)3bOb|FV?Ez*X|BU^QA+h^>>rK&StTskf3f}24K?u;Xm|6)H_yk7 z0#u6bsQN)0>9HxZeQ9Sv-4F$OK8Bv#o2HhWDYD zCR6%sgZ#ouKW9Xl*6&5Ea|IUO)?e?t@Mdv5dd~e^H?39pBJK~D7rY40(rr6u7hXah zbOi4}*P@$*{GD*~=X{>k8i(H*!@y5lZ^&owOUjY?sV|U9>-^L+pG`6Ky5o$+JPCeQ zrOqhqmHcdA+dZ&SY3p{QVE`OMqyI1^|YP!Nq9#ZJTq zD|=Bd?I+j20Ng44Ja_nP3B%cx|EEGN>a!!58Kkc(*;)Sg)CPwc!&*l!G<>!EQH$d{ z%X#y6mJ2Un6>UW>Q}HBdh4M`YyoiumX0Ejy_^!hkP13odHe1XFz+YScQsT}7kwfhB znKMp|E0aogmz(O%su;hOcb>-zKi#p8%D4`fGNUeDnkA>D&XgB1yK$Z$nmer2PrL;* zsjQI+V@yt2|L+bpX+T35`< z+~AsLZCzF`z~Wk(wcRxmckx?h9dr3xpTZf%wXS)MGeP^`F8{`zT`h7j$4PJFY6Ut$ z$=h6`a5}Sj&eN`^vmiOM@zPQ)y&L>M9!=xx5I>{bm-}3!uwq}F^(D?ic6W`!EW{$_ zL}jji>6j~}H$+^Od&c`qS3ojk$VAdDXLBcAPhpk#ADoN8-(1Yx{GnT8CDs!T^JE&* z-Ocqn+`I<&2Xk6h%o^3Qtezk2(h)C6vTOtMOwRL?>Anq4mEt?H81u7Q<(GP*K3iA| zrnwem;f27g>o9w&gR`g(tQE&D(%SM(lGqEIozIugPkrF%r2Oa6LS`P-!b2QNnhs}> zMWr*d)|Ae~jBzHvQF1deYn+)3m=1_sqQp=whB0i7R4~MiuGz@dewabFz{-3-m~Via z%*c(HO>RJ`oNxsq$20LV)PnSBt^>%CK)w)#lpf4#jo5c{#b+%*YAExQ>*>*`?P6U! zfphP?^DCW{p2O3tTCuszWIj-Ct`$_QwT^b|FV>p>v-l3Q-XUmfvo3}|x2E(qAwl%) z$u*_7LT>3n%n;{i?Lhf)79LPoRGNz21Sh&s@H%q)*Z!d(hEY z6}N0BdBiX_ostE3Q=g}5 zH$d_N^EC|LZIIVvkmsn~q9(0He)-lQ&eT~h|1M^)m05DnYfZFIUih z7-Gqd>IeEpWe*!`M8><35!vofNDS}Tz6;PAJ9PJ3;$d0FN-3Vxmxql)B_Z#k)}-k! z2s#nk$S1Z0LrQa{6g|$}jqZ4-wK{jheB5=pjJqu9PVt$&;ZB9cu=&mKxaMx;Gh^Y- zxUZ%B@GOFn$DWGxlE-Fx72nSIE`m1l*pyFuH9U41+^vFNrBs}Zc|yB72rM6lT<7LI zoAF~j7&nCLR!6~rr@ArkG#ZS((q0ohHuJ)x^fiZtDlv#H?N=Ib?ql$MAzi85*0Enh zo@-+n6PBgPs|GTEYl(dq=>$N>ng6=-PCfS{jEZ+ZxgWvgvrTc%z;>h*>G zfGj(nIhly~TAN_qACPA{P7xvkJUeMdGP}WjGn`rBzC$x~USj@&Gb^m4+%M?RvFFcv z-?>xI=&OF;d8p6)#dGFkMKYx+t+3DE2L2?=-;r6kGAG7Z4fx+PH zV*UdkMWwT_=3NZ#B{S#UQVZSzYLi2AkC`9jCAGm_41Is$-BSOY*s>R#zy+t%V86MA zsl}uubJ#QyAb5E1R2>(mEO0vp@lOFyGa!d2T8@EtpWUCC4>uS$4@XsIqz3a(lyk@J2a|Q#2$jYVFA>&BL7NU%2(t z53!B~rorB1jkRwnq1zJ;!3o8@dg0*U)>)KY_64e#V>Z$BD~?^tc{_xQdpPAlyY2lF_s zrQ;G3egVOz=|ZIOrdt2SSg8-U9sv^j_%Kp@&1i2;CBz zVaGt*p>Klz0Qwj-hCgxdxjo<+XpU!$$1-SiJAyv@&a)EV4#;?KgytgYDd^eIU|dDq zNr&MxjdP(-Lq86k4c!`g2Q+z!nb3@XPv}RWKat(98$sT`IH# z+6J8o{Ur1-Xy#Qr=zF2*XAks2Xy(&N=yK=>p!+}vLNlEgp%+1u=VJbn#@*20Lz5=+ zmT`Ir`p?iD3vY$CKu1F}9zQ^nF8ytRE`w&gUxE&UUIop3W13iQ|Aamc%{*p(xC^=% z`UYsy9}UfVH4mC`XaKzydMtD-G~;p!`ZH)J^i9w_0K+tQgbt9pAt2-W7BuZQLB9!| z0sSR3UQU&-`<|dOzPZ*XxZjyM8 zQlFqqBsy&DH1}j=>ak5^xJK9mP z+*s~ca>x4S8!pR5DL?r^K8kHcsg||%ddTvn8)}A^3{859#B2C)0#{1WyAuXRcL|7S zsERD?lsncjl_t`l?3~{GkV?6m1l$MR$ZwXatiDAk<3GGv=WR>l)Y^ zqN7pP%~I)yK)Exff#ypPiC7rc#W!g%T*iZO^P*?f#{w7&rRXVKL8Ez1%pdA0!UFn% zM+Q%+3d^1Ax+BgHXzx)0ZfP7&7*_Y*gSY!Yt(o-9vNfTHq&@RPS1b{as_wi|B&?YS ztdr#D`+A%UIs<)ho>^CI*v+)No3OFzdYE_Ro+p6r9zA*D=<#k6ik}zfd8~+h1R`Ut zk2w|M!}lQO5+WJwPtC|&H$UE~qud|RcL}a|Ugu}X7cbK*g?m4Nd$T-)y)>pXxN+_( zl({l+);8AKH6MI=dMoTMa7Um$ZfsvlZF`hAox2>_U~h*Lv>D)wQQ^|iR|ZC;#>o8a}Zs_3*{ zESWAPk1|HDmXHI^08a_(i%9+RLQ=1A9TIDVAACma{Sp?d@7Q5%rys%IFm^bCL;ceN z{0I8qEAF}mhdB6xD?rBom6J4RH%g6#oao#>}x z9ih8R#CJZ39|J^l|H*yVZHQ1D+$g2!DO^FLc}?``p8k{}=<>VrRbUeLxM9wD6#ICi zVjp}R3>Zh2G5g%M1_z|m(Fd1(u3q2Wovv5^s@j6@>WF%#LCjgWFY5qp!nK4LL>mAa z_h~zHQg6~aWb{gC?opoJvz>+J5cSU;05G3^iZ6ge>*q!_$B( zbqF6gw>L-ZEQI){`S}mDr0BgTWWP?9UkUHM$`|7MNi<$Z6Lfh9!t&SXXT`$W|It2{ z<)W186Qf{Y>=Rp}PwW9R-#(Uor?H>md~y`DQi@(b7#QjC-5s`Z-#+$sm>K)n3=qGX zK6VA%ja7jHsyGoE``Du(PRlFxu}2Yc##t#vPvHt0&1<5MW&80c{VWUT;=1~upKW0o zS9i9>w~ytzf>JCWn?eAIvkw++p_=|zwvl1OGP6gHA3kNuxXk;(*N&SwZYl(GOddB8 zZ=1N+r-MO?{cpI0T<2jwJb)0EivXK}&wWb5of7)?)9&-?ki~XY?>Be3`t@je*43+@ z_LU`19ym59@^I&5tu6MB7rhLwa|h&7^#fnrf6)qi2)JMeZW*pAjl#OB{;no=#RU)A zppboO$iCKi@40Uwf13%DHKomQp4$ltMzrT`FkS9GM+NR-bETAf(>#HG5a0P&=WPSt z_fxS7%$s*~ITm*nN#z}3N)x^X@Wl~DArC&M2{)Upd)#iqFy_2~^-;d@d|+SM4E4@4 z>!ne?jd5;V2|Kr(Z`rSBxchZoxOOlk#^CxFIpv^uG`?S@4@VWL!7ltaB~OKApp@!! zqhMg{b0g5_#=^|E4^M`fu^)>9VjQ;>J@QOOdSfrshu;Qw#y)%o=v_@8z76iiz^_s& zPK3rjobT(D!R$(XIL~==y;LbhPvHt0&1<3$XS_U0f5YsQ+d#)fUnGS|B#a92E1xmM@9Z1;JIA+;7phnrrTm%&)a3&Hj8k0~-5Bo(I30{;@yYjf7vNRGbKn{o^PQ-v%@G^Qx~` z@qm?EH9&-#yD{%Ez+mh(HvCfkqv)qZpv)N+^G9dYIM7~6&h3RM9jQv3#kVKd% zrRXVKL8Ez1^apGU9`!$;s*KDdTGRZ+jI=`d8i_pnIgs~UkZB1z^k z<>@d_n;{WZ`}}^ODNo{T`j<|vUEcXTXFz#uyya`>wc+tv z*=Z-(|xTHAtZ@5hn6yT`m z;H`>Ij$V#vM^AD7>EWk8Jgv3xbJP{s5`ob@eG@LKVzQu$$-F8iv)v|UY{RIqW(m`G zPn%6)4*m4i47WQKUQQL0X;n<_tzt5{iV4FlL`Y177S8ldN>TBkor;0oks{Jb7khD6 zCGUJ>F74vZh1B*JHxY5`=C4JSD_+S=>|3aX4NJnpNDET+c7bxU-sn)N@V3+1H9A5c zgU^Mur8`I-it}+1rZx9AfxAe5NGQTNs*dsSXUZrni4!IJ%52yzf?ZP5xsb*0R%&^q zo#r6*B*#Og=Gw#yVUD9SWliUHfiLaCb#pTl1CMH9osv`>Sq|pa7VycT4sAL8Xsex$ z2OTT5fC%mU3v-K3g_P~{dqsOidj@}lc$Q`V)(e`Gm78kNcT4P3v%l+m)5(z1bLXRM zf3{7!X2qhxwo_mIb!TeqOxwm0w=~xJZnquU_Lt*hUVFjT{q}WBAD$Oz3;g~sD;K6U zv1yO*e(;T*v9`OHz4*>&&yKM@Fl5;?;r0J!d$!(&*9JWOkqxqhXW_lJUhlkf&URqO z_gL;a23-d8_n~d^I4Ki<=~9PyE&NDItRqR3;vRQBSW~*^2IeT!H4u>bX+nN3bs+bX z=w6kh7BQ=${#MolRVS3cjsGY(t(lmwq@qlfU$i|zU5kh$sL+9nNY$L<=91!W0{G!q_)h`Z6AV?QP#^&lQ~t zDC?IHXGzxjrQ!%%c#^wbvB%VNwI1qC!ez{DmoY~l9IsNUD5=`SI;UzFWAf5Tt#w4| zJ0)7{)~O%kw^iyFC3=mE5b0nazP*I)FtlC5knfw<96Nw#}GYCrW%qvf_XMc=3Nlj_S?xJz8+>?2i7{#wPvGtMbro^ejqcF#Cxi~++wbAr8iuAr)qV{1yC zqCM&@_YU^UC)Xh#n5x(d59E4Awabmej0f8zbLSpGnIRGLv_sW@c-o;d@w7u_;%SGB zy&4He3ChM1c!WD|l+R&RO#WQOB;9R7>Z&Ym6Q-&(8TTP>cZ&L;DkiB_Om1?U7^y1? zG;@faS=A(!x_IHQ{t4DT+9f8jWj$=?cqw}Q3%znlMGNaC`cuaA(#7d}^>OV){FAkx z*pbQ?r*cWfJ^;q)i zxt6oK>_5F}_*Zp`2G~AraQcNy?I+sKeQW)DN#-(Jt=HdpsLhE3wm|sq zva+?3-=NP}$!nYKm2v6fXM1V>C%0RDv?$+e%n8mi1wM^eU zck{cpw7F*z?o0a0Hfi7W1w;E?v|akMwzygB33op~{Qdmf_NHgq7S0&_$t}rwbB-qx{oq`wz4_f@96^S%ahW zi;FGowQn*a$wtJ>2GWB(etwm`D)+3j=9XE1GwUxsPRIV?2D49ZW$ zZHGGn`rW?+2Apv}WWeeFc4VNgbpIRN%ecD#XAC&~r?CKp((O+faN4hR7o2XtgoP%Q zPQSmq{^&UU=qf;*iDuuRE8TvJA$(;+SlziaR6DmK-7q(%ms>j@+_)D&_pEnH5$8Py zrHGGI2q5uEKKM-FEMumD>sgQZ*st-y*Zbhl``|D7;9URG`xnCkn2;4TY}AB%$K!Oe zL`IFf&x4GdkUjby4?5-E5gugtD9S{UzB-M|aU?w4@s@aqf{5?;>%&2}|4|ah?q&F61}D{|Jd^N&EXGK40R? z2pi+RjWmCU5dGCDY5yZ(815UP-C3KX-yysneH9`6JxPcQIvHq(#Ipzy?tO&exbH~_ z_Zy`7bA&CBKZFS9HA2w;h_D&@M|4u8!#yIxW`v*@Mc5K|wWN7}X+DGy;bajuL1#*c z_{<=L|AmC`ze>V&gvg&~B)(JPFH8K8#PcP7SmIww{G7xqB>p2I!U;e-XE>n}h7%&3 zNQrlmcyEb2B!08RZibopHGNc66O&i{CtUjCUM@gWjuIanD%D$ zcf_rPz^^4l{x_56b_pw_c~Bti5ncmAxNk{_^mdUjR+062kp`5_d}b zg%V#T?N>>BowR>O;yWdNK*GUN&GoN(Ag>RJZXPO;vY!+FC<6yUIX*0Lj$6c65`z9(LWH+R!Z!%foak`V4YNxZkjc`u3K+$`~1C7vPiu@aw5hNhhA5%h;1|t{Jhf1la~BO; z`au^b6y1>@QVLzVP*M0rb8@RXu%J6M3BgO#9mBf`TEzjMm))05f}N3G69YZQMbS&g zH`0&|AQV50X;ESEJc3Fq9j=4U;)hhq9ihrgTK$}TS;ko@MNi=h8qI&Hd4Z>VRH^Bq zUyhGvoYcN-YZXyI(uwiG!Ix(K^u{bJzJXa3JG0(q>dYGR`6u^gJ9m_FDXwmBwsZ8= zzg@BkV_V3q5D&3wS)2r+@Er9fD+tx2$VQ-)RgTSp*0jiEl^| zdnX1k888_TQpALYRD^dR{c8iHLYpE>T+Jc7EimRw*MgX*Aua50=|MNr-nyit!Ffcb9V!_lx~=_1ho;xP!N&{L$2@N7j^X zGTuee+P%D=>rRv-VZquH&ceWs7;o@BW-Tt+Q9c_x%$3f4xS_YEbls|=(sfA7I;3qK z(zOn0T8A{PLz>nhP3w@Rbx6~?bigcVNVqsi$y_nhA(>*EYXsy_KiJsPYolvzh$o50LAxEuE7D@!CrrS`icH;$*6}!=uYh@|9;odo&l#3?eo<~YY}AdL3Vid%O>EiwxkaV9I9q*)k~d^AeM2TqkcO6Y34%g^m@`wku0yZ-7c^sRs|ep3!B=NsS5!J! zNL1wazg&63K0%aR=M2`%GNjU9)J?o)yJ%L$c1V7UT!cktt3SeHobnK!9pSYU;pux7 z2gPkn-L4nxn!4k%2j#vyl{LwE{&OcoMN09)OAyMo6Uw|(3?Rz96Uw|3%DfZJvqrnt zvxKrXx}J)Gw33|TDA^u(4+k$pLxy@Alu#U8QesZT9_~G4|H|IQM;rE?STDM7&O00WzMkL1mfmt`-(KyW zx53{&1ebCIvO-S1_VJz%`rH{aG@!|z|I|r~8D6{FUdTG{({$D+eaE6T-vh}hV^QbF zT6^H#8oU#|s;D$`GgikNLvO}6VI&~(BNO={^eTKKPcpNhkuRCZ7okB%m|1T`>2GvJ zHZE~l8~?)<82NA40(V>A=(-WDATUd{_fwGHs7nVtDBAqzLMq@fl%{i0P%%q~B{L9l zW!<^85G5`8o&zUo&T?lx!_9+5<&giEWGyP~Dqg+TOCPzv>X4AW$Mmf!Z4djnNaz^6 zQbe7MZ=@j(X^2Y)%mU1T&cb)jDOY&RCcKG#+_ezp8iY5o7pAX=Jj#=J`??r#BOqf? z4A=%~{tD^;0Gh;5E-r93sblp8aPP=FCW7jq4)u;RN-aq~j z@zUK7tnYbW#fy7-H*fTE!}Pg*0!t3|>UUGXzClfjJKnYXV&8Y)t?cus!$shN5J|)Li^i_hbBxaATUC$thJ`A_L+`efn>r!Cn34QC_d9E+m zX0P?|>5PA>QE`5^xKzE#nFvzC17U#2KFQp-pf|Jl){x zhQ}ALaQuqv;x)?v|Cab)mZ4JQL#cfE-|5Kwu`u`Le{Y7Fkq4XsT1!YkDn&0DxRL)o z272VjNRPoQ{`XFN8~I8=n!;(dMa0Y3O3A6)S7 zRTh@LS9`s=b@ASSSnoB+#K3~Dx{~5v1jdqYrWTCI^KF|i2(f0+4QVI7knlRpy9lwS zuuYnON60lZqI6T*ES@|^H92`dTVZY9^|Ko?e;8JVrtB;*~#$(bX^U)4K@J-ex? z#g)%-p40QtYp#GXwaR^vI)=PvmHEZ*d{6|cxc7lc*+>dYtuc|PznOi=F33mbrBdoU z3I@jhaTDqd*B5;I+gO;nn*-HN2OF) z><8e^t(M^H&u+{UC%Q)ya4Wu#k_U|atx5~y;oILX0dXwRxs?jnZ6H64<~7mZ8uN%H z!#dCS>53zhM^)Fq;kvLW59T}jH_8xGO3)Ei*}dnbS8V=DN6nBiqV1!wtF(Q+>0j|Z zte#!fk?$+F{Zo3lzwNePgH8Xp#Am6t$s$nSzU_W3+Cg>go)ZCM-M?JB?*(_pI?aBB z_0YH74}cl0vH^tpIqiO^@&u^jL}+aH+^f%n*_GP;LPP??r&}p{ZUgyYG_Q$v&ph@h zKM~KL)9%TqF;1%8`|jV9FBxxa_Ty=yhxik1etLGN-{pAEbpJ8lqk5<@lJ$ypG#1)e z_b=D({}}JtpBZ}~;^>GcX@m@4xbt@EG1E|>imGSt=w*UJa@26+iVAKC& zy#Hgouddzy^5Z?Kv1hzzot8H?alYpAJU+!=h*p0kc@#a>Rq(JY^Z4iVzUH^gZ&UMA9Ab3_0Cwzj|aGIRbv_V!eZ;V4~x$%Aq2 z!pId|-5UQdzShTT>}mO|(=gFv{gZ8e`tOq8pD=uS4K{jY^Z&MX|HoM#V~h5D8(Vfw zwEJJ4-)B`eHhffUwEXEZNk7&0$4&fwwtb|#<_7#f+P?P3Ilf}6U6YOfe;d#L$Ns)|n^#y(xBXv!olkGV?#8dzY*E2gnl9h|$KIbkY3lE={p;!e zqy1MM`{Ph)jBVg@=Xw7)-*a_qeZP47mrYo;e_68yxN`d+hs%Z|euwQ}Pxl|~|Bv>s z+K7V2zON?M{C@HFFPpGx|FUKapwe{t@&E2&xLABu_jfyW?0D7hucRJB1m24n7y!ma$Or zqP%HJm!=)R)oTO%*23-*(#|PE+TwoE1nG>_-!#yrXR9tspNb=r>Jt&(pO8?lwNDd9m==&WPk*;*-)q}%GPBEUojQLAv(wNYR4X@o2rH#j zGjM45r{!iR1@|y#8)aadA24DA+|sfCi}%povH&O$w#Kfb|5oO*E`>9FS+Gsp6rHdo$4ph-arsk2kER+|v1G&kmLzJx~!LHCq|6%y7#q8T3{j~TEfal}W+V+P)hIQ$8D%)t3(ChgOt zzjSFYz;hzrXiKBV*^*Tc6`)q z-uHg@o@n&i+4X)c&zzXr)L~tIJl=9P-eT%wKKrUAV0l|d?G@VJM&I!G^_HbUk6iar zRD!8X_;c&m1RcArvX#d1&D3?hz4(;b6qK*Et2k`xs^LX3-Q=5sz|~sY$RmNPE#)Sw zb#?gGz_V{z>wbM=dg_^1Yxi+zu+2NaAh)ox&Qkxgwf*q&QJbl!%`LtKHN{UTK4ZO| zuU33j5Y+XS#8aotV~!OBK4D$uU+#=I^;)e3Z@RwefwT6>mIPBmo#h{DbszCxeokAp zrA30)Zt&@dF%g9b^?{)Yb<4Y0wea5V_t+Q;wHDsP{e}oR7Zob)7^CD$zj{gFZHNy| zWK50}1U%jkyqx~#6}dVsJhg1rV4aJjJN3?z{@O|NDlc`^bLcN+Io-UI3RR0@2(cIb z?Ht!Ec*|?$q2|Gr&7sN573 zdtv%)ExduF?mw?RrtL?S(;!za65TdL_hiRuT3GC><<9Kd+k-MpElr*NX0KZ~u+q<_ zMP0~$wfs_jQzy&Uv*Q0|ubq)vX7VdP8h|pYTWD&ll|AJ&w+$-DLX3j{Ik+-B`qc{! zEpdRm%gyzspIv8_sl_0;GIiE&{4W1&s6T4Xs>E8$V~^HeZCzzO zYpGRhb**w|()Et@fR}nUOfa1_*S4H}uvYjM%h}h1EN9=g_${A|@3*XXpwvX^A`PfB zCh%PW(18t)_^(Et+ZJ@z;-BDP`F>wbjeADcIKR~^6VIT=eOgfKiI0lOlWSowyI=9q zqH^;CR<0@CRhuC(7u1_tEW;@!Aq96g3*OB1;a%xFB1??lOFETN%2xu(HY8cPm4dl3!l!U^sc_mpFF`xX@Wt zIrou2JD6AK@Q)=Vh8+F+RP}v_smoKM&7M2#x7u>{kmc3Wcv5~f+sewsE#*PA3kueu zJ}|tHrIxl`A=9&dSuc#Ae%j|6`lzs4XJ5qw>#QeC#el?b3oNKnTG?V}&=Y0{-}ak# zs*c8f<8#ULGp@A@2Rw@w)`hX6zo!x_57Xa_eEJA_%WN2D* zgjdUowsXG>aZmXr+cyZ)?9kedlfGZU+nGLokrNM>tXpkq`;m}Jn%1?enK_9tL6h-4 z>ioR2PIStj7V%NcG@z!D!QqEbKv;H=!}wjg|QU%k~tTTAV$pwcLD?dA_hP z^~_sAway0B4k{0-a|Gr5P6BF>^O&Posri9uw9Q6sd*Y=^?E#huYaQ#PnyDFk{w9ba1?VT1zY{*i&w*hx*~1b@8^Xpzja*ejlIKwhTyE>!|zn${Afje-P%$1J5<8 zjS%xx7;KwtuPO|>Vc4LRH(G@8ykoE9b;Pu=faP@av#OpwW7q51tcsRfKSxbKxgjP8 zMV&c#+RwyNItUY0Mr!m3-m=-jR@$zZb4jwFN&$_9~Z1<(+lIelIJzPy%Y;vsS3#Wt9A})4_@kT zdDm$@ z(~^W`jR`pWEzKz_QBF!-Zcgb0f1GFX%)?lJ=(ayJjNS7#HCKd@P->RLxq#7KEIh~R zPQgNS#e@j|Vh%=HDt`Cj8}&U~cZIi0VA(|>fQ%EB zue`J%5a+x^DdoQPpor9kYlUtL#`lRt$t5MStx)sEC8F{CTdS zC`I?ix=DPvvIHca?Ssz(&g^I3Slzo#ock(8|CqC@zR7){MfFXhPg1jZuUC}3UTE@~ z#2X)88s+sq6JA~#Ga8cf7Wi2!CP@4u6jm z2i;B5oORobx&2twX}(cZNeKIJG)Bg!Jt4wLBLtlhgbYvOYY8FvK)i7T`}5M?4-K2< z*AaqFV?u-k ziMGY~?vn6!Gzs&yc#8#);e?8;sk&AMOwSMkUDDFppiIsNbx(GeH2+E|ddxt=ocyM-oM?9VNBTc$nQxix zH^%R8<_F9VYX|)NEGNy^`dzTJHk-}cO^=!qO_8PtOc|znrV6ZX?bCMt3V**uI-X8i zm$ELo?(~rnAMJ1AXyCB4cnDAX@||(6N^9+6%f6e((K)p&!;T73mg-!U^6u$?7GuR2 zPLn3ipw%~Qr<ys&lAU~C%6$f3 zdRpjf_q_4d_}T?u|0o%moRxC-O(Kp_%!4SbQ)|urTbLtFD-eoFTdtMeF<-?{D@%i~ z`6ag`4@((#1z+I?U)RFd-6j2#2d50Vg0GGSUq8+dTAfxBliWY0{}p^)nCFS%$MDs) zq+N3Fls;GRRblXT7QPyn{3*F(O2;esav6Mm2Va+pTc@;6#>+H~%Ul_aRZUt`TD!KN zC^y!PS}DuF)uPR9^>Y8wK;art_@WqHiCaB`uN}~rE`8N+E#Nxn-spo8pvU8z17;My z*)I*ncLp@yj%EMEagk#(_cGakHGpmcy)k7|vZa-Zo2uU??9nlHZ#Yy z&s|VW4gGQ+%D?!5kWT4WCohPcQf}6%R?iD`i-#5Th=LW5Q`(*!{`roXfb&ftyJ!J^eVd*2H(RG<})X6Oo~Z~sWwO6 zo6UOZ3GF?&UvaW&a&$^`wJCdc&JES1tT%k!e=;PwWlF1Rebt{6T#c_W@O9ToRZp>3 zz@-l{7S}<&or~{<&}a(>IsS9(H?|8^|H;1%fj$a-3i=)BkDyh1QSD+&@-r#VRLOT! z3wK|K{&?S<^(k67>qn!LYm%Q%dAi!vnC3iLO=_m1oGzYNmb^0MF@rBpPkhJh71j7^ z313G~%uRkc<>6}LW{$+Degj7J+U{7EotWb(tvLAJcOv(u+@Gi$6TIriHiPf)=LD^O z^2C&zrv8NQyS#kQG58*juxFjPHF}IXw+AoC{y=Pqe$aeMDdxJ-2cen{7YJ%z$QSOO) zpBP&<*U*MKAf?t5HzapR>0pSnr(|<-n^qI&z6kx&#jp0(O=^+SqT03>j$KvX-l!qM zx^(fQz4|`VSwbP$-}bURN(suXw_y^J5cT9CD^?N z{e1EZDK8k(<0*sW+~=xE&)-FQ7VKS@yeVaq!JnrmU*%j|jlU;_zq|K7n*4am;|718 z@G5ebRpamV+02R5y$h3L#!LvNG4xCSDf)I`7R%o|`iF3jXT4`7f>PdJ)e? zd&ehFPnlkAJeTE;ttOsdiSWMPb64{Cl<@|Cp8AoRJEj_c(}lmHJ;O2fnj<-G&Z-!- zmGv*Yg(ZV&FWAE#pX)y~HMi5<-1sc9=F-jnYTbPLoYBp*d-@x~c>Eco-I_gigI!zU zPlf-;o?ZsK^&(tlH)l^5gWX&&fA{WbXRwR*3UADwRtCFZuXx_EretY&9V)Gxbn0~YSd4pY|m%mfHw;1f22s>4hhj*_x*bVfe`OfYq4R)Vw zF_z%VyQ`}ufAwP>t-Ci$jhZpv&7q&rQDu!#ku$5leBfE5-tW2DEQ$FT?B+ zx>}z&e^T4eepv5QkBL2l;XH8>CXsaE}*~ht>N+>weSPj5#ES*gjX$l(llye zhp36L2x&0op2=jV1SGCR1rQR)-skXf6Gx4nZ2X1=(@H`D5=YtuP6%9VmBL;?;8}=J z79x{{bYvkNSx83~(jlS`cQP4bz1VoBhP4-TChFwcL!-$KiS=7&x8;4uHR zApe1ZiNXENZ&-uF?0kncIMmK_^S{Dbnkh*BsNs`GxzEl_nL4>+`!4@C_g!|OJd_HO zA5nnDJ%9-8&*JEU#`5r!nr{0;gQeHlE~v^tYXA+TqFbVON+^xB-VNYRA%Jv8bsMx- zxXtzb8HS7C-TO1FqsIN2g`n33W=g3j@N5R$xz$T>H{FeS_EYHIxIfbyLif{PPzUBr zI^#zkjd3&5TY`P>)i6^^g{yD{jpjA6KZC6RgVN8uu*`I&pIPbe4pg_#cSl^ek5-wE z)G?p(1HAqBV1^5&+n;h5jHJ&^GlP8t>`N$|@yjsaq(7b+D3tDhssX3{CU-q_M@+b` z?u-rHyS<}kFg*4vy7Kk!PKdC!pcGLJ+=_HsxG|k>v=5FAXt$z!W8EdL>Nn%S{iq3U z*E+p>eel2d;PZX(M}2Udp;3KO)lDv(a~VI?bL_?IgUnGpU2)&&$y3Hnny5`4H*qS;74?kgRK)p~ zF#WA#Yje~mngb6&J0k2Y;baLnN%)0?;{95uH22 z$YTR-*E4j_!km3;JFy!{Uw|s;qwxnk}w4Alm1&1!u_ohE|Ktnglxx*$43$# zC2WCwlK2S;Pf2)A!U_p__m2MA;S%~u$ak@c*O8Ftc8E8SFjT@O5{60GQo;xcdA^7K zq9yDi;Zi`R>kSG0Fu)LxB1F3F63>!2&sEZXr-bJu3`ajj^ScPqd1py{t%RRQ$o`D^ za*h!3DU+~L!XG5`LqA9RAPGYxY#?E%giRz2ldz?P5fVm87%d_0?FhO(B? zW&<)knRw9d76X^CCroX3qrKR3PR+c8G{+|P(s!tiQ6T-OTrupAC>TV3Ez|O zjD!K`-${@CKJzh@5c$+Z!j=+7NEjtyw1izG>>*)q31cNpkg&gm10+n7kmC#6*K|U} zV}*pdi8VKPTZ^5*{W*zMqkJrGx?4e;4^7 zVYr0R684pFfQ0E1j+O8}3Fk_eEf3qcAD&dn7J|p2C2@gs5iG(L4JTD=c3(^agu!)3`684bLA>j}SM@X10 z;Yu@HGiPknosWV)cxwuTxb{zpxkFJjOP#UI2W>bU&@2qZYz z;>06Q9Ht2TUU5F~UEEMnCk7|GPYkN_h}l(4CR8!GyNbzJw~7A6RcaN+Xt$jTV`LSR zj4CE~RWZ5KZK7_&FfR%b64P2JZ#^N`#;9ArCda*gD$QaL%zG4;{J9wtViy)5lxSw*46Q!VP==vBfr0oDcojcIi@wz8Jyx zw^?x#ta_Qve#4PPqxp~@85?Ul(YGJ%VS;yVFMwPH8)WW^APL4p_RYMD1^q?rMl;V_gAzOx& z(C5Gs?y;3sd!E&u!N_Cs!IwGD+JB_Djby2B0yHPrHpdD4S6Nd*cldvE{e<%mrNDv; z6@_20k8ZUM7GgdG6R`b4(``R!6SPvCW27krkZ!5sp^fyM-~lnbY5+fZZgngObb%YC zR9F}SHAA$u$Kh_2as;T{5n_7gR-8j*zz{5@m~%6Jj0fXpq!)|CO@x_Jik`w1G@94M zx`;84n0sJV4f00xx0plR5!LNEpVU?L=UUmml)d^Q{H4ydsxX+Z#=1b9`-03f#)<0; zkngxS)5 zhQt>VGF^l?$Gd?L{sb?JM&rZFW-6g#SCZ?|@n^{OC_~;rxp~>z*!jjt7}G-Bo9RC+ z>hOPDc{z<-OJlUQ8Tnx@EvKloWAd8Pj_H8ufLVYv%i8E_nSRn0n7-b%AgkCFm{S6n z37z4}v+i_hStYL4){F4}sVl(R-F3{G-A||16x5o6T2oMK3TjP3t!Y-%WYSx1ua4r! zg^iMz+Z!CUl+TI}M9f|U^=_^)BBXCzS~^4e)YU3yn(J5&%n{N~S76rHE^|(43ETqL z_TT(zzh}RhTCd}b^UHUb>gIPJUVG=BEt@0zJoeaQ;9>gP*k>8{PKYbTGc>>We#q3( z)2Fs~FAIv@uo}B?f`njdCHgQ7B|;g;CmNv23)LLItRkqILixJWtB(d@3Hq6dE4hn; zJNhw(%luS|V;NNfw82=MT@9m!RLWf}aN~Hh5Ef{1!i>{2y5kr>5E^mI1`vvUkTESP zEHqztTIp~JEQSjo`j2u)sPc$5n?O7dkh}oLWrnNbq4ESq8hL?c{E$k~Q@Dag^O_iw z88460-$Op(Ht>BPS)br4Ym1!ldhkGzHpY=M22htA!9 z)}4q>J$qiYtfH}4yM%K0X_Qq&8Hw#m{T6?^ZCJBU2aI~cy!^vv{rA^zI;65yhUt+b zAuY}vpEBu;rS|UYEz4&+%xB-O{q)&DOM{QDPZ+(@)Uokqt?lOhX_YNvi%Q?gL7$Th z$wQV+`zu`~Ig9OIo-^gR3bgi(kC<0C{^!&trn7VX?3LtkuP_Ub}Tm+XOADerW@1XrcX|DcAdN&TvKK;ADBue-M)?rKT)BMjKs+a=N=V zSogUOqVEo|+99##biwUn{t4HscAyu$5t{R&^XQY;y2h;9i`$9+alN^!(seqgC-B${ zak&}I0ye*09%LC*85R=vo#njwJIjT-<)OiEHoh4q*SnTlLlWLD546<6*Y$DQjXeut z7NbQmcVHG1d*N-IUJP;6EpHGUbnMlyoiplhf3Fe(0K!b2R@mzl-bD#P5$E$woggE~ zvce9#XvhcB&L3rLLJIdnI)+x}m%A6TfNB+tXcn-Ap;JnbrOalz8PI&=9r^!4ippIf z-(?nzZ1$wR_R)aN4HLBRTOb`KG0}cTlQMy_bEhCRN+QsVT)))_3AFs$1(%zGwa9Pt zHzbT~G9|IYQOl|)LU9SE+?lvGH2AE!&gfN?S~btV@n-W`r)EC8q>de5bNmp3jpGmV zT950yaxL%Ay(XOObTEv?C+a3Oouq1jS z9sZB0)U3?k=1Q`@U5vljT9)fHA^YVq%E~(EM2Q8bo_W}8eisdepp#ojewmZ$;$DaM$ev%^&)>VWmI*8H2|Vc;TE`$#hXz3b(n{pRMji_bqtexy6pM5yEFVgvF;xx2UNRzrTKEJTE zeU@p}cGs93t?hltkJ+VKPOZWYn@r()YL?sSw(@YT?d5P|TKy{gGdxOCxea%H{1$T^ zkM!f+^i93en+RV89$#9{@seSs19GO6Fb@hv9@ICRox@58=4dzWEqJ1|eU53B*7g9x zpN5e39o54+1YdXL94-miOsPYt;bB_jtP1Pa0M=47q+ZoE^`eayQJMc^F>C#U#ah@+ z#ai3c!d2R>n?e%WKii;b2y#CvVUsBJX|6U|n~d}q$#gd%lfLo)V51u z{ie4*(;&f;&;WkS2_2pZbxejm(v$U+^tC|v%77_i3tz)ZXXiw3W{c2s>)V2VZfCwe zQQ84%V!oBTGPAb3`oXSMrsM`cEBdq?iLQ# z?`6f>evY~9`gMNbO|C)pg!H`bnE7A|<@Gp^ zQtC?#h1IU>*n_+Hr`7czSjT@*ZU4d6xZtH0OAm;m>0%EU6fjtvoPkuDU!G5#3{f)P zyrL4Zkm)`+qXa!Dp)@rtgyz@cC8JSD42fM2CloQ!Fp-AY7aDGaeyr$Lm12)8;OHUjZWpa-cGJ%uZ1 zG_MIB7E@z`@&n(AwGKCP?WfV+X~1c}!+_IX%FxD_?thmm1mLuP$$$fOE3PwWU@pQPs(qL8m3^6Z<6c++97+1)V-VxOR8u z6@|V?F5S~-=yF*yb-^r|npo?>IV>T61lQ%gh*5a#D)9N zir<&=Kr)p;kSnfXM0b<(gDcA><$4j6o8R|c!|-#jVYGN510(*L(uP=XXo&TOhFEWC zm<5Q{ih1d6Tu!WBY{cqCo2(74jXBxd+qe>Qz+Ggmb!`A|S2ycZR~zd|tS&^mGO&tJ zR9XwG8Vlfdo>)`(@Xhuex^(#T`5V6K(alshZTEuE=BHAsIkUeq_D8P)4^xf+mAhDc8~b9OJ7OE98HX0SV@vg2PdEXy ztLclmRyrJRl~QpcRO1fqxTcr~c%}7(3b^~NtS3xm#D)5wuP3nV)OrFcsbLXa9gt(q zt-7Az?qB4F{}ua}uF+TBzhLW<%H6+kzdz_-a+TEne7R$oE@>e)=UUa%G`@asd=u{O zZ+4n+M`*5d-#PQ*{g`<w`H#ljL{n|pU?XLaXF?TO2O+%lQX5F>F9Q_JcEu+B) z7nR;IdT@PZ)-YFMg|fEXY^LRbPKd0BWYL0QBN z7j^_hh=3NUm56MDwNzVcsR~6DYpsnHm#UGdXj`i`E^QTpQj0_bc})UXiv64a_d9pa zee;%(hrh>C>-oI<&OI}8=g!QX`OcYrOOJfqTQ`rbKeBD<%hp|5sZOSeOmrhGRxO8fl zy4G>&b**D9Xyl2oW6NqUt^tTi3EHE((T3c@9tosFQaM`9uIGH!=&`ltl=u>t{QRuf zfwysWv2m}W=YVeN(2t9haKXR91AUXx4y{0lX3Xj4TZ!~zYZ>j>C94p&zf|Y_A~SDR z=k%N%tw%!Vx2#D|{QTKr2Or8^e({F`msI>D_Yd7V4F27~+XkIE`?~W-eDu=b&F4Ke zD)Ha=lo+&Gs~@soxn$1c^k z`N?89=A`KT$obz4OwYnMBpyO-RYY9nHxLr6rXFQt^>zR>v6+}jH-gn8aBnjR;>?`w{go{uxFg=F!l@nI3+!v7Y_pHU(q9d_~(f+;}b1n2+-t6Z_5jjCRyx z0|!+7W1vt}r%YWq)4CPUa<8Cva2|_~7^rv7o&LXh9;Y4eXexTAQd^(pQAqBCF@f{e z!(l=`9%P;qVt;^J1aR?>Z7LHJ*q&sb490|uU}j>%<&Y!6ggfEx8eBpWCUO%K-h@yA zGh%|^8^gh{;k^#s2|?PKG!*|F2l~b|KVF!i%C34}5%eA7hxG+(m7i( zaoF^ET=vR79>~|6UN~rg-g?X3e7keM{o(+<5Sqz0z)+KIJ;v|2xAmMpK^^ZX0>C$= z{1@Omm}Q`;@;?;rA}Rl4;O^^||4DdONWw(^b<4k7JOda13?p@Gnn$Dj6PNsCuPr;4 z^3QR1hDpjlmh?Gfmw&aY)qfhdWNn)(w?`@ebGb_Df3W=9@&2~_J9Q@W7xjT}%fC~+ zQ0D3z{StA^LYla4$ARLFY)_vJj%Z=!j1xTM z|6J|-8&UtyT`>Q~dDG`c4*>q#>i;ri)o}WMA##kF%bTkI*`Z|C{~SMJeH5(!kA)em zO28Byi~c`ZKSL&AA~#FjvFQI@!uV$xsatsug=mz2>b!ok$I?{2tqhyj|2Y=MFiHK- zd?uv)K{;1h+367$154l7uESw~-8Zau@c17*liQAW^bp|W%^l6cCuSaz+{E@Z^NWz& zXTrcNv)}dsND2k=Xk$RQe!*kG0J=3XAhZvFoA4M-043U6^GM8&Uj9q|N6UXn6g7Zv z%m251fZ^K!C#3wN2s=#xlz-%GR&XT|m48+G-R@@F0R8($+y?l}e(|Z?2RQ%QD3<>J zHvNAil=5);KlOUE{%cDAKOgQ)U4rX8SWgA(|D$2{b@hL9PN0N|+|>Vh=1~RAn(P1P znliKA6#wvO0GZ~|(EpjnezN-mj-~ET!NUxb=>J$==aBLTr97bIt8#BUIZB-`-G0rN z`EORgzl!&_I=_FcjQNUrG#{6l_nRvB-;Vnc&rAe5S#`c$gq=Fy&e{G>KYY)lm4Ca> z;D2u1FWTLHCvARbmM*W+YV#LFSpL5q_lvCjAOCT`;BG&iwe9Xee9fbke{Q^MEB(#t z{4(AA8!_&$;vLQE|G%#MQ%?`4_j{0EBB}p5|I^g_IgSuc@4pc4zOLSXHJ%lcFp-aybB|mh@lRyorg=2lGkSoD6bxnY<@@0T?-46pLXF2Yj%+ZmhxbO36) z?w>bh-v4BKpYe`f(f_u+AHLjw+upa!pZ$Lv+WV^bO0idY8h`fN!j<_x{jvrf(>Q;w zY(LTbIDeh}+EciXZ{Cb43#Q)8DNfNV`Tu?W{4X|9=MTg8GwZ#k+Wh%&XVz!io2c{0 z!`;`d^QYQ*N&QQh$jv&x5<&&cn(OOZhd^{!KG}cbpJAkKP4j5f`RuFnlf5tfvDEpT zqt7r&oqvwsGrP|BXJ@Cc-*03&xAItcJm~vBjR%VtO_{l9#)5D00GWh+^~`J12ly=> zNXcQE{NLyPod7(L>}=qH7y%FTt;8xE9@uk$aB|Q8WSfBTj-F=lZJXfRHbJ;Kz{he0KZXVf>ECm^j}y0za0~_b>-lH6Z@jkA7J*OvWFq+V}gNGg6xdV ze;u)-)crCY=znZJVAQ7r{nwTKrt1EDAFx_)!OD!ufkeofq3?Duv8_i9l&Gm5RVQ>U+nn9B4Ol77NW z7?`?31}1qv2eaVu8V}5j$E`m=F!xsCxDF|J&em@D$8pKvwHm>5w*C|3pS&yhERZae z^GN1wl^{SKc*5~pUJM_@!MI|`)}b=&-*%%T1;)`Z4v2d+^s{htHcKSZ2rc_^j%7TT z=_JJG&K3cja<3qHaF9G4GGEU;!o8pPeT4Wt$J>P{PZ0r}^86s#5}23v;iO6WG_5Jq zr-z=r9pr$Qv;yLg|=`SDt%jecG)*|Jf9sc2V<)WhW zq56*&K3L#6@M!6ny2im~eZ%@g>YMwW(>+<+{9H-Alk+9-3o*Gj#N?h3lOH)ItbOU< zUCM-Sl@m_yblk|h?g%ki6=JeH#N_$<#yrO8=1Qp(rCwfk(e1@!YTj^NTC~1sN6-nO zeB!VA%vh%5r8}t=NE%w1c?ZY-hV`oWW!lds{zm*@tY_d`uqGc; z_0XZQT^=m3pP9;&Z+rCA_5GFhv*|odm2VtVS6awt8A3^`F?E)UA?R2=LVfGsRmXc{ z>aAfoO#-l zdGp+(UwdoVvw4lTTX%OI`AXht`V7@RbLV6hZQZnO{r~%De6Npwop=5EMZak%dn)gS zGrN5C`VBAUZQpkvjwt(Mp6ELIJ=+=^TNmNH3+OvLxwKJJU0!2jLtf+3IFDr=hI!q# zPiFK5$YCNKP_mj4}cE?QT4 z75FSvZUreBx4V|NT#>Z0#j2B}M*+2#;1oHaX|O4g||7ET?D=`Ylj zjNL$U@@ZC>WUTDw=RdJ&EpwcEcURD8%=Yc$S8# z15SsshAJ%N?29=tgBK-Wig-q=sRPQpf_1jhaJNJr0vC5?9B6$Qx?(8|QH}Dbbd@d) zN3hPe7zuG5%!R~1k%gP)(a_nb!}`hIW0&&;ZIaZqCGN4yc=##N(dXPS40l#Vp!*ii z8e-dh3*{fv!zRfMwiNEHieMeEr#uQyf5Pd2;)M1SL;$Be1sBtld7L^TbtxegF0HPJ z%BKrH847$v3Sht?tO3Wf@(@<~qz_zW*mz#&WX&`4EGtvG!-3_c9SU!)eCkl? zIq^9Ey`o`x>1CsqeHnN9rhWfd7+0Tp*_J~ux3IcxX}JEo)CNWG5$#Jf#5_m)8>;Sj zjyiQEp8rnW^88=CqfMyEh;GFD0glZ8#}Dz<>Ncj6`BqbhqPghGeZADE{Gk)w)^yK% z3BC9~swO6eeKWCTIP+{(veNtfayojS&QO|FyHT6IjOlV^Qe6GHm$f+b{j*ventEBH zx9z|ibze^X8I$n)dtU3BjVU!7zsT$NhrZ{2^rOAo=Iwmu`kl}GJMUTiU%&IO&~N^^ z^it?f$Q^~)$Nw?bYmJ~7EB2O@R;O86>TB75_aVPJeLSlYR>$8Fw+4MYBU3VBSGrQ% z1<79Ze**h_m}8@-jhsrl2-8|fYKu%5n00+6%I-#(v2J4x#*1#Lz#5OMec_8>CPa56 z>MW*zC8)z$7tlZ4I{uBuJ)olmOi??O>3$-B%ew$wbm!0rxVy@c{O;)9h6USlIRgYk zwq$uxWH^F#hvkUxNSF)Bdqoy*njbISVY2g*ueV>ngq899jtJnCdj!b?gJgb7zMgr6 zbvgQL6m(179lo|UPeNDyGmbM>+^QtO&x>%e@8wc*C^f3@1@bJ)_&7IdzFOP=Sj(HV z{J564lHOS>LCqNRy_|eYn1sX)|W4naRz~ zNy^TVNeRu@UCig8kh+WY7W!KXUq0ZvY)eC9|F*qavDG_xwKvi0uCjWK+j;(&KKU(b zVq)7Cey7r3hgj)W7uGV72d-|cIx)(w?zr)Cmgt&FNlE7P^BU9ZH--yd3eZQQ_^ zt}l8XX&>`mQhiKPk+)k-%S7`nsbPG00Y0?e*{v|SGI_MsZEH2_V}BjQko5EZvKn<@ zomKR3wX~tpc1AMQg|uzmOg&9$_>M&>?%R`=w^)(5GGSHx>bN^j?Dzn4$TzdDVA={b zRaYbdJK270uCAbN+fO_LCl-@}>k1G2BUUw6S1b?mPl6g;S3C!cNa_ln*R>n(ZLY3( z9|6yXJ0W?m$ihwY<5gF%ePL7d>xxWxOz)Woq%I&79=$G@c74gUi!4oP#8!+gY){yp%d=06Jq=CgeqmW~lZEzA+mpW`qRA+fS zXhjf1ONLuVJwu`c!hhV)kWgpJPMcqH^TOHJvOg_KM+KfN9aZuf^+FQ!Oeb|`{|Qb6 z>z-p_?GEEE7*AHCToX^I^8s3#)ICdJ$9D@!(F(?s&2SJ2o;-&-z6@@OV}gwm4pWz9 zzlo`*$$KRn!cFsN;0aVEgM!zJGNt?!r&7+8TPS^rVPc*ae9)QF!3Zap!i_4^s6;~g z2Ienh*Ff`q13B3d&--Bi2q;9qvYw`f)ooN~HS1$VnR{1P%;RXeD^MFrD7*S_{Fk%r zk&!y=xu5Yst(E*hZEQz(Wo$;9O6#c@H?=MLwYM5)vUe1TT9y4YO^71!*(EbB{5JK~ z^2F=aoFAb=i@z^Bf3DiifX0Bfa)vkne-u}KO8i|h!&A~myHer{lCM_(#p?eA;E!{L z&9wOoqX$2y%)B+~GE8G3WLZVTDYH#m1z-xN_Y8$Qv#joh%=%AA@QnSerho04(0hvE z4iG_jQpB<3NN|e!)|K)QxP*z^Y$M-EFoI!ode5B*_=REoGmO-&yoW+GaLP<0`pB|z zpL&!12Fk=$o1_-8rEq83u|*-o=UCS;%>3rWF*mpn?Q=u`r|b!m*+vG0g{VcU?TZrP zpOSz{@RLer&+iK(|Bz6OYfknTZ``-)@IlD z@$Wg%d)Y0De^qMrs%RK^`-a+UfSNp86g`taya{$h&F*;WxkFa#(uP0ZW~DDsW4iY2 zJQ<@VhMGN{R{EH_r5DqbIDE$L&suw|iuxFfCh2HFx5gYj%RSkdV<$bNHfqcJSr^!& z;zLwBme0|L!A`4IdQ@{mO!|kIiA&EDB=+4J-2@*Y3aI{mLThhN$=Yi5@pZTfEBnD&3$Ij+Y8d2N5! zY4-QudOvTLa#xY(p0cT+@czn|Qaf}?|Kru2^IBi`-uCp$MS0J^J>Zhj50~Y&tlII` z&ENe{)n$#1HQ)zuo#nCT{JA}B(=)!DmB94o_wI>V2Q*9e#(LL|v{Vhd26=($?>X>` z+h#fO_TR~uu;)VXX)&4RxE7PiAtu*^m|W?Y*mujkYn^`d%N;xM@zM~Ji$hGtg_v9v zVlq0!#7ZyLa~e3dfSC{81kBnz)7D7Ry~>VXlQGUxvqQRj%Y2?Sb-u}KXqN7M>+@JV zm!;E`rDPXOXva|srs-Jk70N%e1c{&H_NOINd!hT^VO|PzP({NHw^62h%iTqlBD$Zl z_iPpZKVoi0UT)RTFUq~O;_fSY&zTax&Xdt_W82mHZ};3+`&!}E?WTJs{%q1EEnms@ ze6-?~lIQRFJa5$e&jy{|Z+YI-UN;ncQZk@oTJ?tNMUQ^pv-kXu-)`UVkY`TUJ7+!H z_^2ms+yiO*V(;^~HgrsX;;KcSb>qI%ZSAE)J$AmW;QWca>vtw1UwxwTl|4`OU6oGj zROmQn!qETFNoy$;{uw}GvL?ihe+H1aSrOu9nPXz#F^#1JE_LkW`R|9AED14L9Aa`~ zh>4YcpNb{Fl6=XEhIOTk>s-e*ztayso#V)}ojb|P*M^u(4>6eK$8hyEk=2m*4 zN>iFN>>*C(wYb-nyKTz0eLwl>6$5%~%G;kY^n&}Qy_mPhJ+AbPN$=;?zxv#lo_GJ2 zci~fa|JwS&j=bC(|Mk*yS4_+M&KdnLo3M6uUZ-8-u6w0+ZQeQkr&UkxR*|>m^9>(f zHSM=~IrI13T{r6Qd0qbDOPe|L1vYUfzwFwVchxKFU;pREE)@;$?zwEn_z9lh{_4$r zSGB#?Gc!G7`IDokdw%fHpZ2)2#(26_m*vNweXeKn!sqv#*>7)N|LLbqR^@5^B45Kl zpV)TKs1bMlb9e_&<`W})4`p2GX%|;=S?9_no>>|DJGbw-+;c;RHGes+`}aJZtLKbw z)qjd-)lDVkzk4JH<%m?b4Sx&|cwHXTfn%%0Y}W5L>H2+n*<)Voz}=+_fz_w&;=kuW z&t(e~{~R^E=fJbeHq>5{{Nvs8l-a$d!H92vPpM}k!N-vyUw61;;#GHMJzM11NuJ6N zG4YS-iW|H3H*=zuZqHL=Ig@%e**kdT4+>&|vu>oqr3xXXjN3?=?I2}arIFA_zc$h% ztTqxa+R!Rn8?oGO#}~hy#qXo&_}1I!qu!p6CJg7S{rRZ%_C31Zz8hcKuD4&j?Rg+m zMZ=S~m8diqoojx`7x1H%d;vdRiAg9*h1UFjl(O$wgUVZv4X@;_p*4RfN`=<^R{B_l zB38Ox7YEkicKuF-VSWf-hue8r^dd9Yp)OZ-IO=j$rwj7aFY(i?!}$%ED?JBRs2oZ+ zZ|vsQKV0njK|J&u?un@XuTo#bEPZ}WK*Djn>;C~NkB@Tlg_S;1r6}|N zXh#RI+?eg0FJ;H`DfHMASKpT&dH+?``y|gPQ12`K!^ZlvJi+~t?1K=hYQZ@>T|;LS z7o}t-j7?4$=Ngvcx!9GGS&%q3aa>B*g5+CFA-2RX#TKByV}y7NUZ?!lYrg#Rfr?Tx z62`g`#{EMWI^&s4_KTb%(L~i!6uEX5PR2ZN; zPtD)ud)b%Bu(A79Xd~ukE*1e?{4@EVm}8?t^fyBUaLWCI92w|j(fULCg*9sgd7LL zFW2(DmX~OGB{{-*w>Dp|&6(F-7?kyp!~fCba5q)UbIB3DMOwa9 z%PY0KPRsXcd6SkO)3TaJjptv~^6T3E11*0-j`-DR`Jk5nqvb?^2JKVGnLb)}Yq^J( z`)YZJmW#B^dE0z`vX(gp&G?j%10$Df`N!mNw~-w0DI-TZa6f07bI&!puhjOtwf%l_ z_(x1&I<6y!{2)2}d6XQ_mudNVZU2gv-_-V;YeV-RY5ToeuG991waoDj`p+>mx<8v7 z{&&-ImX>q1T%hGqTArZgtF$~*%k#8+la|+zBmO_u@@8%S1UcUSjFv03{0A++tK}V9 z-lOIHTK+=IUuiiBMV$Vnk|RDHw4ABs0py6^P%V$p@>nfT)bdm<&(-oGE#Io;m0Dh> z<@>b!7&+qk967@Aik9Ed@_1cNCu`0+knR>}`4%lN*YaIjR``JUY^03vD|~?bqL#Ol zLw;M!f7SACEq|uv1}z`aa;z@53NH|DwY~!WD7?UX2GAbiDRWZ_)Ow zbC_S#bUEuv4tHKHk0pmcmup$!0pvMaR(JsU7A-40fP9yh6&^s|sAYu*kOOc4;dxuz zD?EU_TgwU$AU9}P;Q{1$UH%jvKt5B;ZgR*OTF%mP01n{&6KIZdEI6=OyHhxTbW}Ki zbWk_|{~p!ux01tN;Q;L4*78T>@OLjc+&5^MbvDzNW688%Pmbp|lf&KPT7E{`zoccZ zO{RUNmUn3TPqe&W+aJ{OSK2;Rm!}Tocs^arnOg3r<)K>kYI&@dFW2%^Ezi;N0xhp3 zN4ymtAU?m<_Ain{-mc}hwft8t@7D5XT5izt5iQ5-a@L9*>2s!*&(?B=mIrIOh#c`7 zt>sI#e2tc8X_@oz>E9A9FVpg!TK=(?AJp&)F+PsP!@l|8c&|%?J zjX{@?LtaD-bSceU@G3;y8eWqPK z)HxeLvL1!95W{~0+mK9+Xf_*9sdgjNQiyFWQYJ354M6>Yb}n2fy6U3r!DW9|+TZz5^uZHBw6?MKwVgozwb?9d(vm5`d7 zOGDg5adAlea}4y2X&#Ms9>e9Q;Qd5`Wu}~;!p)`OG!TZ7-4_*_cUB~ z8}~}E(%*FY)!CQNm3q?8{wvidDPvy0bb2VIXLL)5$>tD~O(7;$`je`ElW&q$iFQx^ zuJ; zHyqp<~sV-8wv3y-)Cyjs8XGV#gk*5Z)oEWS_1 zZesSi#F)K9Pg@zDx}mpOy>G3YqEbZC*uQ>d>A}q3*!|IdyV=Fw-Lvtv zY~KccV9(~TdVA{LP(AFe8^*T(@N?@9hJQ?5jEixTuyDkIAr)ET&5@qCYI%pG0%IX& zi~&aQumaORdkEp|{p>sW>dUbgdYSq*eN|le#b{>w(OcOtTrvttS5H)T4T^oQ;=fc& zdh&V8-CccIsK-dlZcb15Gu0i{lXgnT+kS!do~pE99Jtr3E$2P^|JJ-TX#C!lZ~VD( z=(9T?d$9f6?ebP!@>TndF%$C+rnUk7BG2C6Yo+Ik1BYKZXWqjxUoGo7WB3{WLjU$| zweQzWLvHT>&p|a8$oig}XBB$#d#}X!;y;%b^yZq;9|FpE!+jmDBo9yl*Y0gkZnEbK zaSs{ByLCfdOMaVvDy^;b{wgk3Mp31ep5v4`GxuNf1Z z5Nb-dSx3c$?KLnu=M_%3`3x2w*a?Z(!Me>lRN|~#o6~JFP}fDG+py0g65Zy0^gWiK zvZoG#>8L6m3Xj1u}IphFP!2fVKq{ zN^~!0Rc=6Mu)Sc*u?y%MhTUB5siyZ~3)qIE@9ZUxO-R49dNIOs4KD6`HcxYgk@8A% zB=}ugzK{HL-7f_D$F#lbAAm%oTSibR`>Nf@-qU9pZ$CJa| zL@m$MTek^?7(J#804WZMe~y8^G0me<&oNAX3SReXH*m#1 z+`2u+g<)cT*Y$)dj#5pi+zC5Xc9GyAWq11Q>mw<<*?s%>wb$%6-*>m!P9&%7%3eOH zPxq>gUt8wOUti~&vfiBG9`DWiU72r$tIjveRlYxdZEAU$ZzQDIE^6SbpNz?DUun;P zYu}S5i=Q+l>e~OPmM84zH`K-^e~8t5amjzJM)VD;TNeBn8q5z#3 zFgiDAv5iT=m&{yArnWo0yx|-ld>#0f(E9F z2biJ?{7lh+n3E9Ft@jqJIpF_%|B&h(igOBJML{##!RaJ~N3c9gcv-Rq6@* zPu!79TGEDNF?Hb7zj^V!3C`|ul*d&!aT%p+I*50H9DJm1lj>VHxUkOhScghe zD_WNf55_3ULQIe2KAvIgHnZo=UNj?mXmj%RN|*d4IhFaq%#$pCqziDFWvK|V8<&u{ z8w3LrM>xhx|7d3FH=`iKssv0CvSLIyav$7Hv>#Fb5+-sJM;?bz1~cN9V4{S>#F48Y zU`Wv+@y{{PH>PRXR=0lMm&5GnB>Pa6RU11;b$P+_ zVEaF-oul5Y?pkLRBo_BAOxxDUYjxY8_Ck=pPrdh3$bKtsd@~_8GT+JF`)MX~N;Ki_ zlp4Eb`U*9rU$sM#q%I~{LcF6}4=&?zwYNPnR7h}f2nid-U-i5 z|Kwf4`c(xiBI)0xLbV(3Y)-%04R<+kCnWC`S-5E)4P0cn{G|IUotK36U;5p$K9O3? zHszdGrjroUJ6wMyy=NW}996I=4MnG4Fid}$l6Z6bbn%r{MQResy z!ztv(O@2!1?eWXwR-D*<=w@C&C5lLNsXB`ypH!)EGd z6%foZ1@RBg0?0Iv1`Y+J5fX`If#I_$7-xdzB&E-ZYd+UW1aQjTaWTwpT!K3&_93Vf zFj7GXV)h52sb;y5aH{==L~I8+td4j6l*JMCV`WFaCv~Zv*a29QBz;)eonguv^kJbd zYw~(xiu7Nl{*FCRN#!)lLO)e|?7fhtdabgaH2bKM(8uNP@k%NW-HUEC6F?K&0_c~z zJ+xnHTtL6n*noa1ufLOu&$FUaqd!&*ze~cvVZAQ25>IP!Var%o;_312V$O&;D=saj zeN2a#j&Yr0&W^>*+ujRrzJAe^so;wi*nF1Uv59E)=J^j+@2Ly*?ooET5nm&E;B_it zm)W-?SQCt096w{1aKYX&w#iVtV)~I(*-l_bra)C!Z=fHv1c}CubJ&9`m)- z-oyyA{0r`Ui(~&oI0l#rhhvx_GV^+5`mc*)efnn&JeIwEv$Jv{?sL1!u0R}pOy&fn zZq30y<4KimMm~hz^VJ1OAH=({=Vx)r@D9I=)pv3AjfE{o#vR%nx3=J)A8y5&Au;d9 zx%X8k6yIMEQ)#*PR{!?MvN})8PcToivGL=j7@Y|jCv>CS2(kPWro=CgDRym7vGS9P zY+o;tJc4B&n44{z!_Z|?wVByJKMrQ5 z4z(S!>7SkD?6a!i&Y{D&o8m}z*eTMzsYA8HLlrQiu0lPE;gfKf{=E;OE9`{iy&?-Y z&7+}1F)V(Hw=iAF7&o)B3Y7+F4~z2}U>8Hi(QNlF*O$D+>6wV$$PVCDkM zJd32?9vwuH&P|wZC!m8N?6*JsG!NtC+9CYhCkxWN=T1(q8dnpWcuwV$z=~Eo z+T)x<&hSl9Gk)jS^-qZPCV8>*aK5{)(c?b2+iH1+2m4k2qT#FT?nQ-|1K)Wv=P4a7 zxBodOnrG)g1q|qG>I7M6E^hKu(r!;&p0FZ*W!$P0+~361j$We;aXDF7l7)BkGn@Jj z(^g0@f|z4sL@q4YPGec68(!i1zBj_0?+_CIhQPq|&jSmV9r|as+k*SPD`6iA=ENgX zk@S5R0ZZs7@#bil(+=V53O7P_(GbbcP4j4A4#VUpyRUn?V-TIbZ-$xQTrfyMNr=M3 zUMGbz_WryGSW{Ru8z&G?jRcF1VT~i_ihvv}5`Bhq9C@l)s~s2D#Kv^2T=+YyN6Luy zyT-E_S>Kp-q^e|iGS<4dcFo6(fs)}ZN9>Hf(z1GrUB@#XYG}+V86H2PWH`?_sQr?? z+y7h|`yZ~43|()~N(ICI<99gj{X|NKQ7QV3z#HNSKc$H`{`_p?2ve8%V1IH-_P*C{ zb!Y#@>wESQm^ktQ$}@3+(5j-fG({B{~Q>|!stVQ1M8jOf$9@3GAl%I&Y4 zNX^fs{Er=<0E|EphAu&>3*slB?CJx5u@Cw@HS^+T?wDmC0_-;nV>EZV)jNOug*YjA z(Sq4iZ(KBEp&f+?{!f-3A>~@i1k09`Q3hM?J-9c^4$Cj~1|hk>7zU<04`h~WA#pbg z24=Y)3ptWn)}t%fwNo_`xy_0gZP5?I>hw`{T<2gpJAkK~@rq@Ujy~_S%BZA~9mUO10kd)v&7?`DE1Z1~30+&2}KJHoSgw~-gz;6 z5)QoAp+yi*70sUEvnjYd2g`O1&tk-HCFNTcRY#LoSu|u6wom_KJ()1_I{UxBTtm}g zvO$smCZ19lu3QJ#<4u+8uUn5FOS$H|g`|EZH|z0ZDc8hQA@NUS;ih>s>T$C^BIp|6Enr_>YGGkbWl2SS zBUbn9wwhbr(+P=xqUvd+MDz+X!hI^$(@aMpsegySz|7NQA-ly9xVQ_hr%NNOr%T{R zB=z)WxQnEoelEg#nmaxIH`mkrR!%+5;_0uanMFg&a-aUW$27}ekQ_GpjV;T>JtWmP zv~CVpmV@i&rpj_~-OQD@)Fr8hQ*&gQPr?=4#y*y^d=;J-5_};y>*ixA%m2-Fb8uM> zteaIH4Jpr3H_x3O;fR0V$XA4LWf91!n>pgood{yF6M=okUcB1pYs6FBQ$SYE$=vMJ zCwY=&YPnmvktbwsx8MEPC(SwFd?vk1++^-!AalIwOK|&~^^DMB+&DWAq$Z4wPZ$?> ziJHyL9R{w@cZJDnPIpSu@z)WY9S77``9|moSx94M2kF0KUCneClKMXr24*|`K3MQs zX)6n6cwi>w9kS=GBaQjxM^XA*%7X_Z93tYiM zzj*?%haBb?Y4Zu>7}975Zmw+UGayTb3Dsy}bM2LZj`QY66<@@=Kn^ChL@tau?u`zv z6zPqri_;1BH_ceEaQ1vOKfdOm;7M<5NO|FRHOqnA7r-2DN|?|jj-=78kho*twfIH5 z*|;#%!y$1;Zt4?VA(X<5x(hb*Qy9WL8(fw*!`;c~vqw-I;;0?6z9Pm$kE-c>0Bt`w zSGf8NaJtMR%Kh2>`|Hicn$P{y?PPRv|7pO&x~JL4{_+9WB@Z_=_HEna_OdZG?=0$5 z71MY0&SAxI`?klu_qlZ~`rv!`_ps%jyytuS;w)bK+&;_(Ed13|@Z;iF4=tPaGIkb@ z%PBZmdU}Wa_s(*AtK^1Bj}lVukt!i&JQ2Q_{DY-!@Rp1C#@7z5oPoFfE3UuQH^dyD}myPM)H+ss>$?6ednzN)yok`?j+6z(R zAZ6k*HIw(zB;vEIiRp$H5#|D1d|VKSdxxe%7NQ%{7+l6{tWpR?%Etba_ZCAm-y4sB z(m%de(2Rawh08?I?eH%W6g>=gbMdT@go#|@Ks)Yn=!PNlEaw$4d<;i0ir$HI@xok4 z{1aKYX&w!Yh~e^+-DBF%d5NT^?SdK+dsO|D2(8B^#wkYI`@b7g+D~yRl+MH=aEvg-4o>7rTj&IjzKtJiujjTTDo27?#ny*hju)l{>pV)KCFWaAb-Qcrd zIp7+*v7xd5E2s^&Zo`h(*)g5l_Cl?2_UYIS=Hi{$Ej_(Q{(_>{>f0sMc&sjOofY$C z+=19H6LNm>Wo%6QqQm7wd!6|~PA}FxX}dNywDrDT?~dEpkmE@?Vjb#zB<{d>3S&_# zq#Q{+SX5)h_Vn)J-Yu>{s=a!+98Y+#dwt=no}agWt-fDE#3t-&VR%h!3+~+lpT9`jhN;2l7S$xi4nqy_RCP@M*msh=e?04OxrG|w za7atG6Vh2|H*QYeJa%N6`8P(hBkZJUn#}XeS|)}wZH1)tXTre5(v7enc1jD6?kE@F zva>2~Ksuvs)(+y8i#Mhu@#^3`l9Tx*qUZG`xo8yCa48?KTjLji&p#{xtcS-CMCf&~xCm(x-|$c&{wF2d9BF^4t)d2J-9TD-_1kf4-YKI9mij+a#V( zP+BOarVHLP6m(sx_TZ9mhMp>Yi?c_U>{qiS#N@jnCO3wdEC?~-I~h-_?#$afDlFG2 zH*!8jI#MV;26c&U*~r-!_9-2FTF$EA+2xFjnaaGEC&zoQbW&*-{G?m%*J^)frjWSs zo6^KgyTE6x^l`;@PNKQ_?S5W58ehvg@YB*_zEw@kf68v!DI!!@PSgA$IS`XOQZNqxASGn$^ zu`#dkfsMo?p2LB2*Bj3nIwZfBhwIUJMu(Z+R=Rz13BxYm!2f0NRfo|=QcqIGH2ZtC zouhiHbYA9NtG<7CCx3~rdV**GeDqKju_$2KT7QvF|O z8@;I5aqn#Nw{MC5(QD8m@~29hHWy*xHxQzZLkiZ1?uWvV2E{^j2tGo$9$cnQkc2wz za+nE;*X#*5^`Wg$NW$qu7s8#X4^4)Dk?2D_Z!nVH`}fgY8;bx_AENHT@P*Tdx+1VQ z!cNGHqnMGK=F!lH7%o5A>u)lUAU4@&cJQn;k=fpUP7)chp?oa*6MIgDM1L~nULt_g zo_m4`Q64S=IOR)&#CK6fgMYo|&uMo)Eg#XGd*re0tj^KE^BI)!oH|z(+@tNe zK9T0*wLDSFTtm(0=W6*TE#Io;)mmPs<@H+Lq~)#TP<~(0vO0$Y{;6{~@V@=p{2)2Z z*(e}yMUHs3)7-830Bt{7%M-{EuesV>o#Tqk!o6}CACAP+p9(F1pk;OL2Hul|JgVNK zc_(uCr_M>n^V=zdS8Dqjay+NbMTPlS+B^~Ygz@A$Te|P2xjJ_P?uSxFIJ}yV*ZdlC zJg3gzz;m}!246#t=kC>9owJJP%P2Elm{cf)Y2?5ZL;vrK32zbXvlw|FdK$hBC`A8H zdYW2UqNx+~166UD;=f?G33{8FnGI<@8=>Cvuc~{s|Mxx2IMT;3^Bb{_ zN_YIW(*bMQP>=Kt?NDGHMH~L%8Kx=g7?mfGkP2Ir}1 zHq>GzO?lcG=#$OzyXu1TA1!yP(+iPWo)WO8{&Sop5|8I>46~C|ue}|;u0qz=qrI?{ z?Jlmf4|lGgiE)p^li~I`BPSN)rbe$Ra4NL}%IuG#{)scB;C8@9fC2Mwa62Fv<358M zmLDNv2q_rjsJp820lTAN9QCb8FpmAFkziaYu&WO5B)+x6)fC2+z@j(oh3sM_lAoLA z#|z_DJFg4HIDQY72b(0dZ7E#8Dbrkt_vY*d%H44>PW02Sr%w%!d7`9i4SOn{>4A&b zH&%0+IcJ0*upt=80pti)6lC}77x6wthwYEzU?ArxRLUHMi?P2)PTQW#)EtG3s+gRy zJ9{2wEVM<<1v>Y z?v+C;r^IES(;YJy+HPuSTM&07_P~#~{lR0oJvDJLm6)qQpNYBTNK%8Eo;$!YEL4db z?8UuY?~ODfCG9#_N@{-cT=id=!f$^9`&EwTw1HEmkA=9!bQhA+$?rm)N@zNCf-DH4 zbI~1fn0+VA%G4)FNf7v*gy@EJ5iUE+E74;6!eig6e|hgHNalOlcS8U8UUZKrETo@T z;xhHj%i&)n7|hwi*Wp*{x|{K*cIIp)YT zsKh0htzcF9RwAD^fTK+9DLq;6%bYW?Ov`tZqrJSH9D!rHgr74oAX{(L64{&q0KDzK zc^&sY`-409?w>Po{@JhEv(Wmz3RG2d2C`z@Z8L$ZZCX`XnFBaypiAMA_=bzqw%50d z|A)u=GOq4$`PrGRKgh|%$Vg3_U6|8Vh&f%DJr;K$5wpeG7TRt&ZXz=SIJ*pERRuMk zyW4NC?-!r3EhgKYiMeG5+HL#9W2MV8G5ylES#FH`hn(Hg3F#*EAZ||Ln18f~{7)(T z-6)9+E+sb@e<#C&xCiw_xuHAC`MB(?h8xiPxL7WP#J>w*VB+d5SfFSq|4iMMIBnu; zJUovCS99U+8hI(Wgo)h5)y43<0%pW7i3`KQu))fqT!imrwBL#MehOZ}%9Qd`INcT9 zcn&dM=ip)*u>3f<*Tj&&0yZ_`Z&|b8KHQjpp8*309SdgV4w7k6&12SQcqhogEbdol zxsSf<1oPK%*U8j=a@S8;Gz&BDqu0DWX&At=%{(EwiRDYmDQ=y6sWWLt%Ejg8jV5`9 z;~r+&<|+^=Q&3Nof5eJnTxQw69C9RO`%bu{z9q!4lgQ1oy%9ng%vi3ER<_3?5bRqJ z68}UNZkk6!XF`+Dpy2sDOesHwJByd|c^D?9yDrN*Q#wsg$)rur)wzEDbZ#iqe1BSY z$!ozIFocBC!YvNmUs{Ez5YfW5I+-}Z(IkzURWr4R? z%@TP1b4$$+;TQm)wbJRI=^N$20sh-=_@sJb8_$j-?waH9ZpcE+Qw1sR+mn{JSdq9g zVO9L5yYXqHvFvp@USKa-dKF>QqePl!(@ zp74AU;)j%Jx}zN2ueJwfW*Ei4^I>lKw;UG4C;G=U5dTKw-o&RgM9}n4;>&SiNfX>! zqhS$AzuIa%R0;RgJ$UiG3`el;aXBo~VJ;-^6-UV{- zOz9yo2;BYdaLE4st<+=oALDys^b&4h5VZ|+P8pqqx`vs5Sl&t0HOzcJ0B zS-5E)jWTbh5fO=bSkhW#|95C!M?trT`aXO{mvI(RDdNnmA!WJGfI+g&RYd(DgG4on zV7HArJK>zNOx*;1#36kRX4z#PI__oHnLjsg#*_t9Z?>0+&6wMJ`i!YJUOQ>#f+^SI zT!@;=Xy$*3F&aRFW7)Qf6Anws9?<}8wibokWaaJ@! z+eNrK{R~(!&isxn-|SxyVmvYa?__9ysduut8q=V&v!zbQM^A&S)=&-1KBm5f>>TM_ zXufYD)&58UIDoYT!`Vj38^N<%&#kkDuPW&6{h2zY13j5*+W1l*OW4(--on0GrK#@1 z0q^u5aa%#+u9$i&Kju(rn{hR+m`pXppQBD`FI-lW6qi|P_0HRQ(J)Wd*vd4_2T$4- zGav(V`*S?^6kJfrnFTF(a0ar>8kX6}Io<-V-TtXtH4I_GDuq?z#%|lxt!jx7#&qM@ zn9N1yJ?AF#{Z_^&?+nM9Fh0q(2QThaGw|Pu8JbkznEPTieUrC|kCnq7|8QTmeRfFb zZoY1QC`}w=MjL2((ux)<6IUgyj=v*r&53OT&BJMsQ)Vuj5zQW$Qwt}V#zIZuWCp5W zVxV9P-4Qp7a2bzV!E2?&KM&lQxXU@jk>KQFcpiyf^f=s2!8?Q`Oynj`)&c+OU`Cug znqIUU0Usfrfs22Jk-9a_j~7mIY|*B#hnw;=(>q-RaLP@MS20hB9wi09!BwZh6gYwzoE^)(B|#H!?nLk=6^RkE0Vbh$8c^5 z`}{!xSWN@$j?@9C;dWpXt~yP17ArY^_2<;3Z7Dm9|m8as9HiI~H*6e8x3 zg7rAgS*BeuK6zl~6d&A=#pT8&B>2Sfd=sDKY!dos_SIYn8Lujl=XnzeJ~5wPEf0Z9 zn8;0h+5@2yX3gOf_12Tom&|baDR^x|u-v>}$388l0lzWvCU|@udYxU=r6p%)b^P0N z6wXGW3&w~(17#OAd&H=@9ftbmQsp1T8C#8LHHNHLijkTFL zosAmVF4(_y7|s8Tiz`i?PgbL0rJm}$-lg1Fb**osjz*o1PuV_L71Zxs^)W7lIH3pn zvXxd>d1V2$#6KOjvJ%vaR;wH4OLgJ%Fq_P0`4)2OdbXS2Li_B!!|LIw+gnNvakTg2 z!*e%v-!&b@*j3*+_()Zk-B$WfibcDm5A-oGoR7c5HJLP*5Ly{!l^yD0TK~H8!Rj$J z=@TDoXdL{kI$z4_{-x$@u;5^%-M}Va67rSqy;imQ-xJkUd;Gun1OzyVC z`o;lP@8`F*_g@dE|d?if45 z)3IHKbzntlLc`g^F!SNS%bw&y?-8rvi@o?Z1@^ZYUoe7S#yzH{>Xx{DZ??K0dF6uY zd^~$j#`(JnMlxO_JKp6%+}u`=AE{8??QQRUwmP@?jeT)(=k)AcK-g7cqRxvf6@VxBtA`Pc{OZMLF9a)`Jd}T*3!amhIYcKcm z*`3FE%$&Q-@fOl2`rI&Rf=iWw|F1N-PB*cgZTqn6B8R8s#x7LLAIGYH_;=#!{sl9x zzv0IDsQm52iYCrjKp|Q^I;YZ@4bxvJUf%@k0eheXOokonDZ1fBy@2yT%(|BCfK-?X ziC)2ZAav&tJQ(2!{(dCtv!=dK1cCnXy+@m`Hv;~dc}m{JdeDfT#j&UBU?wE)%s9}l z4pnRk44H2^myPjdI2bn5zsZQ;a+nE;e-&c z!g+?LljFm1ypb}`t9C)@V!q@0z0aVtl0S|(hnsIG>-F?>^5*9N^ozWIt;klM1N1Rx z&$~+>(R0AS zg-Z&~Dm-IUajU%KE8|-nw9do(V~1nD`McQRBiS449fZC(2}AHa_`;g)H}K6bbH^m? z>nGaS@30?$)PeZKpr+@iXV?zZe^-3x;Jxi`Qv2DBQ2!^et~-u9+MPOWUe*sxb0I;= z;JS`;#IxWixUS>813oV8%F7`r?9m=dT}Ny)USrLIz;>{ZymurFSf2=O*L`=vb=^cb z00fkXyUp+~lDh5#xSJynflHXkB@VP6jR3JSA#l9^E>A+i zp-QX_ni|_TrprB^j%i(L5@ImZyr2JBE91R){!ty16N6o%T2@+}-wQ(HlJcUur4xz{ zdfHi?U&B~P=v*+f-|JCCY6RB^t%zHBV#hzCJ_Y@x&GnG{FTGO4CZ?;9l+a+D<$6P6 zCd)V7@S^O&WoI|sfU0ouSt0Q+xNmVWELcA2AHyR45syv$WWRqT_&EgbBI#Sa1)f*p z9mH*^GZ>EGwgPdsE6jz=IEop$X&#NX0>k7dyDxFGWAOF*7Uglq^K4uUGrzguU-&8M zRIcrOe;3?_n+MisVE<#9JCdD~8}S+%UFkVGE$5Dqa-ZheOISrSu9G*xoBsm(8jB|2 zB=x+?_Sm^=fZ9Ebx?Zxkl^3fQ$HjUF3>w`qHfu#e_oDAqc^bYdxvijmRj&~%3I^}A zx}UqNYh7be*Mqy`i)vyn<`{5pId*}An?3KaN3p%5H|CZXqIYvcZ3m8iG^T~@fstFD zTi&L=f9uve#m52J^fMKGOIG^nYF{eqqvDTC`I8jJAA248{Wn^xhwK@6>lFtMzjDsJ zhw;hA7M2ZZY_zO(L&B{;H*qo^uCbQ#_W0#-D^4sH1)1K_PvWSlYpeGzoTLkb)5+mnMAL9{FKpU ziMx?tbf+dTIv>xoObdA+gu`g|qnj8#p$Uw>2=2ZvMqeX=0GBY4e_f0=`!vKq;}z=G zG>-;Gv)=HN-S2H;G~g@%qg6fQ1fqG24!7P?-bW1Px1)E0(K%uXZep~5igYs&Jq3%I@Ahow)Nf;ch(4o#KQ0(YUg335kEiB@@3|!NLtQepjIA1FJ!Z^U|F zuAT4!IFl4`3L|waPXYhUGZXXox52v6BoE9()`T$JLd?T@&&YxleR|@U#IcFvQj&_^ zel_LzW0A97go!_U=Im)vJ&g6F;SbZ5pH6Zr%Qnq~1TTnFCSGuV2DUGlZ|R0t5-u+; zJ1gJ@G#!_zchDWF0GH|CSXi*!1mn-eFf;LIBjiZ%=Y6=FhD%7oL~i0wnt?wO7lwmj zgOx*vA$S}qFph?CK-{B&KW1IPR1Vgc%y);wmtg%!@P*%)c+Bnl2b7*KYPZE83X(GvzxwZE{5!_#{DdqkIn|DDy%|=kv6J~jW3)X*?Q9K z969p2`L!pU6Auc&CS{`bTkAFoBhH2Q6s#yaZ&z3BBiWMYSQw+l31wFwj{kC&>IJkg zT_z@ja}OV=jqP|&Wo$9MZ?HGr(DQrpFPi?3@t)u0pJ=>ao^B85er&?^@ zsJ2b$YJ0T`8~(oR{COVNhA zBzQO$?yj^SQU4MqauW~lBk)qAP0g=tK3DiSOVe8fzo zNhP!A_l41QGZxI7F?Z6m`3wC59fOG19CztW4%{3;o}%{$Lg1;7v+cP|o8P5ng|A4g zV0>K^;d*_jei7?_oc{!B0$WN7}T;A^)Z%UED=($G`^#alD6zWpRy^O z?5cug|CN9R;^Y{GklvK|6R0~P^}m60Qi*#^U!kTjvJ{x%hNI>%l4Xy63K4@y!5Fy_ z7A$l0k0qV%`0ikg+zqoxFp}q`MS_uIfsu9avpJ0PAV40t6S9kmNPcdbA1{oY?7Ys# zOs1PnUmqj+%_G4`=#YdRS-IkLun`kkBK$gIC??WA7z2y&USi+`&5we0vm)ASseg{% zB&~T}GTb`m%BQ*dq+rx}N{<}kP2FYnp$>UI<~m}=^+?Z7qL`IF*cmsdEYAfJx^@jH z#zMr*RPWYp)EnD-sUcRDKUKeAQlFjKaFM%9G{iui)b@|sB4$q(QsO8IRy<%XrC&N* z?RQR_HVstVR$Stkj(k@<~1e@`qH&x#%xcSM9(j-@o2c*D4gj@4Paqnbqu zb|+YH9_)x^&AH2ho8b2{O@)Ywq+orO`}wYhc`z2|!OVEvngD^%3Wy-d`XCl9xN+XJNY+%NgEZ3ln4Fsd3eb^> zr`%mV_i1~FzE<88?9hjKlKE%vJVWi$hduXj#0TaO#o6d^ya#N$-LWTvZ7 zyuQfXfyoS)pX~XRiyVXK&9CG)C&m&(6{Lh{ zz{E{E-z)4xz}n#%bDxJkxuTm!HfA$OhK3{9n`^%v=KxHCMi(*;)5=L3J5L_>abJI* z;H+ryeDq#Y0hC_1Ca&4C3GL)rom{16JX1U0P?8YS|{!yPZ{d*4ng~Nog za0jardH!@9ns+UU3-VQ;yu>`hZO$=ynJ5~RF3_uYU zJ;0uZsS#kFau=@r_sQ+A`{Ep!}ykjkd+8uISBrs=jeduiE&v z*!gKq&W@+*y^~Jc@o{a>B_+P|mOSgTmK^l`eo4JA^+?XH^8N8^Q_*wv^D$kko~kb$ z(?j)K{mW;q!L#eje6w7S`jXU)-z;BCR~?>R?JITt(s!ORvob%bq7P5{Jg(Go-evjF zgj1(Uv5#p(ZR<5zc)q5Zb4O@0%a^nUAyB^O`c`Y7lU($55T2!*_pr|QjfRmoq%Ft} z>4O?=e4F=ikGUnwu}%VKP9=;@OcxF@f`dC&Nrg{0pAD%f7I1 zcz6*WH1Tj2{EI{<;@Zn=--z zhSQ1Ol$Rm2Usp%sH>QphjF0Cye%tBLCrD;JCS>F3%t@*=IDo3l2K$<38p8?;Z&-lY zqyAwA%v70aAGbY|{&{h+UuYsZ`j?2r>_=Lo&F|9kMlEk8hr8|MNQ8FaW}8jxYX}^N zJtA1wJ0S9X9=OK@$ieFrk1M{v;OeTa^+l6L??lg0&b7WR6F1aeh&}x-?15|W$GFGE`%&P7!6$-` z0-pmu=Um^zOD1;O;*04~?d#lQldr|#PkgHeKjdpM>L0#Uqc;0mOx)vJHRoYpi#gqV ztCr04ojYe}rDs(B$e&vsif)3<-L=+|dwpA$Bo|q|u!oWByS{5tn_RmjW2YTH;(l)V zhS~v3vV1L;p#GS%)wfsGFF1ixHh6zvbwNt`aP~6 zRX?d>%(wE%M|{=rxig+juKJfRN!4F`A{I|viziksSzO%+Uw-c^T@u%2K{eiuFferI zEs5zuA7`OH+1dJ!dAPPUHhw(xZ?jhnxnf801^usEeL?3W0$*Kp+ z&mDRC(A>NJQU0sP9vk}Bo1;Z_3G? zRy%Y@>ydfa-1oh_9e5ARpE>U*O*{dA4u$>XtnXu{X7yulvqWjGf7d07vt~!HxqeFN z>P&MXsY^0pVCvS3peFJ=@!Qc2FV;=$o8#kx|N9{*41*a-{42)2>5lqYICrdH=uW5= zJZ4yg#6M!18NNFaKKjS-Fu_(@b-C~_lDcj#+b7x*{(SN2IW4fB#jevj z&Dl`fY01a6oluW;LfzGA$!oq96Z!PRz7=y;`4X25@O7Ot0JY3YVE=c4@8|hesNE)$ z3oW=R8P2+>WcbImt(UYOH3Rl%!S799#&x+eDXzY~@lMRx+;-_Dmt0bI*p*j*SHEpz zTRfe&^O?8u=Iwk2DobfG>VU^s-b^f~Ec7OBj(ht-EuGz1Iz7rECJ@7#A30Yqu088aaTqaJs;a?;;$#L{6@T?F-MdVT^ z&|nrkuK;J;hM3e8PG-Qu+|y0`!y^G?njbHmeB60s@Yo4c&QIaaRFggvemi@tWacCV zFM?ZkmTg+co;G84Bz>ZQqOU!lQDae$bYRh+PFs5ZnLRsUoEGTh>b$f4$oBbd3OZGO zT$`pe#Y4UdrLDHzW%Y>Ph5dA5dD>c9ksD*UHmW=cEQ^27#+D7WtrWtv40!eso~_5u z6x2Y|l-^!4ys>eq(jAdZrLFMS6qeixyAy;ZNce9qmM|TKn!=I_IB<(2aB&xmCA5eH zOLoJLNU((S6eGcsj0myhGq^idu%r}eVAI#f5`H@eO9&4RmZ&Tnf+c-&ok3I8ZQ9&E z*@I+RTm)mRtZzUedJXnNzz)}H?QJ1WVpjUb(aJS-uoG0S^#&B*+_KHI6p}LQfq_|9 zj)v^UB_!^G=UDJe!Ej|ec#g$fcoa$5-UxS*%&~Y5N<$gkQcsY6PzeWuW^!a z)yReY1bezTBJz=%lgqmg)!kpw-uM9hL`>gc%y83C(_(PF<{@>sTJ3O|`akYC;>_Q` zik2wC$f-1UgJ~-y*pLYWvkkEt7FjTp@=14WL-50yShojMG21 zd&IxdxJNNB0aLUa|E7QPF6!DQHc*eaN!*j9fpPR&oENA@*WD&z#689 zpX@ocPGaB<>~mte*(5DSTM9RhOScRozcI0gSR_Qd?jnFw4xVFcq3;Db-+-xr(Fj@O zz!3?(@(V+HhNMaj{OyX1;}RZnL}C;0pJF6orEjGQ3ue*+oxfi^8Sg-kai99OAO`2Tl2HGY`8; z8SdIpI}ULghd7NxoW>ze;|7BxUgHq2afr`2#A_VlGY;`m7e-`adRUpe)ku+r7?mPM z7GhM27+Hu>DPm;J`P5fBXD{CJ2u5BW-?pK)2=6L#aYTlpDpjFsi%@yi;KI8-E?fwU z2VwCb93F(hgD@zLFnACa55nLd5^SR-J#mIvBNKX=k@rzZ%dESSf_Fs#$h(# z+U9xx#@q8ce6swRkv`X;GjDt3{3kE{{j+zpD}P~Hj};gEaQx>lzWu_VhVHxWk(b`T zF>dJfI|q19U-i_>TMBCnZ+xZx)#NUv+uvSy&afB$-|%7i)6dy{#aR_aHJjY8-tg(B z!s67sUcO>$L;m{@jNW$l#?CKR{QI;Qo*LKYf`=v+4QV@X(vVj={iD1^PR!5=Uu_y% z-Qk`KlJ0)#r4^UC@)BmfKQ#NmhZns5R)-goFTFeu*S4Q7{cia!dGC5|ZSkF#d)~9@ zm2-xDSWvw__toUv{#y9Q%R3j{IV1hm`6E6oysY%*SEfDMvM{|a7(GPgLb|L+w`N434gS;FQmlNyBzB&u^%G0xAE* z;E%y^;R`&0FYp9X{t0}6Cy??_Al08h&RjNlYyFZ*)xJ$(b2D<+MCRZ+->`{$k;`BA zJv^thVQuLaUpH5OXgtZPte2wHv#g_cchq5DHOhIZF6S(_EP2eKcA308Y?*wb)XJ=A zIDnG5wgWDNeJ#SiwgWESBkT$r5O#$P2)m69utQweMpQB%#<(WpFo)rJ#J9zTQn?=3 zu%0DWN-Ik#OQ=ygAG^cXJ*0H@fFD*S%VyO!egT%w71dwhj%AdoLz7#ig!U-$6(F2b z5ud3&a3PLU5x=Q}!4bEq_%2fsx2Y4s5x4)(-ur-8Rb6?*=ib~KVgfNLXhf=kPz@wP z5&{I|(5Gyi{WGY%mXkP~ZjH6CvrcUeA`i!B{dF89tv^rC! zwQaDpuN5449H&7fX;3=DXMOAU`|W+!KKq{BDF&%=qaY;5bgfH@p6!SAN5_I>h7vo-GMi3LH^esIMlgBm1_q2=HiENA=kyo zeQ`Q2-lGJIQM-##g2gj|QG&%N$zqgX@lC*+fKiggJ^E%}{Ld;6{&xk+RQAMm(45Or zGgqJ;gwv1z<{Gr&&Hr=G^R1}GqrdU``Jr-%NJsj)^l|og_Hp)g_Hp)g_VY%opR<2U zUmvJ`zWI?zk#5FItlxU35-# zaawfAu;|j%=nc_@#=9wXY3dD`S@SaL(s^h6p|Z*|Zt}(XEDY9mKF3ZepKw)=j67E> zU6^Y#2HqB8#xPKx+%b%rLIHW(89Jt6yAa^mf>40V9)q-@VdWrtf;9R({yn1G}wv|u}YpvFk8<^|;I z=-fFbiXBtwy>m~R`2I5)SkoTFo3CbF@SWJk;*F^|wijUBiMSY_ZRmWCb}^>nFh)$d zs#p5`ys*5m-q9UY&1u63wF8N8E#S9Y{01??-$B~M+ud-^c{ARA_qiHN;aiD4=^n%n zgKirO5$ouPefgZbpnnC>nW3}7=pfjj_aY{h-gA>}X*iqJaL=lUEJaWHw~#-^ge zByz){<%`O?6p$WLfB>7{(3hUApZ$e#c#$s0g{EYn40kz(((y?8eNlN{7TZ75v-#om zpz){)NI@-rgYd6M5RY~O0Vxx)>CU*v8HP?9Fz1}*U04o3|9S+4xD??6lAh3l?eJvq zFZ)}t_Rw|vWz*q4Xe<-cA^-9Fo+|#r*6eW@-L`SUYCZnLZyMJ(e@0>d_ST*nd>*^iACVQ`el;hr23oy0fbiev|*S zX=T?pHofq|U04-x)0n@-XnuNE{U)dT$(B%lUHeUAW=wQGc(CQdeCNZz!+D}D>qnRW z@c6xpr(+C?`LBr_!NG<;G5r3kOZ0r$=TYK|-#pa$`PEK--M*(gZ^0~iJ$x~zcl`){ zqqO$?Xw#Ee5m3KrJH{vczxeDt-C4EC$>+O&-+ljVjG`)6--Yr$-8m2MJ8$*>#W?as zT=ePzciq&1cen!Y_H&FSDq`m2m+ybNvt-jB+>{P>{9la1cEg*LD<7`?WnouJ`bmV~ zJ<@Y90-?vy6!rhRkUB?e*k?DNo~1IE|8!>oo?pI+{F;&B8+$}f>^UqJdQ{Rr%KJqL7- zL;{w0rMS2IbTc}T^d-Ab&qF-BPuGDC(x)Fsydb_r&!KI%A};$hFP2ZrVfX1gbM|mmX-Htca5ake|v$l|7E6?XJDPA+KRh8W5D@^vCFZ-ld1-sHlD$H z=BKvx0M@sF@B-=!HZLf{1GaJLkBrB0N*OMjw`>PJ2bX}PM;>IS*V`W4*CC$GTlRwv z!duc%h#9)q@8#b(}zgy`N?0Rry+ZbZ*cA@vx+@$Gb!NuIO+nnW15bCR!xrJKjyT-mOt38^JfGdHcThIF z-s}$BQJ;gvLmJnuTc1o8a@zEbcszvlC?LGSZ+CbN5ppCFu*CD*9n$b19uJw1|JXd_ zUC=>zNH*GN5W7PG5^qDA$9L8J@yc>ai5vX7QYS$JPzZ zTF&}4%LDmG7s&)xV%=btkEd|la+3bhuvTv0bRPB&*5j7a$`NYMVeT57Q#nE1M=A^B zgfc!X7U?Hn_UjX4bmggE%DD2(?E6x;MDLG0kn-ihJ@*zBnMCezy7Y@e)FD5gtzWQS z1*FfDhuC_){bLcouk$^K!*~Lc-c<;&)7ydvSqNi#EDPhM;aY&p<{{644#GnY zBOdi_0o_FPyV`ol7$n|}NaP>#E-VMjhDQc?UfNtkd3uc%q;4f263Ng*SSAln&9_

ba4!bo^im?ct{YIY?gqP!d zJI@IkPmGT+$)%~Ma;!tWmOjslpP@l8e$09gB)2h$9i}k&o-4QLk7#rx@-sQxto9+y z9Vt5uZ7^ATXoX2rzQH%{I?=UPSzq?Ud$KBBY%gibMx*2Pw7-_(eFQ3T<3IDP+E`ky zH+OTi@nzukAkX%KN=_oP!+ZXz@w@RBed*{CvdLC54a7apM6gXvA-hzE!^xuMCvUZ(f7^r`%fqV@-b(-`O+Pgi7 zsBww+{+ecaH6*qZb1sN=!Ea~AS7zGBXeqG`7;#79vh6#QXO#A9?x(0Q_+DLA`eT{# z5c$EETEBwz?4c*HN6u_#EZ4q=YA=54)m_}N>zua^b&h~f;T4;t3j zy((kQxb9CXQfe!@?@>N~;nt?Pp(p8^!aKau0zbdVMxelrxWV}7Hmr#)&zLg^XF%(@ zr1i?pJc&%>bd7!D@eJ0ffbasp9hiNb{}qsUemn5NUU3HpCk$cHpHbuZB~%1M}M%p21dX*hRf=vv}TvPoU#Zu_lQVja&M2 zzDOT>!|YM*c_FcG?N>U&`E+nGM?wp6cMo2DDDUzgZMfrPR>N&a8t&4y zzm@6BY?WR|)@>Be8Ha0(vx#9cm|RpS8#4v7?VYjx7)N*{xhD_xe(d+3=&c`Lg|=eb z>w4?Q3lI-o+}P{-(~ob#e+5K#65IB={`BK9k{Gb0X9cNSJ3JXOdLaBbb(=ID*)-BP z{dl^)X~1B~WBOz7A5#9D5L3@PUrEN3>qM8L5<&nZM^rrzJp zUb{IvWAOb58|%)LxwJymH+5Cp=4R{5GTtsg99vJX!-E`z(Wb>XyfF0Zv47BZgi&`F zko2fm*y;7=H+?u;|(TIkzl4_(Gg`jBo4x+#~uh!V>ur7NX!qaniGb z)UA|<#K7wd^3`-H;`tGZzQAwF@w;tWJ;6tFO{Z$@hAp{mUsiqTvw-P& zxMKbKwd?qI_G$VW<`IKn8zWst48|FUpG~nBiY3xZil!6?UMKdZ{vc+~e*{`=_jm8t zv;I%M`r(fj{R8%=xq9MN2W!SmJ#gW~g-3tU^r^T1;rL^zuYP!8%Ip(P%D>F`x8phC zl#fEc%l#<)!Km3OAElnCtXSCXq=YMPdw=$@Ek{$GmhAhF4hwy*Jlfj*^2loJkiRMA z{gxD*6RFPU`e|p%rnhl%eD7SJOQ~||0A=T!W92&x&m>>YU)cP$1c~!q1SBs%f8`zz zYa|k|#3Pn>;N!zcoDbPa7Lkeoa&yO!h1imBNlGs~yFER{RcOqGeQeWJ- z$&r4BeIfBb?zPW%pe=SJF)H7)$rerRkKaU5kr-tY`&-7<9kKeY^t){z{%EO__ssFl zq1~@w_psv7xT_~za?qLZ=>u)xvKLMupS|$yXO2G>{nz6;&cDn``6zNc_amn}H2d3S z;opaj|MH@g-$zH{48zdaIeNG3(w7&WXmQfYQ|A2O_(h?glsRLMc7%$;`?4zcT~zwA z1KwKNW6d4wK;RzS%+AcZFR~@&{=r>uhi|p+&b4((oYgs9W6wg=A=|3W16i*E!i)So za26i0zxZ{>*$A`yH`_4(D>rg$}f%O(;#0>Q}J|1@(uz1Z!9jB zk>A+jO>E7EIr-U=ZtCvYAE+e7kMMCUel)#b{HP@OdfqWwz!=?6{J-g`RsPmJ^B=Cb z@E~=u?;O8(*{rv|gR{lw!sGLRuDfaT z%(e5VBW|s5KHSH5K-1jM&Ofhm^qhw(M!w0EakltP zqu^!w)~L-horynrg(nS6RXZw{sgnd+x}rC|pmy7**D6-{VGm85Ej|wW$>YS>2e4=T zwG$8F0-gyx6L>x_ubXf}2+lrF#U6}doa6E3ng5A1(!Y+g(ci@x={!+n1+Mik48v}Z zPj}A5KW5H<5&G<1UH^m~H6z$<^V;-(>UzN4-|{!-4rGNEzPH494BO5B-nzar) zH%-K@{Qrg>H?P>Ve$O=QM#)+zOK(v%!PNc>Pjxu+I@EdDO;2}Twwif;v+L70P4D_w zylFksPsKmEtK^~1i}18#)1l4_5#w@I67H|xG&cu3RPsA$%6a8i7wo5+wE&m%-;t?A zuOB{Vb@|^uc+u4h+s9n}=_xa>p77P%uKx7A9XR{^^{c=At%+(cN$x2L5gMa+lNKli zQy3h7fW~zzi?CI65}kccm+T;4Cod5$RDyffqk!;w|NH~b?aq-%z!J~z576rByX3{R zs*6mRk9%7tY(sj?TYzOE`1Rd3#0%mNupb$<;s2BeqT|Pt36G#qw(ckS;%_lvhbKcO z*zK0J!ubcD)vn>x=Og&-j7(rFH4?#Xv&ca4etZz&{bnx*L@5rm_E|QOOstDW^g9{e zuh%|vqwETVmQjHB?mFgy@88~-8I_ULE`Hkl`3g~g{0w# zE_s2i&$Xk2#?ueW-1LAHRN*(zy(g0NX5rpW?@gq~KFB`FvIsA@4)-=MXaZe=OF+7X zpBFrX2pl&HNIYV60|W1ZXa_|;&=)V@UhHGczhZS@D_GT~(8=HhERzTRHG+OxzM}p| zJbjV%#5&+NCNGG$Kb-37vSyh?y@TI+Rd2Kv^1t?aAe%?r8h}U4m?1MGiFw2v{oxFc zaP`B9#aQJtTKV}8*M9!to8jjlKK@DZM+d2KK-++JK`rv!_7MjUjM{t^LTBpGr#qwR z)aSJJ#(k{Ah$}X{zWs)4@$Q4BN8Ea5@R)dd1nW`2<_XeI`Rox~IlOT};+2B7dB=X2 zcQDM>Bj$m&dB<+hCAb76FF)@%f(W0JNWc=0*ybG{gJ?roB0b_I6vFOjk{7;*vQRWXYQ!yJ>vL76O4A!oF9d2z_1NWE{81FtL+J*~f zW_?brHT;bF#gV#LcgXN5_*uSU`K_y*&;;B@r(b*Jbx!JtVb`4#PES2QGBPwObWuun z=;F}m&?PBjLYIceg`7zn?q1Wp{8r%R^%^(G9hVt8lj@c?FLx&0x?zJJrl_@t13L|H zy2dc^^c&Wvz|5hZT^1x95o)|J8i>dcpoRu z4D-__f43JoEL(iresN)c{4}wIGVnaAe=jL(?X;Rjb@Dlns;v8kp`1%6jyUK{yyO76 z;e`{)w?@4E*o>`Z&hJyYxkB3JaHL_&51oez${!xTDEy1E_d7zx+3@@16Mh?ezB323 zKpk!{KD*iCY75xD2Ar?CJT1v){L?m0D?pvG{fUOpzR$W9kRBj&loI|pZfrgw@n$02 z<~xVc|JffHX6sPoPd49q9kiXE^mD%s#lk`(Hz4tdZN4)SiMJw*IutLKPs)Ku2DnEA zWr%>JC$wNYJQ;i^-rOV0ry;S>2%URe=<_7 zPxv6kP)+3?4ToS29u3R-rcfHoxdbf0TY|^NV?iheu673fl2&rzd&&`2}r( zLB?F!NW2YcCK_|mo-|a(T-Ns=qB4^%w=pcbUR-+IVTbCm?3IL zfOXf$^vlHX4sYFc+YniIedhX(lYa_G|GWwT(zp1m3|9^=0f{#q0d_y`Z7o+7;@SPU z7Ict){0QRRh)Y1qL~P6bXF#+eEKxtMLm@^)O_3Mtl_|Hbv&VchDWjk04OX>3ZW*qr_ruuTQE(L5}A^n%n zp2L;H8y6%V?VvVK;kg&mm+kSu^@wNll-EHA;VJA$UvTpzk}?t7JcZ+dR)mqC^u<&5 zBHmcU5s>tR7Ho$PJWoliHwaJRw=#Nzv`mYKn6`>|N{4`e$i}_i%?L_Cv7ZuOwm;Nv<_*q{$XbS){mf$>Ww>nSszSf_@PU!qy5xjUC+i_CQ{7AQR z?fpk1*wy)yg}1?{_mhRS2N#q*T!HY)l?Qm%Joj&G`QU3UmxZ0l*uyard3!Uqs)-!` zq~xQ6-%-!L)w1wtc+&TeJLls0u++B~9=$%3)Ue~9Oh0*Wwo zZo6N0#{WIuKeRm!+K={aE7=r!T+Vnu@0T09(#(nPsryAYI&a@Q!_NI>sH7CDcry;u zLzZ5`_?KGKdnL|XEqf?bl8rQPFQZ;HzT26Tx~r}tV)8vWYV)jy4u)k{M`}CIO?m(R z=%XmfcREmGDF-eIf0Xj!Cf;Yh_I_q&%14=hxV_{5jM{unZ3oJra{2kb{~Y$yU;aDe zgx|R2g7POiQmb`3p)$Fe$3$y}MHi)FAzb*L z^vp38>ckN&g}d7(23+SeW6t#}*4%ODIx2m7J={$z)~`#R1~`=F!TBu&gvS>kz}D+( zFzg|Z=a`Lgcya70^Gu?PjmHhc1tdNHJa_@(EtN>X5|8stcD}V%zJ1Muw;;VBvSl~o zHCp+~s}tjqfjp{Y2xJ@XYaTog<-6ScE4Bkz!7&{p8Tw?r`KWj0WlU}A5^#*lZ|A`u zzZQ-b*pN!ai)rI+&A1r^t$v>}h;n6pmiVjSeKe{}<;x7uAxoDMHT%z$07N!Alj?`lhrwsIz{Y3?pay678! zj~z-SgmdiEyS{1YA7U>4=8ALY-JE{@h?Em8Dd$H=&knuc657}4tfp7vG^|wlidm`r z8(FD5d-l<`4U__J2tVfgu}k&vJF@#qJ0g^Gt_=st8_lpr8K^2R|ZT_48kuw-esQ`LlTZm%6xa?mDO8AgUx&V99qr?rr`% z68Q?>xB2hQhzC`#Ns?HK^z1ezdHLt}9>jy&1hN^+y5weyzS$ztRK5Pf{K|f}2tyfF+)P zO;~S!1>{dQ-(kBB!gpBMAZx@6grB%G~ z!lBMdYFzwN=ux33_~hcN7JN`s^k7BGoG}OgkU#q1N4XTVz!BU)SNm$H zB6E1OCMCKk45h6;J#)AoE=MXd;4(EL0!o)yflqxrO(9adKFi8hPR&APV4J=Z_uWC!7ttz5uWphiId>@Ir{C~ z?oTkP{GsBO`aEI&a+Wsjb!K*;}x`ajyu5g=rwxr%tIaLAHVS2OWy(qp7MA_ z`oX6=NAU#X7%uuIIO2IdLVwzEs53o12eZX{J1#DkybpB_+r&{V^LYt8ll&6Zw}8A- z_@_%)RpYxhvb8@ zBdY9qT2=vTTl&jK(#lR^9dSILxIB4zVBWiYrb75kl|DE9+Mm5T2xkX+`WA%Fs`^#8 zEk9%TuCnW0c!HnDWLrFead@TSnv2WsXBUYTcnZHMc}k8|V5Vd1 zk%q^p7VfEBc7u0MA;X@`D^{$SKD9(EX!T0gaBtJ`Nb^$g9>sIeAhJQnth2%SA3=QO zJ(t|XtcNM~IzV#9wu-`B}n{O=uZS$>nLEGs`UVhyu8xP1c1tcD^&9{~!@ot1A(v7$$ z;I)z%u%u@Nsarcd8GMWN;eqz$Z#Dsb-~Pn95$l*`Fe!_?`rrd8{(3(K-)x35^gc17c|+tzKcC>0;cjK@XYiaIj)aK4@x z17q4hiR;|(MweE65DlgWA8Zb`W~ivB#N84)F(159f5bR^@B+gJvwP)(A*ak~J05a` z7kWJJP-i4vb2-fe-|B_Wv2Fy|hGY5MLdEAQGb4j&8$%^0(X)6c@j9DFpo=T;^ST;5 zV7p7i>$W3~t=mX?eqPsr2kc9Uc->ya3Bv0>Mm+mHga;AZysi|y?l8g<@jB|HcE6YO z@Yfiy!v~7jEj2lwI@jI(gZA7x%@p8iK5mE)MP| z@|^w{F+3~lyY6Z9Pr>7EHubg<2RMI#oj=pt;P>GaJon0U>Hh=#WrQ)6cRD0}rb}BGygU&1 zB;t_beK+pub;9&p5VjY7AkUXW6vWIYj0Y|79BwdX-GY6UvGvRi={&7tzWPP@pv@29 zTQ?+;3F4iG5+7t83kcux^TF+Skb_8mK3Ik@n-?4g9gh#rLb$E-wIaQEeDFHNvvoe| zazXgu0>t|~{wpA5BDVP;&+R>outa>Y5#<{%i2+M`R*<^2!;`@WSuPK>-^Q~hz`rg# zvCc=`m}TTQCLgrdnzR1n%@?q>+l&xRU%SKMpqe#B^$yqHQGZkV8hG9VF1>>ow4e9E zhof|=TG63@60HZDF;!0NO{}kt)E~g`z8?ESV5f(3FjIh?9cD)lM5@ZLO9cGkLK*IE z5b^eTz^fT3#NB}N8RdJ?y#CI$wv zJiqS+_kd#CB|pJ5qp_P&_S(E-3+N!c<3+>^;(PHr7)cxAk_WP%vV2kw9nqJMs>tBe9iw%t5zVJooo`*DrR}+J;7&suHi|GN=0{?(@g=3zKF|Ix@6ubJAB{Kyth0DvhbKc{uVuUYbxG+ z8TXfCnOL9k#z~H9%BI8XhRt7{q!Vxbx9R)3>nHB}{gC%ZbiPBo?ndBO>Q$(d$|Pd_d)C>dtF(dsNX+`LfAUB-M^)5#CCWx z`aOA{2N9)@^rzp$%o@}0Id3kY(m@|@w7Y#HIf0JRN1wlAee<8CyyttLmG@{KA|pjU zmm$n<`@Qx1v+|z&%(hgJ26M3>1yb7PjRPa^RTmaB=myoW`RkUW_r6c7!JlK_SMPnc z@1uR3?fX_|#jVZvk|Fa4yzlESEPY=$Z2ku6`+t_YJ}M`PV*jkJAAgL0R@b-r$^hv4 zY{o{{S8W19kMaG!@%^#w1@VpVk8LkUcL()r%XKR_>GD3_Tws63_%in=wmo}JLZ#z2 zWv}bIOty)Ap~V{-0U@SMQy~?*Aue+wZOam!rkleWSPj&v`#vm+h_pUypcT z4Na;c;-^3T{|oXbU?~%^J;Lr!|F`GKB|R$(b!&$wL*FMq^x)KeprrrXc1qpJ7wcUSEb6BazwN?)Q! z{y(RX>tPV~P-seOdu!Lc^zN=z%Fn2D4_C-^cQvG^V|TO2)~uK9r_Q)V$FefAtC@c;ry?3reJ2g=(i?a7qd-|BVKsKRdL%T8M@>q_dBb2PSZdzCx@ehruF?^KbQ9j!@?E{aAM zN1{toDl^M)=2mt^>f+QTdeKgK#%dK%le&n3bd4H#Uj?&_@jK}YO6)y6HVqAoixcL1A7?01%>tgr^2z#DF@|}-( zcD@Ce;$vTCzQb@yzBl9E=AE@jFUb7JBZzl9{wpA5BDQ&F8Zu&6R0`GnpQSzcI3IYs=mBzS$)%OjmtM|SXF;_o$~l{u-m`0W_feNiuLQ^ z)Q{h_>wxR)IK%tJ73(*wTE}7H`M9`8+9YCRzJM6YC;J2a!M;e0NDmTYqUmeIBXO3S zi}_u`Sd8!zF*;3~ixI^MqhV(gqaEpaW&L7-d}ybNQ%T}+=Ly}!V&qO!jNG{*uG|?B zBX5NL}(QxIc>qCz@pB8D8_NXUse)?W&s5g1j z^m1Z(!>`$ZI%D6oBznL+zHx{V5N?x3(fPCt8yhT{JAZI5oN?TA5k(`Si>j zPu66WXDm|zB5M#Z$g-vZ(nardnQUP*lw=LRi-2&c0tDDRzYTq%3SoX(!#OlIW05t- zaF6a}fa&o$$JM&I>qjSmYW1!9m3*r~+4-jRB5Nq8Y+17uiI-UENnZYSTHI@`F-|dobTB||eaD?|IYZjnh?ue6~6{K#ZJS38#r}H~_pnY_oGXYYYI)Jh!(>&u%|Mym7 zJqnQ5=Li8z`bu1UN46!(9>1)ajc@_RUnB%D>CgG-y#~&KU_1`LJS%67%^nbP8ah#gds?F6QeWW zHoi=Ocf;ASOk&wWezM$ng7lOz^uA>0>YUJ5McB9vtt>} z2hWaWbUh4(u?*RBZ(|vDUQ57e@=s+fgPFGCAaiKuWR%2XnPa+xo3YH$^N+`|?rV#a zXf68F^N**^o3fO43i4rIq|0#G`e`ZX99#mzv#I~sJiE6uPOd{dTQ|QEbP(Nq8{#F~ zKmH1&DPX^&gb~}}1Erf&$JKxVjRo=i)#I{0tsXh9mHjZR?7vr5cF8k*dD?a-H|sj*F>PTHyGh8{ zOcmButXw5m%MQPE+!=g)4 zD>G|gjUVq>NN^CyT`E8 zinPdg1(+U__uELy5LhRXfF)nQjpUhtHj-zMUJyR~CgL?(`Lb*TV%tWt00nA7Alr0b zHj8N(X^o`mM?O{7)@xPU*XwMw7uRuRVEeH(_=*pO)NcB-k^3B2svd}f&F9w%1QeP z=g)2X%68JQ@&6++j3{ro^gG0`-5+x?ziHS#46rYI3r*C)>@C6fO&qB^M2x&caeVW~ zlj7R(`!j!h$=84Jo|DTtWXc*R?@0UT`MDcIJ5t6v<3uhwf0MT3zCEL=7k1ZDF6HXk z;|9pJ`(kE~N6d3_!ugb3ol0_z%T1|0W+c~p9nXL0wEX4CJ^$-xQywVeyAVG4Pa6!sqhEgc z=aaL*uOtnoNx4MceZ7l;6mTC6+UW&EesNyW&UZ{N^2G>s$ggJ+?{>))m}Mgn z>+Y&ZXABAy#Kzxoi*Mpz*^Iq%F~jIdAeTG^0R)i~ckVc5ZxKX#mhm8$zT@J(z_jbXPK*wK z+qic9I_ydpM9$2Rsp6c(_LU>Z3t;5T(6g`bt&?Y78B)5xu6y+>z0S`&d)s?}&R90T zATQ2QDd`_ck381qiLEf8uuqT&fITW6izcUZrBk)7*t}TEL~QfK{;WZ!jaER?6I!qx zK2SVS@eY+CYs!OowiU)@nON`SY5x5vp(CsAD=M;T)o9tvSFNpEv0kU$mrVuR6|w6l z+<%~G+7x%gp~QW^suvwIh+U;L##iLQ7ih`ISGpwi$Y^ED_ZTw4gg7tI$1!hy+M_ta z@ruY;dLnAyMCgkvzj7qine5t2ZhRr_$xGCZyYxS#ccR!$#1B&Fk#RNE{5|IyP4$-@ zo=*C6qm%v&HWccjzn$^XA1Wq2P`0S>%3o&9`*NH93Z71iI`5&6)<`7aG<@&`c9n3M z-;RP)uwpGOgK1ac8x5FRI;8Ycej5SuH-ewH(g∓eNezCc^mlVqAnW5W-JM^PbOX zkG8UL=76X}n1K9e9s+D0Y@hFH`#Dliuz4``%^-Ry&m37TnF33hh;1Is{Xc`~r8`fP zUTW77Yk4@z@9HPGliI{BfIOJbJ%i{SwNi8R9x0KreM0ag1JyVmR=U9}O@0 z(NA}VXt8*OVSqBW1>62@w~cH(8$8=JYvat*SE*mJ9tC>isjq{9@fr0?_E=t|{rW1~ zUJfn+>D_*Pb$>v8wFwCY;g!!IUJ!ltFc@b$;!-w*|8=hoY(C7?4ubJEUDnx=_V6RS(5T0TD>Kwt65#^cLetGGo~*Wcy#uRozU`hjk@w-g zE@LCbY8w|=XT0_EwKDfP(d)R3Jv7GWIl43wy&+|OW)j3KT@&T#9;G8z((0 zNZm?4BnFCyzGgC&+SCC9We1h)_OE#@$}6ygbOe}+k*gUzulAbUIKg$8-!xT z!ozKabHyFrG#%&VRL}MFO_#KdqOyj@o0#*jr5TMZxrSyMG4xKhRpL5g=%3q&p?^M3 z4E?i}7<%Xb>(cxd)IawUqeI{}u3c2E^oD>*w065_dST$RGYaF_Mhd?>t9sUg?1n2X zuam88@CtMPZD;3FV4dMZ_8s+Ogz?PggtRIL~IU^IUT5;(VE< zla)DI8XeigG*ZTe^PL^%yEc?2%+1BxP`=-Bp0SGPz3e$V_kIWe8y@#?g|j2#{@2Mn zY$VnJBacw^fbPwluT%96YB(-i=PqRw7s#8+Gly?UxgRTXuFV`1tr-?wlp0+ejV_5? zn_0CqJ#&obZ!)}m5YIc(r5`AvG?Zi#zkz^oGx8W)HsnDzG$G6{lV%}|e;1iF3q(Ab zJNv|PZqhtyUQUS3olS)ybCIqtWf(0p= zN#4k^AzuT}LMF8s%1h4*Qn!*1iDbwmeg_Zq`kNCbKx$J5P$q$WT9EwpH}oyxJBkft zs+Ak-ZLW{@%cP~g=l0l(|F82sXIm8DbI2^s-V+HeT1i$ox^sJSOVP{Li>;)-aoxK0 zJuN1y)->I@e#Nq;X08m4m0}#rP=>MJPFXd9V_LOq1UG`|IqkR-C_i2x&jOE@0kbK{!{eSD8EF+=x*r=xz`&mbt@i94O z?D_8-pGePkuj&hR%6@Lks5zhos8<*nRgoFv6B%6^jouKMpINg++3W2Q6r|N)+LQE~ z{5i-geh&fRbnJJw+}HxXT!pYi@{0Wl-N^vcBOmk2EBeUYXkvL|D8IaV9r=UGj4dk{=;~6x>~Ct1g$Gi;9CwceZE2MKe6Xbg_Va=1 zQC1LekA)g5y)1O%1as&21eiJ>#CaXm(j>D$0o6575_#yX|0>1z;&&GS8&Xh!Ut1m5q~)c)JlMz<7ikaM}6pL}EDzW4;WReCu%!me>TOfP1Z#2mvg4fo;c(AxV5O zPCUl9WqdnicPj!RCX|lBe6w(|3`oL23lxvdhVt^Yg4C^)heR@Dyj{mkkvdRcGCnqb zs)~P7m5e{8HK>pjd_kt?fu{NX8tgB``tZ{kF=Jr1=$c6tk*g6>lU-3Qljw5_wc&&FnFQXSTEIg@VPu)$JyRu@?W zs_U%ogXW?E{HO|dXLX-gUFEFq!{%{T_lc+b6!oh66j_=Ic+M#-1NG}Zc8cWlXN>Nn zcK8Zl_nA^$s!u9T>{IoW9&Gfm`^4HyCc$13RW=aXI}-0&EZ+L|Yio7|03C$H`q*~2Qd-&loyZmdGD8>`U2`m93EE4|u<)`i&mn)K+RbE1pWqDzKh$BJ-ydS;$y zU&^k?z{&~)hy@A(gXibAnmewoXq==Dzebh)dFV&{_5x6Y6cpgs9-)`v0l#e`{fP6+ z{O$shp5HdK9S<7Z^!l<5(SJwMV4Ae4FnPais1)&DWCRx&kKnfrokU_e2v1}i>PC7& zY(wJ%+J;WRHq?fKWBA*rZD==aLt7C?z^Y0KQrHe3DBDn*$x&)k2XOw!{wAUyc{ahp zu?0+{q);9~x4`?M9^ zi+ce+r>&^h-Qq;qSyf!;fCYJ09!31ob|X7Q$^qJC=-W_84B~oX*md}hwD(Zgto<07-fGfFZwoOZf8V9wa_M)7 zk^V6k|F?^|KLGO?LmbDR)PQ)jC-Ga*o&?9i!YNuwQoo7)2#W%*u`B^U02rN$e(D43 zN2ok1p8QkrBW%>(Iz9A@QdMR8hjPLAXbdSoLbvn-C+dgHddd=f3VsIx;pznluw{KA z*mo1c(B+i8WjykGnFnG&C-mk^Sc7L)HflZP0`(95Bl$AS&UYvB1-nrBLJX?BnJ@SJ zgP3KJ6l_Q0d=~-93oIsPp5-+>SR;{uB_6Tv&idgj6sQS-!$FFE!*Z}}_Pot=km2{~ zzo=hH&kE`ho($Q{a(NJO;BMfYFac7VI)Jj7&ppsI-$w&$)`NKGMsRE`!2gXE0+@6m zF1|b45@qdl+zaqI*DVN;UL*uC>CgJ;Wj=bPkKW*;Axm|qjcb3fJ>a!7q1(efv8n_9 z7(ym z{5=}upF5$w+x;H&-7k;dIH5XiyX!glWa#0i_FR4)cBYymE3{xGxR&E?C$D5*DA##d z`w~9BC-d;97CM((u~stH&OM>raDnsi`)15Ms*2$}Cn@d87h?Bq%zdiDdD!!l?=l{U z?{$QcljnKzpB?yo3dF~Py$yA)!q_kExrQ1Qs(*%~ZzLE`<1~xd9RxPT8BY)1*q3iL za6%C3q2d`}@d|AI%>d!Y6D`F3N^P@d^=#|FQGsw-FHT$$o6hqTc-J zXCfZ|E;6tT1j`}7^!WTb7fW~*0_%hTmVD>o-p;o-e|pa8;$530iRX}>T{p~=;Fp1i z@qqfbfW#w~I_I;cC{Qf|*{1uFfx96C@8BO?ko1HWY=i% z$F6KiJ4M-}NN=f^K0b*@D)}AektOv2%D73yXjrp|(Kx2DE3#_c8^ z>G}uY`G2_KT`uN#qtE=u#OOTKBZ%=AHO|W>Mmv+UmGC-6bdO9d58}5yWd$Iq4skjX-S6x?517AhM4865pj#&_9x%6{K$M z@MOq3eg_Zq+A;D<4N{w$N|rCaq)u6rBLpz%$+-BAY)h1NQ*kfA=hq4WOnQlrzS&3L z=A-@NJuU0N^5aQ6IKuUmcIeD8@=nqHmUz9%J2j?*yn6uUro2=BbfBLj4SDx3#1LL@ zy3Y^0;oUA)at`v2l}I^9ouMyzhwV55jp>S~mIPi0y-hcp82csWPiMQU#A0^Zcpkpj#AGiO7yFPnghs@Qoq|r(zudZFEpKa22@*cn}vc3B4niKavZ_kB0dDon{^Lf5u z9acU>+*J?0T)Vfm$bKPC_XBu8Cx1u#SCGGVPB7D1^t`=Bfgx4TFH~#oLR@R7_9(Zw0jCF#+n=R|Kvo1a;Wbr&VEJG_jk z$XKre-L)6o{spV;2lI?ezTuyTO@QA@KqPDd0&IQdO?Rx~*OUAi&;2%mV@NNEo|J2c^F{=eAjqjhbKc%vg?SYV>yo)MK7Yt88HRb&r2=ZF5_U?3?xt1BioGt zX)q+!PS_TyXHj1k;B)#s2#{VW1Tg7!KHAn@`P@GzeV;Er^e(C%@w6_#QQdc-rqRgO z+}Y@mX?WV0rux#w+%=f%SFL5LvCHM@(Xo~UApPn3}W0a{qg+&jHJ$WhHJ$XrM zH2(9ZFK~5?jo1a}VRJ%7>eeQ#KGix4ed|b51E98Z)cDDDSaRRqp4l(2Z&9zRe_jHL zIe$9FS1r0UHF`r7I|<-OCC_0^31uvb)J|*m_5xffiS(x6M;$%ugeKrNI{n%!uX9pI z47=`}aC++bk&&TMp^H+oLl=iehb~DO6S_1!F62zwaQB+#<+lPiuh+Oi?&z5o-?!g; z%Yl;EL&>heZzUjd(=V@&VEkT%NPc-;hA?zvW7p`$J==u<)8liFV~GVm#!ZtDz>@Dm z+}pB<^XFgzJ>+#Q!qA;f5{*bah`ip3c;-(?L&`*~yDDw~*(eZgFMOB2Z1@eRm%mj1 z&_9x%6{K$M@MOqqurUiF%D%kYgh*}b0Lo*I$34(A>s13aArIosV{^zY!2gXG0+=*y z_IyXSCCb~YfCc!R-&KIL-$uVe9s=|E8XpaLYC2^?smjgTOl(Vj+F^Z3(H@f1aUfQd zESg3P88wF(4WphI_KS_gV$Xmb<5|+c{3hJ5?L}hfcDRjem)~&P^2S?(*yT&7PSc_) zvF|$NBp^oiFo5&VJ@>O&5Z6*M+TFFS8#aOL43RvgisJrjlon3jJl}YJsu>AuD?_)D zGCKa7F;dORYj01v;>zpO9+jDBcP9JW&fkU})Bh-MzZ_$8J;KG9H?xVGqFW$g4&>xlebVmy!0cr0sdsb4P{Lj9-~i_&#``$LcU_1iHGcj@!ES!9k`I4J69@D=Cmn|p9fG3n7OhEDiON$wY z)*xP^L;{w0#I~G#4H-2dFp-?(yvTiV(zAlpt>i-@8FG^K;eodQmzhkYHg$}_wEwd$ z1+o7x@CvWKFYOcp{NA?;0ZjUKAHBgxLyl@u6K`a?(i)2D*>Bysy%DIU-BD)jQZ(87 z^tN?PcW+p=a;>!_-!~2wSvm=2qb$9e7&4UaO3XIP@Oy|MQ@6SFKNCad{u?o5YrBg% z=go2LXksWTmlNZ86)^XaTRqF5Rftx1h8 ziY}&f$jlnVu@a7B$MIl#txw>kl-CtbYCSH7lG+<%_SIw7j`_{i<8s_x~WkPLE>`Ne^t( z@bc?%Z}akeMc)e=G~LQ z%h?}1(7wAYp9a>H2jt~8a8DJEf%wjaxX6295;DMaK4mCf|Kydbahm~$+tz`2LLQ?t z&2&`QIARnKY)J8%Y+{TJ#qS1x33wjrl)(D^$NEDW9;4S$*sD16R0le56b4L-N=`HocY@N@y(!Zo_Y(?D?ylmC{P&!$-DZp zBh5kiY~4=Mv$9aPc6c&)D*3zz`izv9On}s;4j@nEJ9waJ)~g2AtOxPzNM2n1JuX9Z zz7yLHdGdJg@9KL^@zFDVbcK)RcNb83DIVVIIj5>~TIwx1jnQtkL#OB9=~H7h?}s7o za%9MPib@wZ5~HFxM?^jLAs0XHhJT9~f`j!OhMw9+jK)5a7!9eIDmQ>MH zIpj34ZRn(KNHMab9r|g6`l;IIctYI0EYFRx+?4Ioz8&5kkfp|#MX%Lwe>vMa6-G-C zo(j{rhkg#)f8#;SNqpVRNpSC`o<0)q8Gno;W?tgIta*tIs3TNg4;f+e2G)0<`!z00 z=k|=US{{=QSf=mWuW=CVDtx0q3%TL(8!Zp`9Sd;T{JRbOu?k^{y^FidsHpB}eHz*iu5I2$Bs6oA~m6rh4-P#IpZ|(4bk{i2C zwo;oqV4&oNWXJEr_QH2$TcR8(0v6!&G9iFTQ;!fJ{TU&EN!#Nk(i{tr4aYN^;3Psb zY0s$##fvPV!j2qkEAeECmN7ji9Mrf18Bapilp$rrkSSzxlpQ;WGhP2l$dG4A1M?g7 zHQxZ6hX{#aHjk3vdnC8%MrLFRZ61X&Hjn#SL(g*55Q4AX4ac&o&pnV^{V=@NLQ}2< z6;X2yRl9hfg4yUWMkLYW&g@TBz8~XN=;U>p`30u7M+mQ3{q6{defh9dFNZs1u$>90y z7anN)OREVuHG7Qwo$onT2w>8MxcCli1LWz`fd%+{o)EyKYkahyr#JYXgQx4x6PK&| z-LzIXZcp<#d)$*$mMyz|#rm}?8kcQoUcR<&`TDvZj#!GfgLf<5j`0J_O~0gCV!TKr zF&e-oVpO`~^=MRT+yLB)aPEUYk{FG{H(sb;wj9Q(Aalvng74XJOgARO+vRM@@YabK zCv?N6O}@(c+0YbPxFg`u4eF%GJjH`K8VIX1Bz5TjbUB-LcXgy6@5=h9>+O)*=`6cz zd%BYw!svi$@x;hcRX=?%l8b%4l;69a{pDQkx$a!;jTkv>*z-2#gZU4qD=S^{Ax$qP z?;OeZjeUu{fmKuwOz`vjSvpw#>M=vw7UgZ66|IRx7o}8WmM%`u%+lOGtvurno4~&Y zZ;YVdVxR^IL&**wWQ=eSe7hF)FT7La0KX@jZ!s=HH!ho(F&>}$=UzWX82hGx$ct(O z*kgoQy^IlVK|HYZCiy?-p@PVZ7Q`bD5MbE|#J0RR!Nd{Bcj?QvREK)GiwU?O=?N{^ z4o`->;CJvq&%Kg&X^`5~)IiL=`tA7>kQLvNZHe+^vd&ulX5kkL8Vr!W&QMyuEb-Bw z_0h|G^hzJ?+~u-n{~)3sdsUecL~*^#oIE+BySY7tsCT&QdA-Bc#t8=#5H(7!j3b8p zC?$scpuLe}3br+l9hAKaLS-9i{OKuT%%^_C#r$@hPo+Gjz3N35D>;OZEpiBBjOp$M zo598yQ%eKy#~Du!(Qeh79Lg|qsBjl$&WWy$hbVKR`#I;TrA7P8q1;R0DHJPzxFW{E z$;BC!;YvuMm5@SecMQ)5DUlS?dyw~#La(6O6!5b)KnSt_+T)Ef{aF37j$>?A?mTZr zX4&V`Gqbe}f~9JeP4GWc@G~gBvhG_9ln}ye3?(_l?;#)@tN;PFJlGF@TZ1sa9O5{G z{72-_G2BxZ5fC}V|JuCx1n8v_30U%7fO|XN@x92Q&m*2Khv*kkVx=c}`Nu8y;K7MOo;Q#qO1xT+D0+_V@%}9&f={XA$BY0@K@=GDGr&uwh0zBW@`oz*l z@6$=SqvQ|d&SDgaa%VL$x8u!eYF0m8O*B{fZ z+SuPXw*nj2D}EkMT7djw5XS*9cVg^%hR#C>?`7S}y`K-i27!}=B-W0 zmpp^{(rc0Nn7-duLi>6U-paiW>~S~CMj*CrC1a3L5S#rr@R0jd3i?OVvx3yE9X?RJ z^-Yth)TRzNowkz0D8i}ON^UdnqQC#`K6-zxq?L_Oc!R+^z{e=1h z?IpJm!;aES3_HpL#1KS}5W|l03^D8`|Lo$u#E8%DNjv^QVl;aECB8j{_URz@l&PhG z*F~Ms4K_x0Whwi8em`VamXTeDIxn^6ky9)?zMPrGbD<(3o(=W&J)_LdQ?}=6y!qn{ zvlE#1JmtFL7|&DG*~k08Qvn1Uir)XqHRt!R=g(p!7x)bl*;Q~BlsCD|_=6^&^cxJ6 zcp6HwiQhp$xSC%!@eFFp7r$)c_hd5`JO0PGM>jIS^!S{1+Zg@~g6RoJzSRh@Wm8Ts zvgsDYOR?sYmm<9qNeo!>^4swr#Dm5-@fhEhO&=riS_BS9IM{@eiIkCkz5f=}i_Iq` zUqp=oJ3JY(iQmBkJ)gYW1W0Y_fWe$kW?M>zUFBx;E?PGEWff(SV#$f@D7qVa!bj+y zc9dYU2aRAH$`)_#_=^mOEZRa08MKoa0_9sS=J%oP{v~2`54l25|H$S7Ho$P6z^m`X<$ux z5YJ}9dSRJZ@8oqCdC^sUlQ*d@EWAlKZL{M}y&FHCt;Ag;Tfc0@#wM_U#Os`<1>c*# zM1Q0heN)>?X2jJuuQvW7PF`vIq0S=XF*5z&q0UK$n)u5|ZoaWxh^|TB5Uz;g*``|O zYcR7cwQ+fxfk@v!P92*_Y61M?9V#VjlR0qtis*v+D}^U*j4e} z<3Il)KY{3~sA}~|DC_Mxz%oX1A%YLyi#;V=Y1>d{+r(h%tLiNVN?jdVywqX{!u$NZ zlxtjT@a_Ei>QxBi-$h?71wkGw!1VZ>c4aFYwQhB(L;{w4=i}byxn*D<Bk{B-&n9)_Q^|Vt(>P5GS-ASNg#`rSQ$KTjM;9Jr{8v5uqVnlw?eSX*tXZ>@1 z)JbA=0^G*eM^UQcBCc4EIi4tmp+1LLG)7YjoXH}oVf7Yect}SSXpCynptI3Ecrcb zz0#H~uj5&aUYQfENsBHThRv&@OQIE-RZG>fdutv3VDdiw1_Py34ka5Xzk`7AtpWtt zd@!hQ85vbPoziau<-RU8k}0s{TkXp?=$e}Tth;Zt@)bTtZ0nRPP%Q$7BfKx2vKBfe z*XIdHdO{1f!v~6Az9yNO+SCDqVFR6L^42=yG|+r!wk`5wyWf+qFTf>0nrl!5NZ%?1 zFzMAknmVRp%fip&Dw%#)X5FVfl~ZWjAS(M8dM44h`@KLAUyd?y{S4oYm_9YsLD#zY zOT^GUze)^U^lQYJkNan0D4a?sML543ZKHdMb=8e zSI=IM-N4l}I}5kQS=A{!hvn^}or1gKa*e+DkvNb;a=#nCC6q^3w5Q}w?!$`Vfb zXY3dvU8eSGCwZ;ocU^5t(!KHK#now#hR0E^aep$(FwZ*jlRX#oNOixFZ9nfAZtNwm z8GFfV9m7oMd+pwNwfH>7Zlad_Lcozf*z&EAkz5#$4q)~OxHi+>BLFLQ7M-p=0^Cv$ zlu*Na4<)(A`WF!SQh)$kuF+<(5ng>SwZU7 z4o`+$V}J6%-Alk^BDJYwP_BWUTJXo8%YLbq8ov+a8nb6xq8uyoJ-5F#IuqtJXB#xqij6rsnnV zZ1f2`h$&@f8BYwEr(_*)6=}#kus|jAwh%*>Z70T`o+5_q`@Z}9E%*65?sM8*7%vO; zO4&!hF8ZQm6UUc@@C~>6ZS_L|*Yb2neV1%c~c`munFzk-YjC zanOwnFg5HEiChC~xNb=*2$TKQ5y@QoS;vJaYT4Cy(5Kpca0X zA2I@k97hb9GtFdk#9- zUIp}WjM*_q+4T;bJ5MzSUGA&nmV1U7`8j!0V2#vcw31&R>YQTc%&&Mmnp@aoEEs>z z{3auCLR87}!Y;2vzQ2}r?Cq!&aN;M~+k`4g~|i5QOzJOdfuia@Y*CA*j} zWf;qVd<`r`J)e%Tt6fK|74m}TOsS+cbpUmN*!Za`zIl1m8YF(2es0p!G~ZuCY-%aK z)Kj1_+GAz@kNro0^cA>R=WNT=9rA$%_*wQr z@9@Q^t^rZpr-c{O(_}cFmZ2%zpc`y;1sRo>3Mtjjs7H)Lxj0rWCB|5lLXdh1+bqu~ zeSjGHiPAUV5Vw;wFu#2`+ug4M3On0v`e-jb>RL>vi5Tg8i5Thpvm5?nH~bA^q<7H8 zzi}}ukLhzRh5LmoeFm8zNUc4*kr*`fBekk1Wnv4Co+avrnpf%Mip_#E1f0_ryO6z}Aa!N$b{xrv|Lfb1qsw28IgWVcpJiEcrWs4lbXanx z8B5MYSaPPok`uh#R~viI3}w$Lim~TN**&jxDA?2vXhuD*1hHvG?bj<0*>n3*}@L5w(_7rR5_=rNaY%J4sd9O&=8 zrV+l@{vWJ5ULu3%2fP}!VCg)HI`eg&Hu*rnGI}q-y)B6%7*}zeMOz5t@IsKN?Cfp3buoHl3~J zU;14w(%ecu3`oZOj{U8fB6-1Xlbh704(QFMGu#x4U(^HcLB#Yt7#N$5q|bVtf{Vpz z!$lj{y#vhl5yoax zYMu#p8P;Pu26K|G*nPghaM*j;Pne#Xw?caSKkY(o?(;X@=ZA@r{!tg7a538#^P?Rt zh#d(2gl6?Ly(tpD3^vQOrp#{QbKODW^R`Oc0DT@9pn?~3ntoM${S_8X0%ql0OL$30x( z?1&gG=Ah9s{!a%!hXwlV(ni-U$FD;aS}{Myz45;o5`KbG>VcZM8CrgVtbYOF=zcjr zCRNL2bY~@_7?1K-=59nT7orcwlgo<`7mo~-f|z3{ohHfaaM?0v8}cRpV7?H6DsQGw z-eJpS?$KR>FagO6?1k|RaQ51tkjpHS2N6|AM@)cxMIAu7%(8o+X)la5>p{HpN-+&!fd9M9Q2P7igXTN3Em5vg z&I&O8Tp@r-FZ9u$@zMOg0*p`DBS3n+5Wu7(FyR^`2HJ> z>sHbLkXWt--)pfjj$F%9g4G8ngxvLOH{w8v+1O&gi0Mp}h_H|-`G7vRF z0875}ac}3_+dhmO&)RZsJJJgx=Uzj++pT=1OvJXFD@B275y*E*B72TM3Z%%RMF6z|Ipn0jOSVNi?#i z*n^V1^<4U_RUVnt!`)rm#8HrOC<|p6%Wv;1@EB>xuARgXK&`}(T|Xv;aa-;y?&XyzGM>wAR@~`LWO@7rNJ)4J@fnb<`2e$yCjcT8P5qCK3SVeEiT_cJZMt=5u!zuQ&z1jlQ+Cf8fAOUFjc zZt7h+`kMKbT%G)XZEtk#ov*9Y%Q?!6RyuhN?MPp(h<niKatAIZHX zP=2y=UFu4w`|%c8kL`5tz*{=`|Ev8W6ZQyw`hH~}&fk2Z;dy=&j-wmQxEUJYHC!ja zb$OSm|2pGjZ2!(L{~IS#HgtV+(?#xlKlf>wdo1gArc+osqjJfytbE=(d9Uv~&;9y8 z>InX?UHc-&qWx`@sT=Omsw_WJ8{mLnkWbq>kj?kzU;yTupB^8rIVZX(ExLGEbV+JO zW({^~8DEhqJGEf8`)(D0*=`1M`WxvF-k4s!)qrV5LupLUZzCYmv;YCNZqkl%2kp&? z#`GJJ7NQzpdejH}WBL}vv*n!ROF3ibo0cA5C-RT!-$i;s#`M|9D9D(eHgnp!*{139 z&hk-qvusv%IkWJx4xgZUI@LVf3-GyLXL5&KDhi+5b`{cJR8RB|>3ejFt@E~T5*S?IEJTtxny6Om#ky-+Yr{TS_?%RrT}FhxSSZ{f7(Te zZy`pbd`$Z7{h8XF7;Nm|JqnziX{W0B3U0h5Idq^2E(!bRWU+dy0h>;%KG3TP6 zB}PO4mHYf1;?a)NMU2WBj<&+|vxyNto*3aH@xEa+XcWmkKWSRw)PC7TiUXe^?GB`3 zbV}OvBU^a}MSPvI)Y3zW&2DQ~LXW%5=sckv+M;jkkJK6*_Y`SLa;+;s=Ln5*HIWCg z+W+f4?DUbXSgnx`1@+ASuw*~>WJYN90N`B0Ihv8y8>I=(pq5C!gDYy}tln4RLJPBYQ zG4gjC9^9dx=pTtk3^rjP4H?xUknhr$jiUke^4I2HUcOe4x|MuLBtxFFPCSS>F#q=H zBgW?*q^kH{8mw6l;>|^a{Tkr^#u-X~pUFO2=5E-wD4#2R|IFuhem0F$=A5o!8# z36Q4zH9fU&DI6ntv3Ae=%{F|*1okC@{h}8|QF0dzP03vl=@D` z-97irot>FGckcPmIrF%1IY=Id>p>iY3x{5W3w%x|{Jc1R`wMV2a$TA>)_m{Uj&(Kp z>pR=4#-*e$I1QJSea`zkc9q?e<~>t-o84u=3CQ|y-Atfp3Qg1 z=Ed$7Y98c2TPK%1^4+UT7Lq!$M@+`ECsNz}=VkYYvz)&F_uNtHZaPi<8yk4+K>x`8 zA+J|L+c(sO^s6e^z6WC4_egB}7BG%eTX+ub;N%W(0qpG51Lj#7flE+~oi7T*o>6#= zo$>g=${0K2@d1FZodgoHTZ*xh zF}+7ElDNf#huC>W1sYXgCG2E=+gD1Y7X-Oe%Lm~`U?=6u$d3=;tMFvC>7}_GAD}H& zGd{4xiYm_YrC(-*+-HI~awTj9OWj*LGmZ*6lXp9_S(AXkE*(8E(mysfJoE(U>PNi~ z93FjQZ1~`zTsDvp?f8~ps0vHJ0-LWp;cgzZFjXqkg+B=wrt&_)&%lMLKS=m*lJGwz z{2y=uDf5-FF_*y=|ATO0@+NWScVW|(!QA$mY{9mUWXrh9^Ojqbrzpi-_T=w$^Sc_h zG;NVB==SG%`f5(Q^n2ekd!8PX-1#HgaEKqxE-C-RxzH6pDx)&w()-Jaa zXz^TP!SEq{|0`L?GcdUSv4g!sh5knebFE!_A873#A1@5=e{6hkEGT@1)A{5F4eQ*r zMvKZH>fpRC@D4WWAP&cEI%wbi@#{nc{@>@${Ewyg5s6`XOM~>JKGXCb)OlzReOq!h zI{h`p>(yaoWrBw~9pA}>!oU){7w(I)=~7B>NVq$drr%=_Jni0Zgie<#2*}UPrF@>K zsf^I+A+aV#D#4YBXNnG{of(nNN)yCgy68;Tx>Kd;MJdT)E$nd3UU8*ja*e7qxtns0 zdTCvsUJYQGWWLp%j$i6u)qU@@`ab=nf0(I$@#`YkVR=o`pSM14-Fmc5@&1zW4$CWw z`sdjUQhMjVJjeLbrHglNzccNZFHigB<;E(1_Ll$GyLUFGBStp*clq^f9w_5S^r4v# z%9s{a1}?<9uuWk`wC{ACL-%~x580P`wz|jjNk3BeMyAhN6cFmOGkOPhD=h9CqYG)i z>vTAhfZjABJ+7nod^7h~*q3IrKXt#B?@mc!zW-9byvO7l`jybbp&so~de!LBql!18 z{~B4D;GrJ9ro`#zH7OjOMfoU4tVcJid518|JnvUU#EPsj<4_PmhIs>98iWUlqLP!j)eEX z)ey$v>gOI!_;I-YbQ&&jIxo&Xk{9555p+7uH-3Q*QkqhsOv5^ZuZ-ViQldss^2#*4%G)nQ4qEQOc$rXJ= z=8x%|j?3vvg5L*w6pyKTN?}IW_o9x|v5LhFyYmfuG)mDqZS6q+OG2i?gnIm^RpQ5_{#OltTvNQ=mZ`Yq8{`&PcF3nL}s5kJI_ zN#RGI0-F>*6MnEa@s~=Z7X-OeD-XhK;m6rDQ>#rMKtCM4n30#AUUq>Xb4I1cC8$Ru z{`Wo;#F1A=GJ2PLrfq>I;d@W~9vw!=pEf}pd4D8-K9U`tpn_+_lXytNztaJ@I4w2v zT7u$%2!}DMkX0%ZSh5SQM)ELR81gv$_GAsYB0rBTAbBa_XT=$RI1ev@F&clc#cOVK zyduW5Z>V~`zz=;xOfd#uNY42}o;q81YAW%C)M*~zJv+ZH|3CK1g^TC(i|w+lG4IA9 z+T6Ec7PxQ2eD>}9KePFQe@n+1Y^65nldaai{nyw+U6V@|c1kcP}fGLb$AvbcF@QEl)}uPK|C;`TSurDuSnjc!^qN$eKX8=M@Ntz9tKN~ zK4@rDG%N9Tg&A31F(!OQ7pn2ioK)g%ic8;}gM2ARY*W0Z3r7@gWciwGJPf}Pm;g>? z!;sPO{_UAr z%gbSIFIlGA%Y7lGxA&33!lA*D-m&riLj(PVf#QW?PQUA?RYgFLb06@%a24zjTn*q! zxEj+jxD?WJN%+Ym{G}xPta!a}VkumWWf@#;SbDy5eNFS9Y-^7yeBSlSB=C8gPb&Yc zH2U*X`sPWed{gF^Ldz>mI^KL!ole6~X&$&AZEbTi>!``W&j?@o8?*xqPy_f0NeV;a8g+@8th3$Z%L`N}J#;dk!1BN_J{o%UUn z?`TB$$8Rl8y;Z+(wg$7W|6Fp%jyF@QlK8T=x+bAYiLs;8RaNq%1|9gZlKs9K z_BJ%^%Wt`<-%D|&*E0UuvPkCFT&WNk(6dmCD@{`V^tntI6AxSgFVIWtbU>^JBix91 zT;G#$3%^f+Jtl}-z7Oa;#Itebi+&IZxZ-*cYdjwn9u z!HDaz4=d~=aJ?9>3T3|MHQ*;Ar<0T=jtu7PjgCMo-KxWX)GHXx^}eqngGA8caOobn z@W|nncmY`#zYJG{ISyZx%!iVlavE8n^lHN2fGhlRB2S59r(A>U1#kIyt;i^LE|%B^RL!gIsDqCt6{$7)-$8ut{1-!`y#ksr*m}%zh3;h89udA_7ghLlRZT*fnQ)iM*sc3 zQ>(JXT-s|TySmg5`1RrFI{gwO%JMN2#F1Djskr4E<5gc7dn?APai!NDq$kml zy29XEN~d(88oXMm0`(~_cFj!o)=||9K7S+2*JR^i_-y(6E?Z`4ZTf)Oz^l8`ygc5l zk<2~PmcXmN(Xo5KMCn6bp+KB5zCWs^FjudM9fU;iZ45_?UN{y}ZpHPlJ zo1E?=wL(P*=NN25Rzsnj*j>)vl0Ee;E+p~EwH zxd->I-MIckHQ8I$j|;tnRiTYl{9S-HJqsh+_x!@DY?IH~@(#`?+lu-(GR%mvig{-b zD^lzm+@vsc)H)qdIjq{JYoWd_hgImX(6$;VgH?Ts7ur^}VAZJpYh-1DhqhHMSQW1E zv-B)|<6-!Xz$&S|fbwp==uB7zW@q#+7vJf87l_w2qf+w~(49v7Z>0(1$g~&kk+uX@ zb%+~rJ@yUKcQNAnLneqL_eb(@Bs;9~uW7}>tn6*h&?*bFsc=IhhYuHqDtiZ$xzQ@* IT;tV$072>v6aWAK literal 0 HcmV?d00001 diff --git a/src/system_K1921VK035.c b/src/system_K1921VK035.c new file mode 100644 index 0000000..9175bc2 --- /dev/null +++ b/src/system_K1921VK035.c @@ -0,0 +1,185 @@ +/*============================================================================== + * Инициализация К1921ВК035 + *------------------------------------------------------------------------------ + * НИИЭТ, Богдан Колбов + *============================================================================== + * ДАННОЕ ПРОГРАММНОЕ ОБЕСПЕЧЕНИЕ ПРЕДОСТАВЛЯЕТСЯ «КАК ЕСТЬ», БЕЗ КАКИХ-ЛИБО + * ГАРАНТИЙ, ЯВНО ВЫРАЖЕННЫХ ИЛИ ПОДРАЗУМЕВАЕМЫХ, ВКЛЮЧАЯ ГАРАНТИИ ТОВАРНОЙ + * ПРИГОДНОСТИ, СООТВЕТСТВИЯ ПО ЕГО КОНКРЕТНОМУ НАЗНАЧЕНИЮ И ОТСУТСТВИЯ + * НАРУШЕНИЙ, НО НЕ ОГРАНИЧИВАЯСЬ ИМИ. ДАННОЕ ПРОГРАММНОЕ ОБЕСПЕЧЕНИЕ + * ПРЕДНАЗНАЧЕНО ДЛЯ ОЗНАКОМИТЕЛЬНЫХ ЦЕЛЕЙ И НАПРАВЛЕНО ТОЛЬКО НА + * ПРЕДОСТАВЛЕНИЕ ДОПОЛНИТЕЛЬНОЙ ИНФОРМАЦИИ О ПРОДУКТЕ, С ЦЕЛЬЮ СОХРАНИТЬ ВРЕМЯ + * ПОТРЕБИТЕЛЮ. НИ В КАКОМ СЛУЧАЕ АВТОРЫ ИЛИ ПРАВООБЛАДАТЕЛИ НЕ НЕСУТ + * ОТВЕТСТВЕННОСТИ ПО КАКИМ-ЛИБО ИСКАМ, ЗА ПРЯМОЙ ИЛИ КОСВЕННЫЙ УЩЕРБ, ИЛИ + * ПО ИНЫМ ТРЕБОВАНИЯМ, ВОЗНИКШИМ ИЗ-ЗА ИСПОЛЬЗОВАНИЯ ПРОГРАММНОГО ОБЕСПЕЧЕНИЯ + * ИЛИ ИНЫХ ДЕЙСТВИЙ С ПРОГРАММНЫМ ОБЕСПЕЧЕНИЕМ. + * + * 2018 АО "НИИЭТ" + *============================================================================== + */ + +//-- Includes ------------------------------------------------------------------ +#include "system_K1921VK035.h" +#include "K1921VK035.h" + +//-- Variables ----------------------------------------------------------------- +uint32_t SystemCoreClock; // System Clock Frequency (Core Clock) + +//-- Functions ----------------------------------------------------------------- +void SystemCoreClockUpdate(void) +{ + uint32_t current_sysclk; + uint32_t pll_n, pll_m, pll_od, pll_refclk, pll_div = 1; + + current_sysclk = RCU->SYSCLKSTAT_bit.SYSSTAT; + + switch (current_sysclk) { + case RCU_SYSCLKSTAT_SYSSTAT_OSICLK: + SystemCoreClock = OSICLK_VAL; + break; + case RCU_SYSCLKSTAT_SYSSTAT_OSECLK: + SystemCoreClock = OSECLK_VAL; + break; + case RCU_SYSCLKSTAT_SYSSTAT_PLLDIVCLK: + case RCU_SYSCLKSTAT_SYSSTAT_PLLCLK: + if (current_sysclk == RCU_SYSCLKSTAT_SYSSTAT_PLLDIVCLK) + pll_div = RCU->PLLDIV_bit.DIV + 1; + pll_n = RCU->PLLCFG_bit.N; + pll_m = RCU->PLLCFG_bit.M; + pll_od = RCU->PLLCFG_bit.OD; + if (RCU->PLLCFG_bit.REFSRC == RCU_PLLCFG_REFSRC_OSICLK) + pll_refclk = OSICLK_VAL; + else // RCU->PLLCFG_bit.REFSRC == RCU_PLLCFG_REFSRC_OSECLK + pll_refclk = OSECLK_VAL; + SystemCoreClock = (pll_refclk * pll_m) / (pll_n * (1 << pll_od) * pll_div); + break; + } +} + +void ClkInit() +{ + uint32_t timeout_counter = 0; + uint32_t sysclk_source; + +//clockout control +#if defined CKO_OSI + SIU->CLKOUTCTL = SIU_CLKOUTCTL_CLKOUTEN_Msk; + RCU->CLKOUTCFG = (RCU_CLKOUTCFG_CLKSEL_OSICLK << RCU_CLKOUTCFG_CLKSEL_Pos) | + (RCU_CLKOUTCFG_CLKEN_Msk); //CKO = OSICLK +#elif defined CKO_OSE && (OSECLK_VAL != 0) + SIU->CLKOUTCTL = SIU_CLKOUTCTL_CLKOUTEN_Msk; + RCU->CLKOUTCFG = (RCU_CLKOUTCFG_CLKSEL_OSECLK << RCU_CLKOUTCFG_CLKSEL_Pos) | + (RCU_CLKOUTCFG_CLKEN_Msk); //CKO = OSECLK +#elif defined CKO_PLL + SIU->CLKOUTCTL = SIU_CLKOUTCTL_CLKOUTEN_Msk; + RCU->CLKOUTCFG = (RCU_CLKOUTCFG_CLKSEL_PLLCLK << RCU_CLKOUTCFG_CLKSEL_Pos) | + (1 << RCU_CLKOUTCFG_DIVN_Pos) | + (RCU_CLKOUTCFG_DIVEN_Msk) | + (RCU_CLKOUTCFG_CLKEN_Msk); //CKO = PLLCLK/4 +#endif + +//wait till external oscillator is ready +#if defined OSECLK_VAL && (OSECLK_VAL != 0) + while ((!RCU->SYSCLKSTAT_bit.OSECLKGOOD) && (timeout_counter < OSECLK_STARTUP_TIMEOUT)) + timeout_counter++; + if (timeout_counter == OSECLK_STARTUP_TIMEOUT) //OSE failed to startup + while (1) { + }; +#endif + +//select system clock +#ifdef SYSCLK_PLL +//PLLCLK = REFSRC * (M/N) * (1/(2^OD)) + #if (OSECLK_VAL == 8000000) + RCU->PLLCFG = (RCU_PLLCFG_REFSRC_OSECLK << RCU_PLLCFG_REFSRC_Pos) | + (1 << RCU_PLLCFG_N_Pos) | + (25 << RCU_PLLCFG_M_Pos); + #elif (OSECLK_VAL == 12000000) + RCU->PLLCFG = (RCU_PLLCFG_REFSRC_OSECLK << RCU_PLLCFG_REFSRC_Pos) | + (3 << RCU_PLLCFG_N_Pos) | + (50 << RCU_PLLCFG_M_Pos); + #elif (OSECLK_VAL == 16000000) + RCU->PLLCFG = (RCU_PLLCFG_REFSRC_OSECLK << RCU_PLLCFG_REFSRC_Pos) | + (2 << RCU_PLLCFG_N_Pos) | + (25 << RCU_PLLCFG_M_Pos); + #elif (OSECLK_VAL == 20000000) + RCU->PLLCFG = (RCU_PLLCFG_REFSRC_OSECLK << RCU_PLLCFG_REFSRC_Pos) | + (2 << RCU_PLLCFG_N_Pos) | + (20 << RCU_PLLCFG_M_Pos); + #elif (OSECLK_VAL == 24000000) + RCU->PLLCFG = (RCU_PLLCFG_REFSRC_OSECLK << RCU_PLLCFG_REFSRC_Pos) | + (3 << RCU_PLLCFG_N_Pos) | + (25 << RCU_PLLCFG_M_Pos); + #elif defined OSICLK_VAL + RCU->PLLCFG = (RCU_PLLCFG_REFSRC_OSICLK << RCU_PLLCFG_REFSRC_Pos) | + (2 << RCU_PLLCFG_N_Pos) | + (50 << RCU_PLLCFG_M_Pos); + #else + #error "Please define OSICLK_VAL and OSECLK_VAL with correct values!" + #endif + RCU->PLLCFG |= (1 << RCU_PLLCFG_OD_Pos) | + (RCU_PLLCFG_OUTEN_Msk); + while (!RCU->PLLCFG_bit.LOCK) { + }; + // additional waitstates + MFLASH->CTRL = (3 << MFLASH_CTRL_LAT_Pos); + //select PLL as source system clock + sysclk_source = RCU_SYSCLKCFG_SYSSEL_PLLCLK; +#elif defined SYSCLK_OSI + sysclk_source = RCU_SYSCLKCFG_SYSSEL_OSICLK; +#elif defined SYSCLK_OSE + sysclk_source = RCU_SYSCLKCFG_SYSSEL_OSECLK; +#else +#error "Please define SYSCLK source (SYSCLK_PLL | SYSCLK_OSI | SYSCLK_OSE)!" +#endif + + //switch sysclk + RCU->SYSCLKCFG = (sysclk_source << RCU_SYSCLKCFG_SYSSEL_Pos); + // Wait switching done + timeout_counter = 0; + while ((RCU->SYSCLKSTAT_bit.SYSSTAT != RCU->SYSCLKCFG_bit.SYSSEL) && (timeout_counter < SYSCLK_SWITCH_TIMEOUT)) + timeout_counter++; + if (timeout_counter == SYSCLK_SWITCH_TIMEOUT) //SYSCLK failed to switch + while (1) { + }; + + //flush and enable cache + MFLASH->CTRL_bit.IFLUSH = 1; + while (MFLASH->ICSTAT_bit.BUSY) { + }; + MFLASH->CTRL_bit.DFLUSH = 1; + while (MFLASH->DCSTAT_bit.BUSY) { + }; + MFLASH->CTRL |= (MFLASH_CTRL_DCEN_Msk) | (MFLASH_CTRL_ICEN_Msk) | (MFLASH_CTRL_PEN_Msk); +} + +void FPUInit() +{ + SCB->CPACR = 0x00F00000; + __DSB(); + __ISB(); +} + +// Разрешение тактирования всей периферии +void PeripheralClockEnable(){ + // Разрешение клоков + RCU->HCLKCFG = 0b00000111; // CAN, GPIOA, GPIOB + RCU->PCLKCFG = 0b0000111111111111; // PWM, CAP, QEP, I2C таймеры + + RCU->UARTCFG[1].UARTCFG_bit.CLKEN = 1;//включили тактирование UART + RCU->UARTCFG[1].UARTCFG_bit.CLKSEL = 1;//PLL = 100МГц + RCU->UARTCFG[1].UARTCFG_bit.DIVEN = 1;//включить делитель + RCU->UARTCFG[1].UARTCFG_bit.DIVN = 1;//делим на 4 по формуле N = 2*(DIVN+1) + RCU->UARTCFG[1].UARTCFG_bit.RSTDIS = 1; //вывели из резета + + // Снятие ресета + RCU->HRSTCFG = 0b00000111; // CAN, GPIOA, GPIOB + RCU->PRSTCFG = 0b0000111111111111; // PWM, CAP, QEP, I2C таймеры +} + +void SystemInit(void) +{ + ClkInit(); + FPUInit(); + PeripheralClockEnable(); +} diff --git a/Лицензионное соглашение [CANOpen].txt b/Лицензионное соглашение [CANOpen].txt new file mode 100644 index 0000000..4a4048d --- /dev/null +++ b/Лицензионное соглашение [CANOpen].txt @@ -0,0 +1,42 @@ +ВНИМАНИЕ! +ЕСЛИ ВЫ ЗАГРУЖАЕТЕ ИЗ СЕТИ ИНТЕРНЕТ, КОПИРУЕТЕ ИЛИ КАКИМ-ЛИБО ДРУГИМ СПОСОБОМ ИСПОЛЬЗУЕТЕ ДАННОЕ ПРОГРАММНОЕ ОБЕСПЕЧЕНИЕ (ПРОДУКТ), ТО ВЫ ПОДТВЕРЖДАЕТЕ СВОЕ СОГЛАСИЕ С УСЛОВИЯМИ ПРЕДСТАВЛЕННОГО НИЖЕ ЛИЦЕНЗИОННОГО СОГЛАШЕНИЯ (ст.1286 ГК РФ). + +Настоящий документ «Лицензионное соглашение с конечным пользователем» (EULA) представляет собой предложение АО «НИИЭТ» и ООО «НПФ ВЕКТОР» (далее — «Правообладатели») заключить соглашение на изложенных ниже условиях. + +1. Термины и определения +Используемые в настоящем Лицензионном соглашении слова и выражения имеют следующие значения, если иное прямо не определено далее по тексту: +а) Лицензия (Соглашение) — текст настоящего документа, распространяемого совместно с Продуктом на любом электронном носителе информации, либо через интернет. +б) Пользователь — лицо, заключившее настоящее Соглашение с Правообладателем в своём или чужом интересе в соответствии с требованиями действующего законодательства и настоящего Соглашения. +в) Продукт — принадлежащий Правообладателям сборник подпрограмм в виде любой из библиотек: «libCANOpen_drv.a», «libCANOpen_drv_CAN1.a», «libCANOpen_drv_CAN2.a», «libCANOpen_drv.mcl», «libCANOpen_drv_CAN1.mcl», «libCANOpen_drv_CAN2.mcl», включая настоящее Соглашение, которые правомерно находятся у конечного Пользователя. + + +2. Лицензия на использование программного продукта +2.1. По настоящему Соглашению Правообладатели предоставляют Пользователю право использования Продукта на условиях простой (неисключительной) лицензии. +2.2. Для заключения настоящего Соглашения на изложенных в нём условиях достаточно совершения Пользователем любого из указанных ниже действий: +• установка (копирование) Продукта на ЭВМ, в том числе в составе других программных модулей и/или проектов программного обеспечения (ПО); +• компоновка (сборка исполнимого модуля) проекта ПО, в состав которого входит данный Продукт; +• загрузка в микроконтроллер исполнимого модуля, собранного с использованием данного Продукта. + +Выполнение указанных выше действий подтверждает ознакомление и полное безоговорочное принятие Пользователем условий, изложенных в настоящем Соглашении, и создает между Пользователем и Правообладателем договор на приведенных условиях в соответствии с положениями ст.437 и 438 ГК РФ. +2.3. Пользователь вправе использовать Продукт в соответствии с условиями настоящего Соглашения следующими способами (с учетом п.3 настоящего Соглашения): +• Пользователь вправе использовать Продукт любым способом, по своему усмотрению, в том числе для извлечения собственной выгоды путём распространения третьим лицам, при условии, что с Продуктом поставляется данное лицензионное Соглашение в неизменном виде и сам продукт передается третьим лицам на безвозмездной основе. +3. Ограничения использования программного продукта +3.1. Пользователь не имеет права самостоятельно или с привлечением третьих лиц дизассемблировать, декомпилировать, дешифровать, модифицировать, производить пошаговую отладку или иные аналогичные действия с Продуктом. +3.2. Пользователь обязан информировать Правообладателей о всех обнаруженных ошибках в работе Продукта с указанием условий их появления для возможности их устранения Правообладателями. +3.3. Пользователь не имеет права удалять или любым способом изменять товарные знаки и уведомления об авторских или любых иных правах, включенные в состав Продукта. +3.4. Пользователь не имеет права удалять из Продукта или любым способом изменять данное лицензионное Соглашение. + +4. Ответственность по Лицензии +4.1. Ввиду предоставления в рамках Лицензии права использования Продукта на безвозмездной основе к отношениям сторон по Лицензии не применимы положения законодательства о защите прав потребителей. +4.2. Правообладатели могут (но не обязаны) оказывать техническую поддержку Пользователю. +4.3. Правообладатели распространяют любые редакции Продукта в виде «как есть», без каких-либо гарантий его корректной работы, на условиях использования, обозначенных в п.2.3 настоящего Соглашения. +4.4. Правообладатели не несут никакой ответственности за вид и способы использования Продукта Пользователем. +4.5. Правообладатели не несут никакой ответственности за убыток или ущерб, включая, в том числе, косвенный или сопутствующий убыток и ущерб, и в целом любой убыток и ущерб, возникший в результате потери данных или упущенной выгоды, или возникший в результате или в связи с использованием данного Продукта. +4.6. Правообладатели вправе по собственному усмотрению, без предварительного уведомления Пользователя производить доработку Продукта, изменять функциональные возможности и/или состав Продукта, в том числе, выпускать обновленный Продукт под новой Лицензией. +4.7. Пользователь несет ответственность за любое нарушение обязательств, установленных настоящим Соглашением и (или) применимым правом, а также за все последствия таких нарушений (включая любые убытки, которые могут понести Правообладатели и иные третьи лица). +4.8. Правообладатели оставляют за собой право преследования нарушителей исключительных прав на Продукт в соответствии с гражданским, административным и уголовным законодательством Российской Федерации по своему усмотрению. + +5. Заключительные положения +5.1. Настоящее Соглашение, порядок его заключения и исполнения, а также вопросы, не урегулированные настоящим Соглашением, регулируются действующим законодательством Российской Федерации. +5.2. Все споры по Соглашению или в связи с ним, не урегулированные путем переговоров между Правообладателем и Пользователем, подлежат рассмотрению в суде по месту нахождения Правообладателя в соответствии с действующим процессуальным правом Российской Федерации. Реквизиты Правообладателей доступны на официальных сайтах: http://niiet.ru, http://motorcontrol.ru +